Skip to content

Commit

Permalink
add climber code
Browse files Browse the repository at this point in the history
  • Loading branch information
taj-maharj08 committed Feb 19, 2024
1 parent 86acd7f commit 791b7d5
Show file tree
Hide file tree
Showing 6 changed files with 158 additions and 54 deletions.
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,7 @@ gversion {
}

// Spotless formatting
// project.compileJava.dependsOn(spotlessApply)
project.compileJava.dependsOn(spotlessApply)
spotless {
java {
target fileTree(".") {
Expand Down
87 changes: 34 additions & 53 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@

import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.auto.NamedCommands;

import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
Expand All @@ -15,13 +14,11 @@
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.robot.arm.Arm;
import frc.robot.climber.Climber;
import frc.robot.drivetrain.Drivetrain;
import frc.robot.intake.Intake;
import frc.robot.shooter.Shooter;
import frc.robot.vision.Vision;

import javax.naming.PartialResultException;

import org.littletonrobotics.junction.LogFileUtil;
import org.littletonrobotics.junction.LoggedRobot;
import org.littletonrobotics.junction.Logger;
Expand All @@ -38,6 +35,7 @@ public class Robot extends LoggedRobot {
private final Intake m_intake = new Intake();
private final Shooter m_shooter = new Shooter();
private final Arm m_arm = new Arm();
private final Climber m_climber;

private final CommandXboxController m_driverController = new CommandXboxController(0);
private final CommandXboxController m_operatorController = new CommandXboxController(1);
Expand Down Expand Up @@ -71,23 +69,24 @@ public Robot() {
case kReal:
m_drivetrain = Subsystems.createTalonFXDrivetrain();
m_vision = Subsystems.createFourCameraVision();
m_climber = Subsystems.createSparkMAXClimber();
break;
case kSim:
m_drivetrain = Subsystems.createTalonFXDrivetrain();
m_vision = Subsystems.createFourCameraVision();
m_climber = Subsystems.createBlankClimber();
break;
default:
m_drivetrain = Subsystems.createBlankDrivetrain();

m_vision = Subsystems.createBlankFourCameraVision();
m_climber = Subsystems.createBlankClimber();
break;
}
m_vision.setVisionPoseConsumer(m_drivetrain.getVisionPoseConsumer());
m_drivetrain.setDefaultCommand(
m_drivetrain.joystickDrive(
() -> -m_driverController.getLeftY(),
() -> -m_driverController.getLeftX(),
// This needs to be getRawAxis(2) when using sim on a Mac
() -> -m_driverController.getRightX()));
// NamedCommands.registerCommand("stop", m_shooter.Stop().withTimeout(0.5));
// NamedCommands.registerCommand("sensorIntake", SensorIntake());
Expand All @@ -103,9 +102,8 @@ public Robot() {
// NamedCommands.registerCommand("ArmDown", m_arm.goDown());
NamedCommands.registerCommand("goDownAuto", m_arm.goToDegSeq(10, 0, -2));
NamedCommands.registerCommand("2ndNoteShot", m_arm.goToDeg(10, 12));
NamedCommands.registerCommand("Stop Intake Shooter Feeder", Commands.sequence(
m_intake.Stop(),
m_shooter.Stop()));
NamedCommands.registerCommand(
"Stop Intake Shooter Feeder", Commands.sequence(m_intake.Stop(), m_shooter.Stop()));
NamedCommands.registerCommand("Arm Go Down", m_arm.goDown());

m_autoChooser = new LoggedDashboardChooser<>("Auto Chooser", AutoBuilder.buildAutoChooser());
Expand Down Expand Up @@ -145,20 +143,17 @@ public Robot() {
.onTrue(new ParallelCommandGroup(m_intake.intake(false), m_shooter.FeederOn()).repeatedly())
.onFalse(
new ParallelRaceGroup(
m_shooter.PullBack(), m_intake.intake(speakerShot).withTimeout(0.25)).finallyDo(() -> m_shooter.Stop()));
m_shooter.PullBack(), m_intake.intake(speakerShot).withTimeout(0.25))
.finallyDo(() -> m_shooter.Stop()));

// ___________________OperatorController______________________\\
m_operatorController
.leftTrigger()
.onTrue(Commands.parallel(m_intake.release(),m_arm.goToAmp(), m_shooter.ShooterOn()))
.onFalse(Commands.sequence(
m_arm.goDown(),
m_shooter.ShooterOff()));
.onTrue(Commands.parallel(m_intake.release(), m_arm.goToAmp(), m_shooter.ShooterOn()))
.onFalse(Commands.sequence(m_arm.goDown(), m_shooter.ShooterOff()));

// prep for climb
m_operatorController.rightBumper()
.onTrue(m_arm.goToDegSeq(110, 0, 0))
.onFalse(m_arm.goDown());
m_operatorController.rightBumper().onTrue(m_arm.goToDegSeq(110, 0, 0)).onFalse(m_arm.goDown());

m_operatorController.rightTrigger().onTrue(m_arm.goDown()).onFalse(m_arm.goDown());

Expand All @@ -169,41 +164,35 @@ public Robot() {
m_arm.goToDeg(20, 25),
new InstantCommand(() -> speakerShot = true),
m_shooter.ShooterOn()))
.onFalse(Commands.sequence(
m_arm.goDown(),
m_shooter.ShooterOff()));
.onFalse(Commands.sequence(m_arm.goDown(), m_shooter.ShooterOff()));

// turn on the shooter wheels
m_operatorController.y().onTrue(m_shooter.Shoot());

m_operatorController
.leftBumper()
.onTrue(new ParallelCommandGroup(m_arm.goToDeg(0, 20), m_shooter.Catch().repeatedly()))
.onFalse(new ParallelCommandGroup( m_arm.goDown(), m_shooter.Stop()));
.onFalse(new ParallelCommandGroup(m_arm.goDown(), m_shooter.Stop()));

m_operatorController.povDown().whileTrue(m_climber.winchDown());
}

public Command SensorIntake() {
return new ParallelRaceGroup(
new RepeatCommand(m_intake.intake(speakerShot)),
new RepeatCommand(m_shooter.FeederOn())
.until(
() -> {
return m_shooter.hasNote();
}))
.andThen(Commands.sequence(
m_intake.Stop(),
m_shooter.FeederOff()));
new RepeatCommand(m_intake.intake(speakerShot)),
new RepeatCommand(m_shooter.FeederOn())
.until(
() -> {
return m_shooter.hasNote();
}))
.andThen(Commands.sequence(m_intake.Stop(), m_shooter.FeederOff()));
}

/**
* This function is called every robot packet, no matter the mode. Use this for
* items like
* diagnostics that you want ran during disabled, autonomous, teleoperated and
* test.
* This function is called every robot packet, no matter the mode. Use this for items like
* diagnostics that you want ran during disabled, autonomous, teleoperated and test.
*
* <p>
* This runs after the mode specific periodic functions, but before LiveWindow
* and`
* <p>This runs after the mode specific periodic functions, but before LiveWindow and`
* SmartDashboard integrated updating.
*/
@Override
Expand All @@ -224,36 +213,28 @@ public void autonomousInit() {
}

@Override
public void autonomousPeriodic() {
}
public void autonomousPeriodic() {}

@Override
public void teleopInit() {
}
public void teleopInit() {}

@Override
public void teleopPeriodic() {
}
public void teleopPeriodic() {}

@Override
public void disabledInit() {
}
public void disabledInit() {}

@Override
public void disabledPeriodic() {
}
public void disabledPeriodic() {}

@Override
public void testInit() {
}
public void testInit() {}

@Override
public void testPeriodic() {
}
public void testPeriodic() {}

@Override
public void simulationInit() {
}
public void simulationInit() {}

@Override
public void simulationPeriodic() {
Expand Down
11 changes: 11 additions & 0 deletions src/main/java/frc/robot/Subsystems.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,9 @@
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Transform3d;
import edu.wpi.first.math.geometry.Translation3d;
import frc.robot.climber.Climber;
import frc.robot.climber.ClimberIO;
import frc.robot.climber.ClimberIOSparkMAX;
import frc.robot.drivetrain.Drivetrain;
import frc.robot.drivetrain.ImuIO;
import frc.robot.drivetrain.ImuIOPigeon2;
Expand Down Expand Up @@ -37,4 +40,12 @@ public static Vision createFourCameraVision() {
public static Vision createBlankFourCameraVision() {
return new Vision(new VisionIO() {}, new VisionIO() {}, new VisionIO() {}, new VisionIO() {});
}

public static Climber createSparkMAXClimber() {
return new Climber(new ClimberIOSparkMAX());
}

public static Climber createBlankClimber() {
return new Climber(new ClimberIO() {});
}
}
38 changes: 38 additions & 0 deletions src/main/java/frc/robot/climber/Climber.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
package frc.robot.climber;

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import org.littletonrobotics.junction.Logger;

public class Climber extends SubsystemBase {
private final ClimberIO m_climberIO;
private final ClimberIOInputsAutoLogged m_inputs = new ClimberIOInputsAutoLogged();

public Climber(ClimberIO climberIO) {
m_climberIO = climberIO;

setDefaultCommand(idle());
}

@Override
public void periodic() {
m_climberIO.updateInputs(m_inputs);
Logger.processInputs("ClimberInputs", m_inputs);
}

public Command idle() {
return this.run(
() -> {
m_climberIO.setLeftDutyCycle(0.0);
m_climberIO.setRightDutyCycle(0.0);
});
}

public Command winchDown() {
return this.run(
() -> {
m_climberIO.setLeftDutyCycle(0.5);
m_climberIO.setRightDutyCycle(0.5);
});
}
}
24 changes: 24 additions & 0 deletions src/main/java/frc/robot/climber/ClimberIO.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
package frc.robot.climber;

import org.littletonrobotics.junction.AutoLog;

public interface ClimberIO {
@AutoLog
public class ClimberIOInputs {
public double leftWinchPositionRad = 0.0;
public double leftWinchVelocityRadPerSec = 0.0;
public double leftWinchAppliedVolts = 0.0;
public double leftWinchCurrentAmps = 0.0;

public double rightWinchPositionRad = 0.0;
public double rightWinchVelocityRadPerSec = 0.0;
public double rightWinchAppliedVolts = 0.0;
public double rightWinchCurrentAmps = 0.0;
}

public default void updateInputs(ClimberIOInputs inputs) {}

public default void setLeftDutyCycle(double outputDutyCycle) {}

public default void setRightDutyCycle(double outputDutyCycle) {}
}
50 changes: 50 additions & 0 deletions src/main/java/frc/robot/climber/ClimberIOSparkMAX.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
package frc.robot.climber;

import com.revrobotics.CANSparkMax;
import com.revrobotics.RelativeEncoder;
import edu.wpi.first.math.util.Units;

public class ClimberIOSparkMAX implements ClimberIO {

private final double kWinchReduction = 1.0;
private final CANSparkMax m_leftWinchMotor, m_rightWinchMotor;
private final RelativeEncoder m_leftWinchEncoder, m_rightWinchEncoder;

public ClimberIOSparkMAX() {

m_leftWinchMotor = new CANSparkMax(8, CANSparkMax.MotorType.kBrushless);
m_rightWinchMotor = new CANSparkMax(9, CANSparkMax.MotorType.kBrushless);

m_leftWinchEncoder = m_leftWinchMotor.getEncoder();
m_rightWinchEncoder = m_rightWinchMotor.getEncoder();
}

@Override
public void updateInputs(ClimberIOInputs inputs) {
inputs.leftWinchPositionRad =
Units.rotationsToRadians(m_leftWinchEncoder.getPosition() / kWinchReduction);
inputs.leftWinchVelocityRadPerSec =
Units.rotationsToRadians(m_leftWinchEncoder.getVelocity() / kWinchReduction);
inputs.leftWinchAppliedVolts =
m_leftWinchMotor.getAppliedOutput() * m_leftWinchMotor.getBusVoltage();
inputs.leftWinchCurrentAmps = m_leftWinchMotor.getOutputCurrent();

inputs.rightWinchPositionRad =
Units.rotationsToRadians(m_rightWinchEncoder.getPosition() / kWinchReduction);
inputs.rightWinchVelocityRadPerSec =
Units.rotationsToRadians(m_rightWinchEncoder.getVelocity() / kWinchReduction);
inputs.rightWinchAppliedVolts =
m_rightWinchMotor.getAppliedOutput() * m_rightWinchMotor.getBusVoltage();
inputs.rightWinchCurrentAmps = m_rightWinchMotor.getOutputCurrent();
}

@Override
public void setLeftDutyCycle(double outputDutyCycle) {
m_leftWinchMotor.set(outputDutyCycle);
}

@Override
public void setRightDutyCycle(double outputDutyCycle) {
m_rightWinchMotor.set(outputDutyCycle);
}
}

0 comments on commit 791b7d5

Please sign in to comment.