-
Notifications
You must be signed in to change notification settings - Fork 0
/
robot.py
187 lines (145 loc) · 6.42 KB
/
robot.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
import sys
import wpilib
from dashboard import Dashboard
from drivetrain.controlStrategies.autoDrive import AutoDrive
from drivetrain.controlStrategies.trajectory import Trajectory
from drivetrain.drivetrainCommand import DrivetrainCommand
from drivetrain.drivetrainControl import DrivetrainControl
from humanInterface.driverInterface import DriverInterface
from humanInterface.ledControl import LEDControl
from navigation.forceGenerators import PointObstacle
from utils.segmentTimeTracker import SegmentTimeTracker
from utils.signalLogging import logUpdate
from utils.calibration import CalibrationWrangler
from utils.faults import FaultWrangler
from utils.crashLogger import CrashLogger
from utils.rioMonitor import RIOMonitor
from utils.singleton import destroyAllSingletonInstances
from utils.powerMonitor import PowerMonitor
from webserver.webserver import Webserver
from AutoSequencerV2.autoSequencer import AutoSequencer
from utils.powerMonitor import PowerMonitor
from wpimath.geometry import Translation2d, Pose2d, Rotation2d
class MyRobot(wpilib.TimedRobot):
#########################################################
## Common init/update for all modes
def robotInit(self):
# Since we're defining a bunch of new things here, tell pylint
# to ignore these instantiations in a method.
# pylint: disable=attribute-defined-outside-init
remoteRIODebugSupport()
self.crashLogger = CrashLogger()
wpilib.LiveWindow.disableAllTelemetry()
self.webserver = Webserver()
self.driveTrain = DrivetrainControl()
self.autodrive = AutoDrive()
self.stt = SegmentTimeTracker()
self.dInt = DriverInterface()
self.ledCtrl = LEDControl()
self.autoSequencer = AutoSequencer()
self.dashboard = Dashboard()
self.rioMonitor = RIOMonitor()
self.pwrMon = PowerMonitor()
# Normal robot code updates every 20ms, but not everything needs to be that fast.
# Register slower-update periodic functions
self.addPeriodic(self.pwrMon.update, 0.2, 0.0)
self.addPeriodic(self.crashLogger.update, 1.0, 0.0)
self.addPeriodic(CalibrationWrangler().update, 0.5, 0.0)
self.addPeriodic(FaultWrangler().update, 0.2, 0.0)
self.autoHasRun = False
def robotPeriodic(self):
self.stt.start()
self.dInt.update()
self.stt.mark("Driver Interface")
self.driveTrain.update()
self.stt.mark("Drivetrain")
self.autodrive.updateTelemetry()
self.driveTrain.poseEst._telemetry.setCurAutoDriveWaypoints(self.autodrive.getWaypoints())
self.driveTrain.poseEst._telemetry.setCurObstacles(self.autodrive.rfp.getObstacleStrengths())
self.stt.mark("Telemetry")
self.ledCtrl.setAutoDrive(self.autodrive.isRunning())
self.ledCtrl.setStuck(self.autodrive.rfp.isStuck())
self.ledCtrl.update()
self.stt.mark("LED Ctrl")
logUpdate()
self.stt.end()
#########################################################
## Autonomous-Specific init and update
def autonomousInit(self):
# Start up the autonomous sequencer
self.autoSequencer.initialize()
# Use the autonomous rouines starting pose to init the pose estimator
self.driveTrain.poseEst.setKnownPose(self.autoSequencer.getStartingPose())
# Mark we at least started autonomous
self.autoHasRun = True
def autonomousPeriodic(self):
self.autoSequencer.update()
# Operators cannot control in autonomous
self.driveTrain.setManualCmd(DrivetrainCommand())
def autonomousExit(self):
self.autoSequencer.end()
#########################################################
## Teleop-Specific init and update
def teleopInit(self):
# clear existing telemetry trajectory
self.driveTrain.poseEst._telemetry.setCurAutoTrajectory(None)
# If we're starting teleop but haven't run auto, set a nominal default pose
# This is needed because initial pose is usually set by the autonomous routine
if not self.autoHasRun:
self.driveTrain.poseEst.setKnownPose(
Pose2d(1.0, 1.0, Rotation2d(0.0))
)
def teleopPeriodic(self):
# TODO - this is technically one loop delayed, which could induce lag
# Probably not noticeable, but should be corrected.
self.driveTrain.setManualCmd(self.dInt.getCmd())
if self.dInt.getGyroResetCmd():
self.driveTrain.resetGyro()
if self.dInt.getCreateObstacle():
# For test purposes, inject a series of obstacles around the current pose
ct = self.driveTrain.poseEst.getCurEstPose().translation()
tfs = [
#Translation2d(1.7, -0.5),
#Translation2d(0.75, -0.75),
#Translation2d(1.7, 0.5),
Translation2d(0.75, 0.75),
Translation2d(2.0, 0.0),
Translation2d(0.0, 1.0),
Translation2d(0.0, -1.0),
]
for tf in tfs:
obs = PointObstacle(location=(ct+tf), strength=0.5)
self.autodrive.rfp.addObstacleObservation(obs)
self.autodrive.setRequest(self.dInt.getNavToSpeaker(), self.dInt.getNavToPickup())
# No trajectory in Teleop
Trajectory().setCmd(None)
#########################################################
## Disabled-Specific init and update
def disabledPeriodic(self):
self.autoSequencer.updateMode()
Trajectory().trajHDC.updateCals()
def disabledInit(self):
self.autoSequencer.updateMode(True)
#########################################################
## Test-Specific init and update
def testInit(self):
wpilib.LiveWindow.setEnabled(False)
def testPeriodic(self):
pass
#########################################################
## Cleanup
def endCompetition(self):
self.rioMonitor.stopThreads()
destroyAllSingletonInstances()
super().endCompetition()
def remoteRIODebugSupport():
# TODO - is this still needed in 2025+?
if __debug__ and "run" in sys.argv:
print("Starting Remote Debug Support....")
try:
import debugpy # pylint: disable=import-outside-toplevel
except ModuleNotFoundError:
pass
else:
debugpy.listen(("0.0.0.0", 5678))
debugpy.wait_for_client()