Skip to content

Commit 2d26a56

Browse files
amp bar layers
1 parent dbfb048 commit 2d26a56

3 files changed

Lines changed: 106 additions & 6 deletions

File tree

src/main/java/frc/robot/BuildConstants.java

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -5,12 +5,12 @@ public final class BuildConstants {
55
public static final String MAVEN_GROUP = "";
66
public static final String MAVEN_NAME = "2024RobotCode";
77
public static final String VERSION = "unspecified";
8-
public static final int GIT_REVISION = 313;
9-
public static final String GIT_SHA = "974424bf6ad82162eaa1ac360b41f2aa0d05c04d";
10-
public static final String GIT_DATE = "2024-07-27 20:08:15 EDT";
11-
public static final String GIT_BRANCH = "rainbow-rumble";
12-
public static final String BUILD_DATE = "2024-07-28 13:00:32 EDT";
13-
public static final long BUILD_UNIX_TIME = 1722186032402L;
8+
public static final int GIT_REVISION = 316;
9+
public static final String GIT_SHA = "5cc22806712e7f8851e100516ff524db3c14f0e2";
10+
public static final String GIT_DATE = "2024-08-03 20:37:50 EDT";
11+
public static final String GIT_BRANCH = "rotation-lock";
12+
public static final String BUILD_DATE = "2024-08-06 15:04:45 EDT";
13+
public static final long BUILD_UNIX_TIME = 1722971085276L;
1414
public static final int DIRTY = 1;
1515

1616
private BuildConstants() {}
Lines changed: 28 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,28 @@
1+
package frc.robot.subsystems.elevator;
2+
3+
import org.littletonrobotics.junction.AutoLog;
4+
5+
public interface AmpBarIO {
6+
7+
@AutoLog
8+
public static class AmpBarIOInputs {
9+
10+
public double barVelocity = 0;
11+
public double barPosition = 0;
12+
public double currentAmps = 0;
13+
public double appliedVolts = 0;
14+
public double barPositionSetpoint = 0;
15+
}
16+
17+
public default void updateInputs(AmpBarIOInputs inputs) {}
18+
19+
public default void setBrakeMode(boolean bool) {}
20+
21+
public default void setPositionSetpoint(double position, double ffVolts) {}
22+
23+
public default void setVoltage(double volts) {}
24+
25+
public default void stop() {}
26+
27+
public default void configurePID(double kP, double kI, double kD) {}
28+
}
Lines changed: 72 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,72 @@
1+
package frc.robot.subsystems.elevator;
2+
3+
import com.revrobotics.CANSparkBase.ControlType;
4+
import com.revrobotics.CANSparkBase.IdleMode;
5+
import com.revrobotics.CANSparkLowLevel;
6+
import com.revrobotics.CANSparkMax;
7+
import com.revrobotics.SparkPIDController;
8+
import com.revrobotics.SparkPIDController.ArbFFUnits;
9+
10+
public class AmpBarIOSparkMAX implements AmpBarIO {
11+
12+
private final CANSparkMax barMotor;
13+
private final SparkPIDController pid;
14+
private double barPositionSetpoint = 0;
15+
16+
public AmpBarIOSparkMAX(int motorID) {
17+
18+
barMotor = new CANSparkMax(motorID, CANSparkLowLevel.MotorType.kBrushless);
19+
20+
pid = barMotor.getPIDController();
21+
pid.setFeedbackDevice(barMotor.getAbsoluteEncoder());
22+
23+
barMotor.restoreFactoryDefaults();
24+
barMotor.setCANTimeout(250);
25+
barMotor.burnFlash();
26+
barMotor.clearFaults();
27+
}
28+
29+
@Override
30+
public void updateInputs(AmpBarIOInputs inputs) {
31+
inputs.barVelocity = barMotor.getEncoder().getVelocity();
32+
inputs.barPosition = barMotor.getEncoder().getPosition();
33+
inputs.barPositionSetpoint = barPositionSetpoint;
34+
inputs.currentAmps = barMotor.getOutputCurrent();
35+
inputs.appliedVolts = barMotor.getAppliedOutput();
36+
}
37+
38+
@Override
39+
public void setBrakeMode(boolean bool) {
40+
41+
if (bool) {
42+
barMotor.setIdleMode(IdleMode.kBrake);
43+
} else {
44+
barMotor.setIdleMode(IdleMode.kCoast);
45+
}
46+
}
47+
48+
@Override
49+
public void setPositionSetpoint(double position, double ffVolts) {
50+
51+
this.barPositionSetpoint = position;
52+
pid.setReference(position, ControlType.kPosition, 0, ffVolts, ArbFFUnits.kVoltage);
53+
}
54+
55+
@Override
56+
public void setVoltage(double volts) {
57+
barMotor.setVoltage(volts);
58+
}
59+
60+
@Override
61+
public void stop() {
62+
barMotor.stopMotor();
63+
}
64+
65+
@Override
66+
public void configurePID(double kP, double kI, double kD) {
67+
68+
pid.setP(kP);
69+
pid.setI(kI);
70+
pid.setD(kD);
71+
}
72+
}

0 commit comments

Comments
 (0)