1
+ /* Black Knights Robotics (C) 2025 */
1
2
package frc .robot .subsystems ;
2
3
3
4
import com .ctre .phoenix .motorcontrol .can .WPI_TalonSRX ;
8
9
import com .revrobotics .spark .config .SparkFlexConfig ;
9
10
import edu .wpi .first .math .controller .ArmFeedforward ;
10
11
import edu .wpi .first .math .controller .ProfiledPIDController ;
11
- import edu .wpi .first .math .system .plant .DCMotor ;
12
12
import edu .wpi .first .wpilibj2 .command .SubsystemBase ;
13
13
import frc .robot .constants .ClimberConstants ;
14
14
15
15
public class ClimberSubsystem extends SubsystemBase {
16
16
17
17
private final WPI_TalonSRX rotaryMotor = new WPI_TalonSRX (ClimberConstants .ROTARY_MOTOR_ID );
18
- //Bag motor
19
- private final SparkFlex jointMotor = new SparkFlex (
20
- ClimberConstants .JOINT_MOTOR_ID , SparkLowLevel .MotorType .kBrushless );
21
- //Neovortex arm motor
22
- private final ProfiledPIDController pidController = new ProfiledPIDController (
23
- ClimberConstants .JOINT_P , ClimberConstants .JOINT_I , ClimberConstants .JOINT_D , ClimberConstants .ARM_CONSTRAINTS );
24
-
25
- //private final RelativeEncoder rotaryEncoder = rotaryMotor.getEncoder
26
- //I dont think talonsrx has built in encoder.
18
+ // Bag motor
19
+ private final SparkFlex jointMotor =
20
+ new SparkFlex (ClimberConstants .JOINT_MOTOR_ID , SparkLowLevel .MotorType .kBrushless );
21
+ // Neovortex arm motor
22
+ private final ProfiledPIDController pidController =
23
+ new ProfiledPIDController (
24
+ ClimberConstants .JOINT_P ,
25
+ ClimberConstants .JOINT_I ,
26
+ ClimberConstants .JOINT_D ,
27
+ ClimberConstants .ARM_CONSTRAINTS );
28
+
29
+ // private final RelativeEncoder rotaryEncoder = rotaryMotor.getEncoder
30
+ // I dont think talonsrx has built in encoder.
27
31
private final RelativeEncoder jointEncoder = jointMotor .getEncoder ();
28
32
29
33
private boolean isRotaryRotating = false ;
30
34
private int currentDirection = 1 ;
31
35
32
36
private final ArmFeedforward climberFF =
33
-
34
37
new ArmFeedforward (
35
38
ClimberConstants .JOINT_S ,
36
39
ClimberConstants .JOINT_G ,
37
40
ClimberConstants .JOINT_V ,
38
- ClimberConstants .JOINT_A
39
- );
41
+ ClimberConstants .JOINT_A );
40
42
41
43
public ClimberSubsystem () {
42
44
43
- SparkFlexConfig elbowMotorConfig = new SparkFlexConfig ();
45
+ SparkFlexConfig elbowMotorConfig = new SparkFlexConfig ();
44
46
45
47
jointMotor .configure (
46
48
elbowMotorConfig ,
47
49
SparkBase .ResetMode .kNoResetSafeParameters ,
48
50
SparkBase .PersistMode .kPersistParameters
49
- //When we turn motor on, we do not reset parameters.
50
- //Persist means that it doesn't clear the parameters when it turns off
51
- );
51
+ // When we turn motor on, we do not reset parameters.
52
+ // Persist means that it doesn't clear the parameters when it turns off
53
+ );
52
54
}
53
55
54
56
/**
55
57
* Sets pidController target position.
58
+ *
56
59
* @param position Position is target PID position.
57
60
*/
58
61
public void setJointPosition (double position ) {
@@ -61,14 +64,16 @@ public void setJointPosition(double position) {
61
64
62
65
/**
63
66
* Sets rotary motor(Bag motor) voltage.
67
+ *
64
68
* @param voltage Voltage is target voltage for rotary motor.
65
69
*/
66
- public void setRotaryVoltage (double voltage ){
70
+ public void setRotaryVoltage (double voltage ) {
67
71
rotaryMotor .setVoltage (voltage );
68
72
}
69
73
70
74
/**
71
- *gets joint motor velocity(Neo vortex)
75
+ * gets joint motor velocity(Neo vortex)
76
+ *
72
77
* @return joint encoder velocity.
73
78
*/
74
79
public double getJointVelocity () {
@@ -77,54 +82,58 @@ public double getJointVelocity() {
77
82
78
83
/**
79
84
* Sets the voltage of the joint motor(Neo vortex)
85
+ *
80
86
* @param voltage Voltage is target voltage
81
87
*/
82
- public void setJointVoltage (double voltage ){
88
+ public void setJointVoltage (double voltage ) {
83
89
jointMotor .setVoltage (voltage );
84
90
}
85
91
86
92
/**
87
93
* Stops rotary motor when it hits cage and sees current spike.
94
+ *
88
95
* @param currentMax Current maximum when rotary motor hits hardstop.
89
96
*/
90
- public void stopRotaryMotor (double currentMax ){
91
- if (rotaryMotor .getSupplyCurrent () > currentMax ){
97
+ public void stopRotaryMotor (double currentMax ) {
98
+ if (rotaryMotor .getSupplyCurrent () > currentMax ) {
92
99
rotaryMotor .setVoltage (0 );
93
100
}
94
101
}
95
102
96
103
/**
97
104
* Gets joint encoder position
105
+ *
98
106
* @return joint encoder position
99
107
*/
100
- public double getJointPosition (){
108
+ public double getJointPosition () {
101
109
return jointEncoder .getPosition ();
102
110
}
103
111
104
112
/**
105
- * Rotates rotary motor. Sets boolean isRotaryRotating = true when it is called.
106
- * We set currentDirection *= -1 as it will reverse the direction of the rotary motor after it has rotated.
113
+ * Rotates rotary motor. Sets boolean isRotaryRotating = true when it is called. We set
114
+ * currentDirection *= -1 as it will reverse the direction of the rotary motor after it has
115
+ * rotated.
107
116
*
108
117
* @param voltage Voltage is target voltage.
109
118
*/
110
- public void rotateRotary (double voltage ){
119
+ public void rotateRotary (double voltage ) {
111
120
rotaryMotor .setVoltage (voltage * currentDirection );
112
121
isRotaryRotating = true ;
113
122
currentDirection *= -1 ;
114
123
}
115
124
116
125
@ Override
117
126
public void periodic () {
118
- if (isRotaryRotating ){
127
+ if (isRotaryRotating ) {
119
128
stopRotaryMotor (ClimberConstants .CURRENT_MAX );
120
129
}
121
130
double pidCalc = pidController .calculate (getJointPosition ());
122
131
double ffCalc = climberFF .calculate (getJointPosition (), getJointVelocity ());
123
132
setJointVoltage (pidCalc + ffCalc );
124
133
}
125
134
126
- // Arm motor needs pid for current
127
- // Rotate until current function
128
- // Rotate at a specific amount of volts until spike in current and then stop rotating.
135
+ // Arm motor needs pid for current
136
+ // Rotate until current function
137
+ // Rotate at a specific amount of volts until spike in current and then stop rotating.
129
138
130
139
}
0 commit comments