Skip to content

Commit

Permalink
Control changes (#29)
Browse files Browse the repository at this point in the history
* Changed controls for Driver and Operator

* fix arm encoder constant and switched driver trigger controls

* climb direction fix

---------

Co-authored-by: Anay Nagar <[email protected]>
  • Loading branch information
ProgrammingSR and ReeledWarrior14 authored Mar 9, 2024
1 parent 599e075 commit e88e22c
Show file tree
Hide file tree
Showing 3 changed files with 36 additions and 20 deletions.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ public static final class IntakeConstants {
public static final double kIntakeAmpScoringAngle = -93; // 193 - 100 (previous angle)

/** Encoder offset in rotations */
public static final double kArmEncoderOffset = 0.2252;
public static final double kArmEncoderOffset = 0.3415;

public static final double kIntakeSpeed = 0.5;

Expand Down
47 changes: 31 additions & 16 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -110,26 +110,26 @@ public RobotContainer() {
IOConstants.kControllerDeadband)
* DriveConstants.kMaxSpeedMetersPerSecond
* (1 - m_driverController
.getLeftTriggerAxis()
.getRightTriggerAxis()
* IOConstants.kSlowModeScalar),
// * 0.8,
MathUtil.applyDeadband(
-m_driverController.getLeftX(),
IOConstants.kControllerDeadband)
* DriveConstants.kMaxSpeedMetersPerSecond
* (1 - m_driverController
.getLeftTriggerAxis()
.getRightTriggerAxis()
* IOConstants.kSlowModeScalar),
// * 0.8,
MathUtil.applyDeadband(
-m_driverController.getRightX(),
IOConstants.kControllerDeadband)
* DriveConstants.kMaxAngularSpeedRadiansPerSecond
* (1 - m_driverController
.getLeftTriggerAxis()
.getRightTriggerAxis()
* IOConstants.kSlowModeScalar)
/ 2,
!m_driverController.getRightBumper()),
!m_driverController.getLeftBumper()),
m_robotDrive));
}

Expand All @@ -151,13 +151,11 @@ private void configureBindings() {
new NoteOuttakeCommand(m_intakeSubsystem)))
.onFalse(new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Off));

new JoystickButton(m_operatorController, Button.kA.value)
.onTrue(new InstantCommand(() -> m_climberSubsystem.forward(),
m_climberSubsystem));
new JoystickButton(m_operatorController, Button.kB.value)
.onTrue(new InstantCommand(() -> m_climberSubsystem.reverse(),
m_climberSubsystem));
new JoystickButton(m_driverController, Button.kRightBumper.value)
.onTrue(new IntakeArmPositionCommand(m_intakeSubsystem, ArmPosition.Amp))
.onFalse(new IntakeArmPositionCommand(m_intakeSubsystem, ArmPosition.Retracted));

// Intake, Driver Controller Right Trigger
new Trigger(() -> {
return m_driverController.getLeftTriggerAxis() > 0.5;
}).whileTrue(
Expand All @@ -167,13 +165,30 @@ private void configureBindings() {
new IntakeArmPositionCommand(m_intakeSubsystem, ArmPosition.Retracted)))
.onFalse(new IntakeArmPositionCommand(m_intakeSubsystem, ArmPosition.Retracted));

// Outtake, Operator Controller Right Trigger
new Trigger(() -> {
return m_driverController.getRightTriggerAxis() > 0.5;
}).whileTrue(
new SequentialCommandGroup(
new IntakeArmPositionCommand(m_intakeSubsystem, ArmPosition.Amp),
new NoteOuttakeCommand(m_intakeSubsystem)))
.onFalse(new IntakeArmPositionCommand(m_intakeSubsystem, ArmPosition.Retracted));
return m_operatorController.getRightTriggerAxis() > 0.5;
}).whileTrue(new NoteOuttakeCommand(m_intakeSubsystem));

new Trigger(() -> {
return m_operatorController.getLeftTriggerAxis() > 0.5;
}).onTrue(new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Shooting))
.onFalse(new ShooterSetSpeedCommand(m_shooterSubsystem, ShootSpeed.Off));

// Climber Up, Operator Controller Right Bumper + A Button
new Trigger(() -> {
return m_operatorController.getAButton() && m_operatorController.getRightBumper();
}).whileTrue(new InstantCommand(() -> m_climberSubsystem.forward()));

// Climber Down, Operator Controller Right Bumper + B Button
new Trigger(() -> {
return m_operatorController.getBButton() && m_operatorController.getRightBumper();
}).whileTrue(new InstantCommand(() -> m_climberSubsystem.reverse()));

// Toggle Distance Sensor, Operatoe Controller Left Bumper + Start Button
new Trigger(() -> {
return m_operatorController.getLeftBumper() && m_operatorController.getStartButton();
}).onTrue(new InstantCommand(() -> m_intakeSubsystem.toggleDistanceSensor()));
}

/**
Expand Down
7 changes: 4 additions & 3 deletions src/main/java/frc/robot/subsystems/ClimberSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,10 +13,10 @@
import frc.robot.Constants.ClimberConstants;

public class ClimberSubsystem extends SubsystemBase {
private final DoubleSolenoid m_leftSolenoid = new DoubleSolenoid(PneumaticsModuleType.REVPH,
private final DoubleSolenoid m_leftSolenoid = new DoubleSolenoid(2, PneumaticsModuleType.REVPH,
ClimberConstants.leftForwardChannel, ClimberConstants.leftReverseChannel);
private final DoubleSolenoid m_rightSolenoid = new DoubleSolenoid(PneumaticsModuleType.REVPH,
ClimberConstants.rightForwardChannel, ClimberConstants.rightReverseChannel);
private final DoubleSolenoid m_rightSolenoid = new DoubleSolenoid(2, PneumaticsModuleType.REVPH,
ClimberConstants.rightReverseChannel, ClimberConstants.rightForwardChannel);
private PneumaticHub m_pHub;

private boolean m_compressorEnabled;
Expand All @@ -37,6 +37,7 @@ public ClimberSubsystem() {
public void periodic() {
m_leftSolenoid.set(m_state);
m_rightSolenoid.set(m_state);
SmartDashboard.putString("pneumatics state", m_state.name());
SmartDashboard.putNumber("pressure", m_pHub.getPressure(0));
}

Expand Down

0 comments on commit e88e22c

Please sign in to comment.