Skip to content

Commit

Permalink
tune setpoints dp
Browse files Browse the repository at this point in the history
  • Loading branch information
KPatel008 committed Jan 22, 2025
1 parent bf96ff2 commit 85040aa
Show file tree
Hide file tree
Showing 2 changed files with 28 additions and 10 deletions.
20 changes: 12 additions & 8 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ private void configureBindings() {
* MaxAngularRate) // Drive counterclockwise with negative X (left)
));

joystick.a().whileTrue(drivetrain.applyRequest(() -> brake));
//joystick.a().whileTrue(drivetrain.applyRequest(() -> brake));
// joystick
// .b()
// .whileTrue(
Expand All @@ -82,18 +82,22 @@ private void configureBindings() {
// point.withModuleDirection(
// new Rotation2d(-joystick.getLeftY(), -joystick.getLeftX()))));

joystick.rightTrigger().whileTrue(s_Shooter.shootL2()).onFalse(s_Shooter.stop());
joystick.rightTrigger().whileTrue(s_Shooter.shootTrough()).onFalse(s_Shooter.stop());
joystick.y().whileTrue(s_Shooter.intake()).onFalse(s_Shooter.stop());
joystick.a().whileTrue(s_Shooter.shootTrough()).onFalse(s_Shooter.stop());
// joystick.a().whileTrue(s_Shooter.shootTrough()).onFalse(s_Shooter.stop());

joystick.b().onTrue(s_Elevator.goToL1()).onFalse(s_Elevator.stop());
joystick.leftBumper().onTrue(s_Elevator.goToL2
()).onFalse(s_Elevator.stop());
joystick.rightBumper().onTrue(s_Elevator.goToL3()).onFalse(s_Elevator.stop());
joystick.leftTrigger().onTrue(s_Elevator.goToL4()).onFalse(s_Elevator.stop());
joystick.leftBumper().onTrue(s_Elevator.goToL2()).onFalse(s_Elevator.goToL1());
joystick.rightBumper().onTrue(s_Elevator.goToL3()).onFalse(s_Elevator.goToL1());
joystick.leftTrigger().onTrue(s_Elevator.goToL4()).onFalse(s_Elevator.goToL1());
joystick.povUp().whileTrue(s_Elevator.moveUp()).onFalse(s_Elevator.stop());
joystick.povDown().whileTrue(s_Elevator.moveDown()).onFalse(s_Elevator.stop());
joystick.povLeft().onTrue(s_Elevator.reZero());
joystick.back().onTrue(s_Elevator.reZero());
joystick.x().onTrue(s_Elevator.goToL3A()).onFalse(s_Elevator.goToL1());
joystick.a().onTrue(s_Elevator.goToL2A()).onFalse(s_Elevator.goToL1());




// Run SysId routines when holding back/start and X/Y.
// Note that each routine should be run exactly once in a single log.
Expand Down
18 changes: 16 additions & 2 deletions src/main/java/frc/robot/subsystems/elevator/Elevator.java
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,10 @@ public class Elevator extends SubsystemBase {
private final ElevatorIO m_io;
private final double L1Setpoint = 29;
private final double L2Setpoint = 32.5;
private final double L3Setpoint = 51.5;
private final double L4Setpoint = 75;
private final double L3Setpoint = 48.5;
private final double L4Setpoint = 74.5;
private final double L2ASetpoint = 37.5;
private final double L3ASetpoint = 54;
//inch to rotations of the motor
final double m_gearRatio = 0.5 * (1d / (1.75100 * Math.PI)) * ( 2d / 3d ) * 25;

Expand Down Expand Up @@ -65,6 +67,18 @@ public Command goToL4(){
m_io.gotosetpoint(L4Setpoint, m_gearRatio);
}).withName("L4");
}
public Command goToL3A(){
// return this.run(() -> m_io.gotosetpoint(L1Setpoint,m_gearRatio));
return this.runOnce(() -> {
m_io.gotosetpoint(L3ASetpoint, m_gearRatio);
}).withName("L3A");
}
public Command goToL2A(){
// return this.run(() -> m_io.gotosetpoint(L1Setpoint,m_gearRatio));
return this.runOnce(() -> {
m_io.gotosetpoint(L2ASetpoint, m_gearRatio);
}).withName("L2A");
}
public Command reZero(){
return this.runOnce(() -> {
m_io.setPosition(L1Setpoint*m_gearRatio);
Expand Down

0 comments on commit 85040aa

Please sign in to comment.