generated from DeepBlueRobotics/EmptyProject2024
-
Notifications
You must be signed in to change notification settings - Fork 1
/
Arm.java
267 lines (216 loc) · 10.7 KB
/
Arm.java
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
package org.carlmontrobotics.subsystems;
import static org.carlmontrobotics.Constants.Arm.*;
import org.carlmontrobotics.commands.ArmTeleop;
import org.carlmontrobotics.lib199.MotorConfig;
import org.carlmontrobotics.lib199.MotorControllerFactory;
import org.opencv.core.Mat;
import com.revrobotics.AbsoluteEncoder;
import com.revrobotics.CANSparkBase;
import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkMax;
import com.revrobotics.RelativeEncoder;
import com.revrobotics.SparkAbsoluteEncoder;
import com.revrobotics.SparkPIDController;
import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.controller.ArmFeedforward;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.units.Angle;
import edu.wpi.first.units.Measure;
import edu.wpi.first.units.MutableMeasure;
import edu.wpi.first.units.Voltage;
import edu.wpi.first.util.sendable.SendableBuilder;
import edu.wpi.first.wpilibj.DriverStation;
import static edu.wpi.first.units.Units.DegreesPerSecond;
import static edu.wpi.first.units.Units.Rotations;
import static edu.wpi.first.units.Units.RotationsPerSecond;
import static edu.wpi.first.units.Units.RadiansPerSecond;
import static edu.wpi.first.units.Units.Radians;
import static edu.wpi.first.units.Units.Seconds;
import static edu.wpi.first.units.Units.Volts;
import edu.wpi.first.units.Velocity;
import static edu.wpi.first.units.MutableMeasure.mutable;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj.sysid.SysIdRoutineLog;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
// Arm angle is measured from horizontal on the intake side of the robot and bounded between -3π/2 and π/2
// Wrist angle is measured relative to the arm with 0 being parallel to the arm and bounded between -π and π (Center of Mass of Roller)
public class Arm extends SubsystemBase {
private final CANSparkMax armMotorMaster/* left */ = MotorControllerFactory.createSparkMax(ARM_MOTOR_PORT_MASTER,
MotorConfig.NEO);
private final CANSparkMax armMotorFollower/* right */ = MotorControllerFactory
.createSparkMax(ARM_MOTOR_PORT_FOLLOWER, MotorConfig.NEO);
private final SparkAbsoluteEncoder armMasterEncoder = armMotorMaster
.getAbsoluteEncoder(SparkAbsoluteEncoder.Type.kDutyCycle);
private final MutableMeasure<Voltage> voltage = mutable(Volts.of(0));
private final MutableMeasure<Velocity<Angle>> velocity = mutable(RadiansPerSecond.of(0));
private final MutableMeasure<Angle> distance = mutable(Radians.of(0));
private static double kDt = 0.02;
// PID, feedforward, trap profile
// rel offset = starting absolute offset
private final ArmFeedforward armFeed = new ArmFeedforward(kS, kG, kV, kA);
private final SparkPIDController armPIDMaster = armMotorMaster.getPIDController();
private static TrapezoidProfile.State setpoint;
private TrapezoidProfile armProfile = new TrapezoidProfile(TRAP_CONSTRAINTS);
TrapezoidProfile.State goalState = new TrapezoidProfile.State(0, 0);// TODO: update pos later
// rad, rad/s
// public static TrapezoidProfile.State[] goalState = { new
// TrapezoidProfile.State(-Math.PI / 2, 0), new TrapezoidProfile.State(0, 0) };
private ShuffleboardTab sysIdTab = Shuffleboard.getTab("arm SysID");
public Arm() {
// weird math stuff
armMotorMaster.setInverted(MOTOR_INVERTED_MASTER);
armMotorMaster.setIdleMode(IdleMode.kBrake);
armMotorFollower.setInverted(MOTOR_INVERTED_FOLLOWER);
armMotorFollower.setIdleMode(IdleMode.kBrake);
// Comment out when running sysid
armMasterEncoder.setPositionConversionFactor(ROTATION_TO_RAD);
armMasterEncoder.setVelocityConversionFactor(ROTATION_TO_RAD);
armMasterEncoder.setZeroOffset(ENCODER_OFFSET_RAD);
// ------------------------------------------------------------
armMasterEncoder.setInverted(ENCODER_INVERTED);
armMotorFollower.follow(armMotorMaster, MOTOR_INVERTED_FOLLOWER);
armPIDMaster.setP(kP);
armPIDMaster.setI(kI);
armPIDMaster.setD(kD);
// armPID.setTolerance(posToleranceRad, velToleranceRadPSec);
armPIDMaster.setFeedbackDevice(armMasterEncoder);
armPIDMaster.setPositionPIDWrappingEnabled(true);
armPIDMaster.setPositionPIDWrappingMinInput(LOWER_ANGLE_LIMIT_RAD);
armPIDMaster.setPositionPIDWrappingMaxInput(UPPER_ANGLE_LIMIT_RAD);
armPIDMaster.setIZone(IZONE_RAD);
TRAP_CONSTRAINTS = new TrapezoidProfile.Constraints(
armFeed.maxAchievableVelocity(12, Math.PI/2, 0),
MAX_FF_ACCEL_RAD_P_S);
//^ worst case scenario
SmartDashboard.putData("Arm", this);
setpoint = getCurrentArmState();
goalState = getCurrentArmState();
setArmTarget(goalState.position);
//sysid buttons on smartdashbaord; sysid tab name is arm sysid
sysIdTab.add("quasistatic forward", sysIdQuasistatic(SysIdRoutine.Direction.kForward));
sysIdTab.add("quasistatic backward", sysIdQuasistatic(SysIdRoutine.Direction.kReverse));
sysIdTab.add("dynamic forward", sysIdDynamic(SysIdRoutine.Direction.kForward));
sysIdTab.add("dynamic backward", sysIdDynamic(SysIdRoutine.Direction.kReverse));
}
@Override
public void periodic() {
if (DriverStation.isDisabled())
resetGoal();
// ARM_TELEOP_MAX_GOAL_DIFF_FROM_CURRENT_RAD =
// SmartDashboard.getNumber("ARM_TELEOP_MAX_GOAL_DIFF_FROM_CURRENT_RAD",
// ARM_TELEOP_MAX_GOAL_DIFF_FROM_CURRENT_RAD);
// armConstraints = new TrapezoidProfile.Constraints(MAX_FF_VEL , MAX_FF_ACCEL
// );
// smart dahsboard stuff
// SmartDashboard.putBoolean("ArmPIDAtSetpoint", armPID1.atSetpoint());
// SmartDashboard.putBoolean("ArmProfileFinished",
// armProfile.isFinished(armProfileTimer.get()));
// posToleranceRad = SmartDashboard.getNumber("Arm Tolerance Pos",
// posToleranceRad);
// velToleranceRadPSec= SmartDashboard.getNumber("Arm Tolerance Vel",
// velToleranceRadPSec);
// SmartDashboard.putNumber("MaxHoldingTorque", maxHoldingTorqueNM());
// SmartDashboard.putNumber("V_PER_NM", getV_PER_NM());
// SmartDashboard.putNumber("COMDistance", getCoM().getNorm());
SmartDashboard.putNumber("InternalArmVelocity", armMasterEncoder.getVelocity());
// SmartDashboard.putNumber("Arm Current", armMotor.getOutputCurrent());
// SmartDashboard.putNumber("ArmPos", getArmPos());
autoCancelArmCommand();
driveArm();
}
public void autoCancelArmCommand() {
if (!(getDefaultCommand() instanceof ArmTeleop) || DriverStation.isAutonomous())
return;
double requestedSpeeds = ((ArmTeleop) getDefaultCommand()).getRequestedSpeeds();
if (requestedSpeeds != 0) {
Command currentArmCommand = getCurrentCommand();
if (currentArmCommand != getDefaultCommand() && currentArmCommand != null) {
currentArmCommand.cancel();
}
}
}
// #region Drive Methods
private void driveArm() {
setpoint = armProfile.calculate(kDt, setpoint, goalState);
double armFeedVolts = armFeed.calculate(setpoint.position, setpoint.velocity);
if ((getArmPos() < LOWER_ANGLE_LIMIT_RAD)
|| (getArmPos() > UPPER_ANGLE_LIMIT_RAD)) {
armFeedVolts = armFeed.calculate(getArmPos(), 0);
//kg * cos(arm angle) * arm_COM_length
}
armPIDMaster.setReference(setpoint.position, CANSparkBase.ControlType.kPosition, 0, armFeedVolts);
}
public void setArmTarget(double targetPos) {
targetPos = getArmClampedGoal(targetPos);
goalState.position = targetPos;
goalState.velocity = 0;
}
public void resetGoal() {
double armPos = getArmPos();
setArmTarget(armPos);
}
public void driveMotor(Measure<Voltage> volts) {
armMotorMaster.setVoltage(volts.in(Volts));
}
private SysIdRoutine.Config defaultSysIdConfig = new SysIdRoutine.Config(Volts.of(1).per(Seconds.of(1)), Volts.of(2), Seconds.of(10));
public void logMotor(SysIdRoutineLog log) {
log.motor("armMotorMaster")
.voltage(voltage.mut_replace(
armMotorMaster.getBusVoltage() * armMotorMaster.getAppliedOutput(),
Volts))
.angularVelocity(velocity.mut_replace(
armMasterEncoder.getVelocity()* (Math.PI/ 180),
RadiansPerSecond))
.angularPosition(distance.mut_replace(
armMasterEncoder.getPosition(),
Radians));
}
private final SysIdRoutine routine = new SysIdRoutine(
defaultSysIdConfig,
new SysIdRoutine.Mechanism(
this::driveMotor,
this::logMotor,
this));
public Command sysIdQuasistatic(SysIdRoutine.Direction direction) {
return routine.quasistatic(direction);
}
public Command sysIdDynamic(SysIdRoutine.Direction direction) {
return routine.dynamic(direction);
}
// #endregion
// #region Getters
public double getArmPos() {
return MathUtil.inputModulus(armMasterEncoder.getPosition(), ARM_DISCONT_RAD,
ARM_DISCONT_RAD + 2 * Math.PI);
}
public double getArmVel() {
return armMasterEncoder.getVelocity();
}
public TrapezoidProfile.State getCurrentArmState() {
return new TrapezoidProfile.State(getArmPos(), getArmVel());
}
public TrapezoidProfile.State getCurrentArmGoal() {
return goalState;
}
public boolean armAtSetpoint() {
return Math.abs(getArmPos() - goalState.position) < POS_TOLERANCE_RAD &&
Math.abs(getArmVel() - goalState.velocity) < VEL_TOLERANCE_RAD_P_SEC;
}
public double getArmClampedGoal(double goal) {
return MathUtil.clamp(MathUtil.inputModulus(goal, ARM_DISCONT_RAD, ARM_DISCONT_RAD + 2 * Math.PI),
LOWER_ANGLE_LIMIT_RAD, UPPER_ANGLE_LIMIT_RAD);
}
public double getMaxAccelRad(){
return armFeed.maxAchievableVelocity(12, getArmPos(), getArmVel());
}
}