-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathmechanism.py
244 lines (199 loc) · 9.67 KB
/
mechanism.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
import wpilib
import wpilib.drive
import wpimath.controller
from wpimath.controller import PIDController
from wpimath.controller import ArmFeedforward
import rev
from wpilib import DoubleSolenoid
import rev
from beambreak import BeamBreak
import math
class Mechanism:
def __init__(self, config) -> None:
self.config = config
motor_type_brushless = rev.CANSparkLowLevel.MotorType.kBrushless
motor_type_brushed = rev.CANSparkLowLevel.MotorType.kBrushed
self.intakeMotor = rev.CANSparkMax(config["INTAKE_MOTOR_ID"], motor_type_brushless)
self.indexMotor = rev.CANSparkMax(config["INDEX_MOTOR_ID"], motor_type_brushless)
self.indexEncoder = self.indexMotor.getEncoder()
self.inARollBack = False
self.rollBackStartValue = 0
self.leftShootingMotor = rev.CANSparkMax(config["SHOOTER_LEFT_MOTOR_ID"], motor_type_brushless)
self.rightShootingMotor = rev.CANSparkMax(config["SHOOTER_RIGHT_MOTOR_ID"], motor_type_brushless)
self.leftShootingEncoder = self.leftShootingMotor.getEncoder()
self.rightShootingEncoder = self.rightShootingMotor.getEncoder()
self.leftShootingMotor.enableVoltageCompensation(12)
self.rightShootingMotor.enableVoltageCompensation(12)
self.leftShootingMotor.setOpenLoopRampRate(config["SHOOTER_OPEN_LOOP_RAMP_RATE"])
self.rightShootingMotor.setOpenLoopRampRate(config["SHOOTER_OPEN_LOOP_RAMP_RATE"])
self.leftShooterPID = PIDController(0.0002, 0, 0)
self.rightShooterPID = PIDController(0.0003, 0.0001, 0.0001) #0.0007, 0, 0.0005
# self.moveHoodMotor = rev.CANSparkMax(config["HOOD_MOTOR_ID"], motor_type_brushless)
self.sprocketLeftMotor = rev.CANSparkMax(config["SPROCKET_LEFT_MOTOR_ID"], motor_type_brushless)
self.sprocketRightMotor = rev.CANSparkMax(config["SPROCKET_RIGHT_MOTOR_ID"], motor_type_brushless)
self.sprocketLeftMotor.enableVoltageCompensation(12)
self.sprocketRightMotor.enableVoltageCompensation(12)
self.sprocketRightMotor.setInverted(False)
self.sprocketPID = PIDController(config["SPROCKET_PID_KP"], config["SPROCKET_PID_KI"], config["SPROCKET_PID_KD"])
self.sprocketFeedforward = ArmFeedforward(config["SPROCKET_FEEDFORWARD_KS"],config["SPROCKET_FEEDFORWARD_KG"],config["SPROCKET_FEEDFORWARD_KV"],config["SPROCKET_FEEDFORWARD_KA"])
self.sprocketAbsoluteEncoder = wpilib.DutyCycleEncoder(config["SPROCKET_ENCODER_ID"])
self.sprocketEncoderShift = config["SPROCKET_ENCODER_SHIFT"]
self.sprocketEncoderZero = config["SPROCKET_ENCODER_ZERO"]
self.indexingBeam = BeamBreak(config["INTAKE_BEAMBREAK_PIN"])
self.autonSprocketPosition = -38
self.shooting = False
self.climbMotor = rev.CANSparkMax(config["CLIMB_MOTOR_ID"], motor_type_brushless)
return
#action is intake or eject, L1 is intake, B is eject
def intakeNote(self):
self.intakeMotor.set(self.config["INTAKE_SPEED"])
return
def reverseIntake(self):
self.intakeMotor.set(-self.config["INTAKE_SPEED"])
return
def stopIntake(self):
self.intakeMotor.set(0)
def ejectNote(self):
self.intakeMotor.set(-1*self.config["INTAKE_SPEED"])
return
#do the sequence that shoots the note
#r1 shoots the note
def shootNote(self):
#self.leftShootingMotor.set(self.config["SHOOTER_LEFT_SPEED"])
self.setLeftShooterRPM(-4500)
self.setRightShooterRPM(5500)
#self.rightShootingMotor.set(self.config["SHOOTER_RIGHT_SPEED"])
return
def shootAmp(self):
#self.leftShootingMotor.set(self.config["SHOOTER_LEFT_SPEED"])
self.setLeftShooterRPM(-2000)
self.setRightShooterRPM(2000)
#self.rightShootingMotor.set(self.config["SHOOTER_RIGHT_SPEED"])
return
def lobNote(self, rpm):
self.setLeftShooterRPM(-rpm * 1.2)
self.setRightShooterRPM(rpm)
def shootReverse(self):
self.leftShootingMotor.set(self.config["SHOOTER_LEFT_REVERSE_SPEED"])
self.rightShootingMotor.set(self.config["SHOOTER_RIGHT_REVERSE_SPEED"])
return
#forces stop because motor doesn't always go to 0 by itself
def stopShooting(self):
self.leftShootingMotor.set(0)
self.rightShootingMotor.set(0)
return
def sprocketUp(self): #moves the shooter away from the intake
config = self.config
self.sprocketLeftMotor.set(config["SPROCKET_MOTOR_LEFT_UP"])
self.sprocketRightMotor.set(config["SPROCKET_MOTOR_RIGHT_UP"])
self.sprocketLimitStop()
return
def sprocketDown(self): #moves the shooter back to the intake
config = self.config
self.sprocketLeftMotor.set(config["SPROCKET_MOTOR_LEFT_DOWN"])
self.sprocketRightMotor.set(config["SPROCKET_MOTOR_RIGHT_DOWN"])
#self.sprocketLimitStop()
return
def sprocketFullSpeedDown(self):
self.sprocketLeftMotor.set(-1)
self.sprocketRightMotor.set(1)
def sprocketToPosition(self, targetPosition): #test and debug me!
config = self.config
self.sprocketPIDCalculation = self.sprocketPID.calculate(self.getSprocketAngle(), targetPosition)
self.sprocketFeedforwardCalculation = self.sprocketFeedforward.calculate(math.radians(self.getSprocketAngle()), config["SPROCKET_FEEDFORWARD_VELOCITY"], config["SPROCKET_FEEDFORWARD_ACCELERATION"])
if(targetPosition <= -30):
self.sprocketPIDCalculation /= 2
self.sprocketMotorSpeed = self.sprocketPIDCalculation + self.sprocketFeedforwardCalculation
self.sprocketRightMotor.set(-self.sprocketMotorSpeed)
self.sprocketLeftMotor.set(self.sprocketMotorSpeed)
#print(self.getSprocketAngle())
self.sprocketLimitStop()
#print('targetPosition', targetPosition)
return abs(targetPosition - self.getSprocketAngle()) < 1
def stopSprocket(self):
config = self.config
self.sprocketFeedforwardCalculation = self.sprocketFeedforward.calculate(math.radians(self.getSprocketAngle()), config["SPROCKET_FEEDFORWARD_VELOCITY"], config["SPROCKET_FEEDFORWARD_ACCELERATION"])
self.sprocketRightMotor.set(-self.sprocketFeedforwardCalculation)
self.sprocketLeftMotor.set(self.sprocketFeedforwardCalculation)
#print(self.sprocketFeedforwardCalculation)
def sprocketLimitStop(self):
if(self.getSprocketAngle() > 90):
self.stopSprocket()
def stopIndexing(self):
self.indexMotor.set(0)
return
def getSprocketAngle(self):
return (self.sprocketAbsoluteEncoder.getAbsolutePosition() * 360 + self.sprocketEncoderShift) % 360 - self.sprocketEncoderZero
def indexNote(self):
self.inARollBack = False
self.indexMotor.set(self.config["INDEX_SPEED"])
return
def fullIndex(self):
self.inARollBack = False
self.indexMotor.set(1)
return
def reverseIndex(self):
self.inARollBack = False
self.indexMotor.set(-1 * self.config["INDEX_SPEED"])
return
def indexFixedRollBack(self):
if not self.inARollBack:
self.inARollBack = True
self.rollBackStartValue = self.indexEncoder.getPosition()
def indexBeamBroken(self):
return self.indexingBeam.beamBroken()
def indexBeamHealthy(self):
return self.indexingBeam.isSelfCheckHealthy()
def periodic(self):
if self.inARollBack:
self.indexMotor.set(-self.config["INDEX_SPEED"])
if(self.indexEncoder.getPosition() < self.rollBackStartValue - self.config["INDEX_ROLL_BACK_ROTATIONS"]):
self.inARollBack = False
self.indexMotor.set(0)
def getShooterRPM(self):
return self.leftShootingEncoder.getVelocity(), self.rightShootingEncoder.getVelocity()
def setLeftShooterRPM(self, rpm):
self.leftShootingMotor.set(rpm / 5100 + self.leftShooterPID.calculate(self.leftShootingEncoder.getVelocity(), rpm))
def setRightShooterRPM(self, rpm):
self.rightShootingMotor.set(rpm / 5100 + self.rightShooterPID.calculate(self.rightShootingEncoder.getVelocity(), rpm))
#print(self.rightShooterPID.calculate(self.rightShootingEncoder.getVelocity(), rpm))
def setAutonSprocketPosition(self, position):
self.autonSprocketPosition = position
def setShootState(self, isShooting):
self.shooting = isShooting
def autonPeriodic(self):
self.sprocketToPosition(self.autonSprocketPosition)
if self.indexBeamBroken() and not self.shooting:
self.stopIndexing()
else:
self.indexNote()
def lockClimb(self):
self.climbMotor.set(-0.4)
def stopClimb(self):
self.climbMotor.set(0)
def reverseClimb(self):
self.climbMotor.set(0.4)
def getAutoAimAngle(self, distance, yaw):
v = 675
r = 1.15
h = 29
a = 18
d = 12
angleWing = 12.9
if distance < 176:
l = math.atan(
(78 - h + (193.04429 * r * ((distance + d) /(v * math.cos(math.radians(a))))**2)) / (distance + d)
)
u = math.atan(
(82.875 - h + (193.04429 * r * ((distance + d) /(v * math.cos(math.radians(a))))**2)) / (distance + d - (18))
)
angle = math.degrees(((u+l)/-2))+30
else:
angle = ((angleWing-9.9)/(231.5-176))*(distance-176)+9.9
return(angle)
def lobShotAngle(self, distance): #distance to amp
angle = -19+(0.008*distance)
return angle
def lobShotRPM(self, distance):
rpm = (1000/123)*(distance-316.5)+3000
return rpm