if (turret != null && drive != null && hood != null && shooter != null && spindexer != null) {
Command runSpindexer = new RunSpindexer(spindexer, turret);
- NamedCommands.registerCommand("Auto shoot", new Superstructure(turret, drive, hood, shooter, spindexer));
+ NamedCommands.registerCommand("Auto shoot", new AutoShootCommand(turret, drive, hood, shooter, spindexer));
NamedCommands.registerCommand("Start Spindexer",
new InstantCommand(() -> CommandScheduler.getInstance().schedule(runSpindexer)));
NamedCommands.registerCommand("Stop Spindexer", new InstantCommand(() -> runSpindexer.cancel()));
package frc.robot.subsystems.Climb;
+
import edu.wpi.first.math.util.Units;
public class ClimbConstants {
/** Winch spool radius in meters */
public final static double WHEEL_RADIUS = Units.inchesToMeters(0.334);
/** climber stowed ? position in meters */
- public final static double BOTTOM_POSITION = Units.inchesToMeters(-8);
+ public final static double BOTTOM_POSITION = Units.inchesToMeters(8);
/** Calibration position: lower than BOTTOM_POSITION to reduce motor strain */
- public final static double CALIBRATION_POSITION = Units.inchesToMeters(-8.5);
+ public final static double CALIBRATION_POSITION = Units.inchesToMeters(8.5);
/** position that should put the robot off the ground? in meters. */
- public final static double CLIMB_POSITION = Units.inchesToMeters(-6);
+ public final static double CLIMB_POSITION = Units.inchesToMeters(6);
public final static double UP_POSITION = 0.0;
// current limits (in amps)
motor.setNeutralMode(NeutralModeValue.Brake);
TalonFXConfiguration config = new TalonFXConfiguration();
- config.MotorOutput.Inverted = InvertedValue.Clockwise_Positive;
+ config.MotorOutput.Inverted = InvertedValue.CounterClockwise_Positive;
motor.getConfigurator().apply(config);
setCurrentLimits(ClimbConstants.CALIBRATION_CURRENT);
}
motor.set(power);
- SmartDashboard.putNumber("Climb/PID_Setpoint_Rotations", pid.getSetpoint());
- SmartDashboard.putNumber("Climb/Motor_Actual_Rotations", motor.getPosition().getValueAsDouble());
- SmartDashboard.putNumber("Climb/Motor_Actual_Meters", inputs.positionMeters);
+ SmartDashboard.putNumber("Climb PID_Setpoint_Rotations", pid.getSetpoint());
+ SmartDashboard.putNumber("Climb Motor_Actual_Rotations", motor.getPosition().getValueAsDouble());
+ SmartDashboard.putNumber("Climb Motor_Actual_Meters", inputs.positionMeters);
- Logger.recordOutput("LinearClimb/setpointMeters", Units.rotationsToRadians(pid.getSetpoint())
+ Logger.recordOutput("LinearClimb setpointMeters", Units.rotationsToRadians(pid.getSetpoint())
* ClimbConstants.WHEEL_RADIUS / ClimbConstants.CLIMB_GEAR_RATIO);
updateInputs();
Logger.processInputs("LinearClimb", inputs);
private final ShooterIOInputsAutoLogged inputs = new ShooterIOInputsAutoLogged();
- double powerModifier = 1.3;
+ double powerModifier = 1.25; // TESTED
public Shooter(){
updateInputs();