Skip to content

Commit 8ac0772

Browse files
brought back deleted code
1 parent 942e2cd commit 8ac0772

2 files changed

Lines changed: 129 additions & 6 deletions

File tree

src/main/java/frc/robot/subsystems/elevator/ElevatorIO.java

Lines changed: 47 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,52 @@ public static class ElevatorIOInputs {
2525

2626

2727
default void updateInputs(ElevatorIOInputs inputs) {}
28-
default void setPIDGains(double kP, double kI, double kD) {}
28+
29+
default void setVoltage(double voltage) {}
30+
// Getter method for target height
31+
default void getSetpoint() {
32+
return 0.0;
33+
}
34+
35+
// Getter method for current position
36+
default void getPosition() {
37+
return 0.0;
38+
}
39+
40+
default void updateInputs(ElevatorIOInputs inputs) {}
41+
// Getter method for velocity
42+
default void getVelocity(){
43+
return 0.0;
44+
}
45+
2946
default void setRPM(double rpm){}
47+
// Checking if elevator goes above limit height
48+
default boolean isLimitSwitchPressed() {
49+
return false;
50+
}
51+
3052
default void setFeedForwardGains(double kS, double kV, double kA) {}
31-
}
53+
54+
// Subsystem API (Used by commands)
55+
56+
57+
// The target height in meters
58+
default void setSetpoint(double setpoint) {}
59+
60+
// Profiled PID to go to setpoint
61+
public default void goToSetpoint() {}
62+
63+
// Returns true if elevator at setpoint
64+
public default boolean atSetpoint() {
65+
return false;
66+
}
67+
68+
// Setter for voltage
69+
default void setVoltage(double voltage) {}
70+
71+
72+
73+
}
74+
75+
76+
Lines changed: 82 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,84 @@
1+
package frc.robot.subsystems.elevator;
2+
3+
import com.revrobotics.RelativeEncoder;
4+
import com.revrobotics.spark.SparkBase.PersistMode;
5+
import com.revrobotics.spark.SparkBase.ResetMode;
6+
import com.revrobotics.spark.SparkLowLevel.MotorType;
7+
import com.revrobotics.spark.SparkMax;
8+
import com.revrobotics.spark.config.SparkBaseConfig.IdleMode;
9+
import com.revrobotics.spark.config.SparkMaxConfig;
10+
import edu.wpi.first.math.MathUtil;
11+
import edu.wpi.first.math.controller.ElevatorFeedforward;
12+
import edu.wpi.first.math.controller.ProfiledPIDController;
13+
import edu.wpi.first.math.trajectory.TrapezoidProfile;
14+
import edu.wpi.first.wpilibj.DigitalInput;
15+
import edu.wpi.first.wpilibj.Timer;
16+
import frc.robot.Constants;
17+
import org.littletonrobotics.junction.Logger;
18+
119
public class ElevatorIOSparkMax implements ElevatorIO {
2-
// Profiled PID
3-
private ProfiledPIDController controller = new ProfiledPIDController(
4-
kP, kI, kD,
5-
new TrapezoidProfile.Constraints(MaxVelocity, MaxAcceleration));
20+
21+
double lastTime = Timer.getFPGATimestamp();
22+
23+
private SparkMax leftMotor;
24+
// right follows left
25+
private SparkMax rightMotor;
26+
private RelativeEncoder leftEncoder;
27+
28+
29+
public class ElevatorIOSparkMax {
30+
private ProfiledPIDController pidController =
31+
new ProfiledPIDController(
32+
ElevatorConstants.ELEVATOR_REAL_PID[0],
33+
ElevatorConstants.ELEVATOR_REAL_PID[1],
34+
ElevatorConstants.ELEVATOR_REAL_PID[2],
35+
new TrapezoidProfile.Constraints(
36+
ElevatorConstants.MAX_VELOCITY, ElevatorConstants.MAX_ACCELERATION));
37+
38+
39+
public ElevatorIOSparkMax() {
40+
leftMotor = new SparkMax(ElevatorConstants.LEFT_MOTOR_ID, MotorType.kBrushless);
41+
rightMotor = new SparkMax(ElevatorConstants.RIGHT_MOTOR_ID, MotorType.kBrushless);
42+
43+
leftEncoder = leftMotor.getEncoder();
44+
leftEncoder.setPosition(0);
45+
46+
SparkMaxConfig leftConfig = new SparkMaxConfig();
47+
leftConfig
48+
.smartCurrentLimit(Constants.NEO_CURRENT_LIMIT)
49+
.idleMode(ElevatorConstants.MOTOR_DEFAULT_IDLE_MODE) //??
50+
.voltageCompensation(12.0)
51+
.inverted(false);
52+
leftConfig
53+
.encoder
54+
.positionConversionFactor(ElevatorConstants.POSITION_CONVERSION_FACTOR)
55+
.velocityConversionFactor(ElevatorConstants.POSITION_CONVERSION_FACTOR / 60.0);
56+
57+
SparkMaxConfig rightConfig = new SparkMaxConfig();
58+
rightConfig.apply(leftConfig);
59+
rightConfig.follow(leftMotor, true);
60+
61+
// reset safe kResetSafeParameters switches the motor to default paramaters, then adds the
62+
// changes from the config object
63+
// persist paramaters saves these changes to the motor memory so it doesn't get cooked during
64+
// brownouts
65+
// only use persist in the BEGINNING, not later
66+
leftMotor.configure(leftConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
67+
rightMotor.configure(
68+
rightConfig, ResetMode.kResetSafeParameters, PersistMode.kPersistParameters);
69+
70+
pidController.setTolerance(ElevatorConstants.SETPOINT_TOLERANCE_METERS);
71+
72+
limitSwitch = new DigitalInput(ElevatorConstants.LIMIT_SWITCH_CHANNEL);
73+
74+
}
75+
76+
private void updateMotorConfig(SparkMaxConfig config) {
77+
// DO NOT RESET paramaters becasue we only want to change some paramaters, not all
78+
// DO NOT PERSIST because this is a temporary change that we don't want to save to memory
79+
leftMotor.configure(config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
80+
rightMotor.configure(
81+
config, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters);
82+
}
83+
}
684
}

0 commit comments

Comments
 (0)