Skip to content

Commit

Permalink
make the sparkmaxes actually turn again (doh)
Browse files Browse the repository at this point in the history
  • Loading branch information
willitcode committed Feb 7, 2024
1 parent d28bab3 commit a2d6e81
Showing 1 changed file with 4 additions and 4 deletions.
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -47,8 +47,8 @@ public void robotInit() {
solenoid2 = new DoubleSolenoid(PneumaticsModuleType.CTREPCM, 4, 5);
controller = new XboxController(0);
talon = new TalonFX(1);
leftStickSparkMax = new CANSparkMax(3, MotorType.kBrushless);
rightStickSparkMax = new CANSparkMax(5, MotorType.kBrushless);
leftStickSparkMax = new CANSparkMax(4, MotorType.kBrushless);
rightStickSparkMax = new CANSparkMax(6, MotorType.kBrushless);
}

/**
Expand Down Expand Up @@ -96,8 +96,8 @@ public void teleopPeriodic() {
solenoid2.set(Value.kOff);
}

// leftStickSparkMax.set(getScaledControllerLeftYAxis());
// rightStickSparkMax.set(getScaledControllerRightYAxis());
leftStickSparkMax.set(getScaledControllerLeftYAxis());
rightStickSparkMax.set(getScaledControllerRightYAxis());
}

/** This function is called once when the robot is disabled. */
Expand Down

0 comments on commit a2d6e81

Please sign in to comment.