Skip to content

Commit

Permalink
created digital switches and limits in elevator sim
Browse files Browse the repository at this point in the history
  • Loading branch information
Tylefrost committed Feb 8, 2025
1 parent b3bdae5 commit 05cf5c3
Show file tree
Hide file tree
Showing 3 changed files with 21 additions and 1 deletion.
6 changes: 6 additions & 0 deletions simgui-ds.json
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,11 @@
"visible": true
}
},
"System Joysticks": {
"window": {
"visible": false
}
},
"keyboardJoysticks": [
{
"axisConfig": [
Expand Down Expand Up @@ -109,6 +114,7 @@
}
],
"robotJoysticks": [
{},
{
"guid": "Keyboard0"
}
Expand Down
8 changes: 8 additions & 0 deletions src/main/java/frc/robot/commands/ManualElevatorCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,14 @@ public void execute() {
double calculatedVolts = elevator.elevatorFF.calculate(manualVelocity);
Logger.recordOutput("ElevatorSubsystem/target_voltage", calculatedVolts);
this.elevator.setElevatorVoltage(calculatedVolts);
if (elevator.getLoadHeight() >= 1.8) {
// We are going up and top limit is tripped so stop
elevator.setElevatorVoltage(ElevatorConstants.kG);
}
if (elevator.getLoadHeight() <= 0.5) {
// We are going down and bottom limit is tripped so stop
elevator.setElevatorVoltage(ElevatorConstants.kG);
}
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,7 @@

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.filter.LinearFilter;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.simulation.ElevatorSim;
import frc.robot.constants.ElevatorConstants;
import org.littletonrobotics.junction.Logger;
Expand All @@ -22,14 +23,19 @@ public class ElevatorIOSim implements ElevatorIO {
0,
0.01,0);

public static final DigitalInput toplimitSwitch = new DigitalInput(0);
public static final DigitalInput bottomlimitSwitch = new DigitalInput(1);

@Override
public void updateInputs(ElevatorIO.ElevatorIOInputs inputs) {
elevatorMotor1Sim.update(LOOP_PERIOD_SECS);
inputs.unfilteredLoadHeight = elevatorMotor1Sim.getPositionMeters();
inputs.loadHeight = elevatorFilter.calculate(inputs.unfilteredLoadHeight);
inputs.elevatorCurrentAmps = new double[]{Math.abs(elevatorMotor1Sim.getCurrentDrawAmps())};
inputs.elevatorSpeed = elevatorMotor1Sim.getVelocityMetersPerSecond();


Logger.recordOutput("ElevatorSubsystem/toplimitSwitch", toplimitSwitch.get());
Logger.recordOutput("ElevatorSubsystem/bottomlimitSwitch", bottomlimitSwitch.get());
Logger.recordOutput("ElevatorSubsystem/loadHeight", inputs.loadHeight);
Logger.recordOutput("ElevatorSubsystem/unfilteredLoadHeight", inputs.unfilteredLoadHeight);
}
Expand Down

0 comments on commit 05cf5c3

Please sign in to comment.