Skip to content

Commit e622ad0

Browse files
Spotless applied
1 parent b718b23 commit e622ad0

File tree

2 files changed

+43
-35
lines changed

2 files changed

+43
-35
lines changed

src/main/java/frc/robot/constants/ClimberConstants.java

Lines changed: 4 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,4 @@
1+
/* Black Knights Robotics (C) 2025 */
12
package frc.robot.constants;
23

34
import edu.wpi.first.math.trajectory.TrapezoidProfile;
@@ -12,18 +13,16 @@ public class ClimberConstants {
1213
public static final double JOINT_P = 0;
1314
public static final double JOINT_I = 0;
1415
public static final double JOINT_D = 0;
15-
//sgva
16+
// sgva
1617
public static final double JOINT_S = 0;
1718
public static final double JOINT_G = 0;
1819
public static final double JOINT_V = 0;
1920
public static final double JOINT_A = 0;
2021

2122
public static final double CURRENT_MAX = 0;
2223
public static final double CLIMBER_TOLERANCE = 0;
23-
//Current as in electricity.
24+
// Current as in electricity.
2425

25-
26-
27-
//
26+
//
2827

2928
}
Lines changed: 39 additions & 30 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,4 @@
1+
/* Black Knights Robotics (C) 2025 */
12
package frc.robot.subsystems;
23

34
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
@@ -8,51 +9,53 @@
89
import com.revrobotics.spark.config.SparkFlexConfig;
910
import edu.wpi.first.math.controller.ArmFeedforward;
1011
import edu.wpi.first.math.controller.ProfiledPIDController;
11-
import edu.wpi.first.math.system.plant.DCMotor;
1212
import edu.wpi.first.wpilibj2.command.SubsystemBase;
1313
import frc.robot.constants.ClimberConstants;
1414

1515
public class ClimberSubsystem extends SubsystemBase {
1616

1717
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.
2731
private final RelativeEncoder jointEncoder = jointMotor.getEncoder();
2832

2933
private boolean isRotaryRotating = false;
3034
private int currentDirection = 1;
3135

3236
private final ArmFeedforward climberFF =
33-
3437
new ArmFeedforward(
3538
ClimberConstants.JOINT_S,
3639
ClimberConstants.JOINT_G,
3740
ClimberConstants.JOINT_V,
38-
ClimberConstants.JOINT_A
39-
);
41+
ClimberConstants.JOINT_A);
4042

4143
public ClimberSubsystem() {
4244

43-
SparkFlexConfig elbowMotorConfig = new SparkFlexConfig();
45+
SparkFlexConfig elbowMotorConfig = new SparkFlexConfig();
4446

4547
jointMotor.configure(
4648
elbowMotorConfig,
4749
SparkBase.ResetMode.kNoResetSafeParameters,
4850
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+
);
5254
}
5355

5456
/**
5557
* Sets pidController target position.
58+
*
5659
* @param position Position is target PID position.
5760
*/
5861
public void setJointPosition(double position) {
@@ -61,14 +64,16 @@ public void setJointPosition(double position) {
6164

6265
/**
6366
* Sets rotary motor(Bag motor) voltage.
67+
*
6468
* @param voltage Voltage is target voltage for rotary motor.
6569
*/
66-
public void setRotaryVoltage(double voltage){
70+
public void setRotaryVoltage(double voltage) {
6771
rotaryMotor.setVoltage(voltage);
6872
}
6973

7074
/**
71-
*gets joint motor velocity(Neo vortex)
75+
* gets joint motor velocity(Neo vortex)
76+
*
7277
* @return joint encoder velocity.
7378
*/
7479
public double getJointVelocity() {
@@ -77,54 +82,58 @@ public double getJointVelocity() {
7782

7883
/**
7984
* Sets the voltage of the joint motor(Neo vortex)
85+
*
8086
* @param voltage Voltage is target voltage
8187
*/
82-
public void setJointVoltage(double voltage){
88+
public void setJointVoltage(double voltage) {
8389
jointMotor.setVoltage(voltage);
8490
}
8591

8692
/**
8793
* Stops rotary motor when it hits cage and sees current spike.
94+
*
8895
* @param currentMax Current maximum when rotary motor hits hardstop.
8996
*/
90-
public void stopRotaryMotor(double currentMax){
91-
if(rotaryMotor.getSupplyCurrent() > currentMax){
97+
public void stopRotaryMotor(double currentMax) {
98+
if (rotaryMotor.getSupplyCurrent() > currentMax) {
9299
rotaryMotor.setVoltage(0);
93100
}
94101
}
95102

96103
/**
97104
* Gets joint encoder position
105+
*
98106
* @return joint encoder position
99107
*/
100-
public double getJointPosition(){
108+
public double getJointPosition() {
101109
return jointEncoder.getPosition();
102110
}
103111

104112
/**
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.
107116
*
108117
* @param voltage Voltage is target voltage.
109118
*/
110-
public void rotateRotary(double voltage){
119+
public void rotateRotary(double voltage) {
111120
rotaryMotor.setVoltage(voltage * currentDirection);
112121
isRotaryRotating = true;
113122
currentDirection *= -1;
114123
}
115124

116125
@Override
117126
public void periodic() {
118-
if(isRotaryRotating){
127+
if (isRotaryRotating) {
119128
stopRotaryMotor(ClimberConstants.CURRENT_MAX);
120129
}
121130
double pidCalc = pidController.calculate(getJointPosition());
122131
double ffCalc = climberFF.calculate(getJointPosition(), getJointVelocity());
123132
setJointVoltage(pidCalc + ffCalc);
124133
}
125134

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.
129138

130139
}

0 commit comments

Comments
 (0)