Skip to content
This repository has been archived by the owner on May 19, 2024. It is now read-only.

Commit

Permalink
fix(arm): Flip state of limit switch.
Browse files Browse the repository at this point in the history
  • Loading branch information
haydenheroux committed Mar 1, 2024
1 parent 3a9b578 commit ec741ba
Show file tree
Hide file tree
Showing 4 changed files with 12 additions and 10 deletions.
14 changes: 7 additions & 7 deletions src/main/java/frc/lib/Configurator.java
Original file line number Diff line number Diff line change
Expand Up @@ -101,12 +101,12 @@ public static void configureREV(Supplier<REVLibError> config) {
* @param sparkMax
*/
public static void configureStatusFrames(CANSparkMax sparkMax) {
Configurator.configureREV(() -> sparkMax.setPeriodicFramePeriod(PeriodicFrame.kStatus0, 25));
Configurator.configureREV(() -> sparkMax.setPeriodicFramePeriod(PeriodicFrame.kStatus1, 50));
Configurator.configureREV(() -> sparkMax.setPeriodicFramePeriod(PeriodicFrame.kStatus2, 50));
Configurator.configureREV(() -> sparkMax.setPeriodicFramePeriod(PeriodicFrame.kStatus3, 65535));
Configurator.configureREV(() -> sparkMax.setPeriodicFramePeriod(PeriodicFrame.kStatus4, 65535));
Configurator.configureREV(() -> sparkMax.setPeriodicFramePeriod(PeriodicFrame.kStatus5, 65535));
Configurator.configureREV(() -> sparkMax.setPeriodicFramePeriod(PeriodicFrame.kStatus6, 65535));
// Configurator.configureREV(() -> sparkMax.setPeriodicFramePeriod(PeriodicFrame.kStatus0, 25));
// Configurator.configureREV(() -> sparkMax.setPeriodicFramePeriod(PeriodicFrame.kStatus1, 50));
// Configurator.configureREV(() -> sparkMax.setPeriodicFramePeriod(PeriodicFrame.kStatus2, 50));
// Configurator.configureREV(() -> sparkMax.setPeriodicFramePeriod(PeriodicFrame.kStatus3, 65535));
// Configurator.configureREV(() -> sparkMax.setPeriodicFramePeriod(PeriodicFrame.kStatus4, 65535));
// Configurator.configureREV(() -> sparkMax.setPeriodicFramePeriod(PeriodicFrame.kStatus5, 65535));
// Configurator.configureREV(() -> sparkMax.setPeriodicFramePeriod(PeriodicFrame.kStatus6, 65535));
}
}
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,7 @@
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.lib.Telemetry;
import frc.robot.arm.Arm;
import frc.robot.auto.Auto;
import frc.robot.intake.Intake;
Expand Down Expand Up @@ -55,6 +56,7 @@ public static RobotContainer getInstance() {
/** Initializes subsystem telemetry. */
private void initializeTelemetry() {
if (RobotConstants.USE_TELEMETRY) {
Telemetry.initializeShuffleboards(arm);
SmartDashboard.putData("Arm Mechanism", RobotMechanisms.getInstance().getMechanism());
}

Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/arm/ArmFactory.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,8 @@ public static LimitSwitchIO createLimitSwitch() {
* @return a shoulder motor.
*/
public static ShoulderMotorIO createShoulderMotor() {
// if (Robot.isReal() && RobotConstants.REAL_SUBSYSTEMS.contains(Subsystem.ARM))
// return new ShoulderMotorIOSparkMax();
if (Robot.isReal() && RobotConstants.REAL_SUBSYSTEMS.contains(Subsystem.ARM))
return new ShoulderMotorIOSparkMax();

return new ShoulderMotorIOSim();
}
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/arm/LimitSwitchIODigital.java
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,6 @@ public void configure() {}

@Override
public void update(LimitSwitchIOValues values) {
values.isPressed = digitalInput.get();
values.isPressed = !digitalInput.get();
}
}

0 comments on commit ec741ba

Please sign in to comment.