-
Notifications
You must be signed in to change notification settings - Fork 0
/
robot.py
444 lines (350 loc) · 14.9 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
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
#!/usr/bin/env python3
#
# Copyright (c) FIRST and other WPILib contributors.
# Open Source Software; you can modify and/or share it under the terms of
# the WPILib BSD license file in the root directory of this project.
#
# This is to help vscode
from typing import Callable
from commands2 import Command, CommandScheduler
import wpilib
import wpilib.event
from wpilib import SmartDashboard
import wpilib.shuffleboard
import rev
import wpimath
import wpimath.filter
import wpimath.geometry
import wpimath.kinematics
import wpimath.units
import wpimath.controller
import constants
from subsystems.drivetrain import Drivetrain
from subsystems.arm import Arm
from subsystems.shooter import Shooter
from subsystems.vision import Vision
from utils.coroutinecommand import RestartableCommand, commandify
import utils.math
from utils.gentools import doneable
from pathplannerlib.auto import PathPlannerAuto, AutoBuilder, PathPlannerPath, NamedCommands
from utils.swerveheading import SwerveHeadingState
field = wpilib.Field2d()
class MyRobot(wpilib.TimedRobot):
def robotInit(self) -> None:
"""Robot initialization function"""
# CameraServer.launch("camera.py")
# Command scheduler
self.scheduler = CommandScheduler.getInstance()
self.swerve = Drivetrain()
self.arm = Arm(30, 35)
self.shooter = Shooter(31, 32, 33)
self.scheduler.registerSubsystem(
self.swerve,
self.arm,
self.shooter,
)
# We call this registerNamedCommand wrapper to ensure statically that all
# our PathPlanner event commands are restartable.
def registerNamedCommand(name: str, cmd: Callable[[], Command]):
NamedCommands.registerCommand(name, RestartableCommand(cmd))
registerNamedCommand("setArmIntake", commandify(self.setArmIntake))
registerNamedCommand("setArmSpeaker", commandify(self.setArmSpeaker))
registerNamedCommand("setArmAmp", commandify(self.setArmAmp))
registerNamedCommand("intakeNote", commandify(self.intakeNote))
registerNamedCommand("shootNote", commandify(self.shootNote))
registerNamedCommand("stopIntake", commandify(self.stopIntake))
self.swerve.setupPathPlanner()
self.armButton = wpilib.DigitalInput(0)
self.leftStick = wpilib.Joystick(0)
self.rightStick = wpilib.Joystick(1)
self.gamePad = wpilib.XboxController(2)
# Slew rate limiters to make joystick inputs more gentle
self.xspeedLimiter = wpimath.filter.SlewRateLimiter(8)
self.yspeedLimiter = wpimath.filter.SlewRateLimiter(8)
self.rotLimiter = wpimath.filter.SlewRateLimiter(6)
self.swerve.updatePIDConfig()
self.swerve.gyro.reset()
self.armButtonPastState = False
self.wasDetected = False
self.vision = Vision()
self.autoPID = wpimath.controller.PIDController(1 / 2, 0, 0.05)
# In order to play nice with PathPlanner's autos, which are Command-only,
# we always store Commands in our auto chooser. However, since we want our
# autos to be restartable, we use these wrappers to ensure that all our auto
# options can be wrapped in RestartableCommand.
self.autoChooser = wpilib.SendableChooser()
def setDefaultAuto(name: str, cmd: Callable[[], Command]):
self.autoChooser.setDefaultOption(name, RestartableCommand(cmd))
def addAuto(name: str, cmd: Callable[[], Command]):
self.autoChooser.addOption(name, RestartableCommand(cmd))
setDefaultAuto("None", commandify(self.doNothingAuto))
addAuto("Two Nothing", commandify(self.twoNothing))
addAuto("One Note", commandify(self.oneNoteAuto))
addAuto("Amp-Amp", lambda: PathPlannerAuto("Amp-Amp"))
addAuto("Amp-Amp Center", lambda: PathPlannerAuto("Amp-Amp Center"))
addAuto("Amp-Amp Rollout", lambda: PathPlannerAuto("Amp-Amp Rollout"))
addAuto("Center-Center", lambda: PathPlannerAuto("Center-Center"))
addAuto("Center-Center Amp", lambda: PathPlannerAuto("Center-Center Amp"))
addAuto("Center-Center Amp Source", lambda: PathPlannerAuto("Center-Center Amp Source"))
addAuto("Center-Center Source", lambda: PathPlannerAuto("Center-Center Source"))
addAuto("Source-Source", lambda: PathPlannerAuto("Source-Source"))
SmartDashboard.putData("Auto selection", self.autoChooser)
def robotPeriodic(self) -> None:
# swervemodule.driveP = wpilib.SmartDashboard.getNumber(
# "driveP", swervemodule.driveP
# )
# swervemodule.driveI = wpilib.SmartDashboard.getNumber(
# "driveI", swervemodule.driveI
# )
# swervemodule.driveD = wpilib.SmartDashboard.getNumber(
# "driveD", swervemodule.driveD
# )
# swervemodule.driveFF = wpilib.SmartDashboard.getNumber(
# "driveFF", swervemodule.driveFF
# )
# swervemodule.driveOutputMin = wpilib.SmartDashboard.getNumber(
# "driveOutputMin", swervemodule.driveOutputMin
# )
# swervemodule.driveOutputMax = wpilib.SmartDashboard.getNumber(
# "driveOutputMax", swervemodule.driveOutputMax
# )
# swervemodule.steerP = wpilib.SmartDashboard.getNumber(
# "steerP", swervemodule.steerP
# )
# swervemodule.steerI = wpilib.SmartDashboard.getNumber(
# "steerI", swervemodule.steerI
# )
# swervemodule.steerD = wpilib.SmartDashboard.getNumber(
# "steerD", swervemodule.steerD
# )
# swervemodule.steerFF = wpilib.SmartDashboard.getNumber(
# "steerFF", swervemodule.steerFF
# )
# swervemodule.steerOutputMin = wpilib.SmartDashboard.getNumber(
# "steerOutputMin", swervemodule.steerOutputMin
# )
# swervemodule.steerOutputMax = wpilib.SmartDashboard.getNumber(
# "steerOutputMax", swervemodule.steerOutputMax
# )
field.getObject("origin").setPose(wpimath.geometry.Pose2d())
poses = self.vision.update()
self.swerve.updateVision(poses)
self.swerve.updateOdometry()
field.setRobotPose(self.swerve.getPose())
self.arm.periodic2175()
self.scheduler.run()
self.arm.updateTelemetry()
self.swerve.updateTelemetry()
self.shooter.updateTelemetry()
SmartDashboard.putData(field)
# TODO: This should almost certainly move to teleopPeriodic.
if self.leftStick.getRawButtonPressed(8):
self.swerve.gyro.reset()
self.swerve.headingController.setGoal(self.swerve.gyro.getRotation2d())
def autonomousInit(self) -> None:
self.scheduler.cancelAll()
self.swerve.gyro.reset()
self.swerve.headingController.setState(SwerveHeadingState.DISABLE)
autoCommand = self.autoChooser.getSelected()
self.scheduler.schedule(autoCommand)
def autonomousPeriodic(self) -> None:
# No code necessary. The CommandScheduler will continue to run the command
# scheduled by autonomousInit.
return
def teleopInit(self) -> None:
self.swerve.headingController.setState(SwerveHeadingState.OFF)
self.scheduler.cancelAll()
self.intakeLocked = False
def teleopPeriodic(self) -> None:
if self.leftStick.getRawButton(2) or self.leftStick.getRawButton(3) or self.rightStick.getRawButton(2) or self.rightStick.getRawButton(3):
self.driveWithJoystick(False)
else:
self.driveWithJoystick(True)
if self.gamePad.getYButton():
self.arm.setArmPreset("high")
shooterPower = constants.kShooterPresets["high"]
elif self.gamePad.getXButton():
self.arm.setArmPreset("mid")
shooterPower = constants.kShooterPresets["mid"]
elif self.gamePad.getAButton():
self.arm.setArmPreset("low")
shooterPower = constants.kShooterPresets["low"]
else:
self.arm.setArmPreset("intake")
shooterPower = constants.kShooterPresets["intake"]
intakeSpeed = wpimath.applyDeadband(-self.gamePad.getLeftY(), 0.1)
if self.shooter.noteDetected():
self.wasDetected = True
if intakeSpeed < 0:
intakeSpeed = 0
else:
if self.wasDetected and intakeSpeed < 0:
intakeSpeed = 0
else:
self.wasDetected = False
if self.gamePad.getLeftBumper() or self.gamePad.getRightBumper():
self.shooter.setShooterSpeed(shooterPower)
if self.shooter.isShooterAtTarget(shooterPower):
intakeSpeed = -1
elif self.gamePad.getAButton() or self.gamePad.getYButton() or self.gamePad.getXButton():
self.shooter.setShooterSpeed(shooterPower)
else:
self.shooter.setShooterSpeed(0)
self.shooter.setIntakeSpeed(intakeSpeed)
def driveWithJoystick(self, fieldRelative: bool) -> None:
xSpeed = (
self.xspeedLimiter.calculate(
utils.math.signedPower(
wpimath.applyDeadband(-self.leftStick.getY(), 0.1)
)
)
* constants.kMaxSpeed
)
# we invert the Y axis of the joysticks
ySpeed = (
self.yspeedLimiter.calculate(
utils.math.signedPower(
wpimath.applyDeadband(-self.leftStick.getX(), 0.1)
)
)
* constants.kMaxSpeed
)
rot = (
self.rotLimiter.calculate(
utils.math.signedPower(
wpimath.applyDeadband(-self.rightStick.getX(), 0.1)
)
)
* constants.kMaxAngularSpeed
)
# if(self.leftStick.getRawButton(2)):
# ampHeight = wpimath.units.meters(5.49275)
# error = float(ampHeight) - float(self.swerve.getPose().y)
# ySpeed = error * 0.2
# rot = 90
if(self.leftStick.getRawButton(1) or self.rightStick.getRawButton(1)):
xSpeed /= 2
ySpeed /= 2
rot /= 2
wpilib.SmartDashboard.putNumber("X Speed", xSpeed)
wpilib.SmartDashboard.putNumber("Y Speed", ySpeed)
wpilib.SmartDashboard.putNumber("Rotation Speed", rot)
self.swerve.drive(xSpeed, ySpeed, rot, fieldRelative, self.getPeriod())
def disabledInit(self) -> None:
self.scheduler.cancelAll()
self.arm.setIdleMode(rev.CANSparkBase.IdleMode.kBrake)
def disabledPeriodic(self) -> None:
SmartDashboard.putBoolean("arm/button", self.armButton.get())
SmartDashboard.putBoolean("arm/buttonOld", self.armButtonPastState)
if self.armButton.get() != self.armButtonPastState:
self.arm.setIdleMode(rev.CANSparkMax.IdleMode.kBrake if self.armButton.get() else rev.CANSparkMax.IdleMode.kCoast)
self.armButtonPastState = self.armButton.get()
def disabledExit(self) -> None:
self.arm.setIdleMode(rev.CANSparkMax.IdleMode.kCoast)
def testPeriodic(self) -> None:
self.shooter.lowerMotor.set(1)
self.shooter.upperMotor.set(1)
# --------------------------------------------------------------------
# --------------------------------------------------------------------
# --------------------------------------------------------------------
# @doneable
# def driveToPoint(self, point: wpimath.geometry.Pose2d):
# while True:
# yield
# direction = point.translation() - self.swerve.getPose().translation()
# error = direction.norm()
# if error < 0.1:
# self.swerve.drive(0, 0, 0, True, self.getPeriod())
# return
# pidOut = self.autoPID.calculate(-error) # Negated because normally you don't use error as your process variable
# clampMag = 0.25
# if pidOut > clampMag:
# pidOut = clampMag
# elif pidOut < 0:
# pidOut = 0
# normalized = (direction / direction.norm())
# outputX = normalized.X() * pidOut * constants.kMaxSpeed
# outputY = normalized.Y() * pidOut * constants.kMaxSpeed
# # print(direction, error, pidOut, (outputX, outputY))
# #TODO this should be field relative
# self.swerve.drive(outputX, outputY, 0, False, self.getPeriod(), point.rotation())
# # print(self.swerve.getPose().translation())
@doneable
def setArmSpeaker(self):
print("going to speaker preset")
self.arm.setArmPreset("low")
self.shooter.setShooterPreset("low")
yield
@doneable
def setArmAmp(self):
print("going to amp preset")
self.arm.setArmPreset("high")
self.shooter.setShooterPreset("high")
yield
@doneable
def setArmIntake(self):
print("going to intake preset")
self.arm.setArmPreset("intake")
self.shooter.setShooterSpeed(0)
yield
@doneable
def doNothingAuto(self):
print("Doing nothing...")
yield from sleep(2)
print("Still doing nothing...")
yield from sleep(2)
print("Done doing nothing :)")
@doneable
def twoNothing(self):
nothingOne = self.doNothingAuto()
nothingTwo = self.doNothingAuto()
while not (nothingOne.done or nothingTwo.done):
nothingOne.resume()
nothingTwo.resume()
yield
@doneable
def oneNoteAuto(self):
yield from self.shootNote()
@doneable
def intakeNote(self):
print("intaking note")
self.arm.setArmPreset("intake")
self.shooter.setIntakeSpeed(-0.5)
while not self.shooter.noteDetected():
yield
self.shooter.setIntakeSpeed(0)
print("done intaking note")
@doneable
def stopIntake(self):
self.shooter.setIntakeSpeed(0)
yield
@doneable
def shootNote(self):
print("Shooting note")
self.shooter.setIntakeSpeed(0)
self.arm.setArmPreset("low")
self.shooter.setShooterPreset("low")
t = AutoTimer(3)
while not (self.shooter.atTarget() and self.arm.atTarget()) and not t.expired():
yield
self.shooter.setIntakeSpeed(-0.8)
yield from sleep(1/3)
self.shooter.setIntakeSpeed(0)
self.shooter.setShooterSpeed(0)
self.arm.setArmPreset("intake")
@doneable
def sleep(duration: float):
t = wpilib.Timer()
t.start()
while not t.hasElapsed(duration):
yield
class AutoTimer:
def __init__(self, duration: float):
self.duration = duration
self.t = wpilib.Timer()
self.t.start()
def expired(self):
if self.t.hasElapsed(self.duration):
return True
else:
return False