summaryrefslogtreecommitdiff
path: root/src/main/java/frc/robot/RobotContainer.java
diff options
context:
space:
mode:
Diffstat (limited to 'src/main/java/frc/robot/RobotContainer.java')
-rw-r--r--src/main/java/frc/robot/RobotContainer.java34
1 files changed, 18 insertions, 16 deletions
diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java
index 9a6241a..40a0180 100644
--- a/src/main/java/frc/robot/RobotContainer.java
+++ b/src/main/java/frc/robot/RobotContainer.java
@@ -35,8 +35,9 @@ public class RobotContainer
m_chooser.addOption("Shoot",
Commands.parallel(
m_shooter.run(() -> m_shooter.atPercentage(1)),
- Commands.none().withTimeout(500).andThen(m_intake.run(() -> m_intake.atPercentage(1)))));
+ Commands.none().withTimeout(2000).andThen(m_intake.run(() -> m_intake.atPercentage(1)).withTimeout(3000))));
SmartDashboard.putData(m_chooser);
+
configureBindings();
}
@@ -68,19 +69,20 @@ public class RobotContainer
private void configureBindings()
{
- m_shooter.setDefaultCommand(m_shooter.run(() -> m_shooter.atPercentage(0.0)));
+ m_shooter.setDefaultCommand(m_shooter.run(() -> m_shooter.atPercentage(-0.2)));
m_intake.setDefaultCommand(m_intake.run(() -> m_intake.atPercentage(0.0)));
m_hooks.setDefaultCommand(m_hooks.run(() -> m_hooks.atPercentage(
deadzone(-0.1, 0.1, m_controller2.getRawAxis(4)),
deadzone(-0.1, 0.1, m_controller2.getRawAxis(5)))));
- // m_mech.setDefaultCommands(
- // m_mech.m_arm.run(() -> m_mech.m_arm.incrementAngle(
- // deadzone(-0.05, 0.05, m_controller2.getRawAxis(2)) * 0.3)) ,
- // m_mech.m_chain.run(() -> m_mech.m_chain.atPercentage(
- // m_controller2.getRawAxis(0)
- // * (-0.5) + 0.5))
- // );
+ m_mech.setDefaultCommands(
+ m_mech.m_arm.run(() -> m_mech.m_arm.incrementAngle(
+ deadzone(-0.05, 0.05, m_controller2.getRawAxis(2)) * 0.05)) ,
+ m_mech.m_chain.run(() -> m_mech.m_chain.atPercentage(
+ m_controller2.getRawAxis(0)
+ * (-0.5) + 0.5))
+ );
+
m_mech.setDefaultCommand(m_mech.run(() -> m_mech.toState(MechCmd.MANUAL).execute()));
m_drive.setDefaultCommand(m_drive.run(() -> {
@@ -88,8 +90,8 @@ public class RobotContainer
m_controller1.getRawAxis(2),
m_controller1.getRawAxis(1));
m_drive.tank(
- inputs[0] * Constants.DriveMaxSpeed,
- inputs[1] * Constants.DriveMaxSpeed);
+ -inputs[1] * Constants.DriveMaxSpeed, // reversed inputs
+ -inputs[0] * Constants.DriveMaxSpeed);
}));
@@ -102,12 +104,12 @@ public class RobotContainer
// new Trigger(() -> m_controller.getRawAxis(6) > 0).whileTrue(m_drive.followTrajectory(trajectory));
- new Trigger(() -> m_controller1.getRawAxis(6) > 0).whileTrue(m_intake.run(() -> m_intake.atPercentage(0.3)));
- new Trigger(() -> m_controller1.getRawAxis(4) > 0).whileTrue(m_intake.run(() -> m_intake.shoot()));
- new Trigger(() -> m_controller1.getRawAxis(7) > 0).whileTrue(m_shooter.run(() -> m_shooter.atPercentage(1)));
- new Trigger(() -> m_controller1.getRawAxis(5) > 0).whileTrue(m_intake.run(() -> m_intake.atPercentage(0.6)));
+ new Trigger(() -> m_controller2.getRawButton(1)).whileTrue(m_intake.run(() -> m_intake.atPercentage(-0.1)));
+ new Trigger(() -> m_controller1.getRawAxis(5) > 0).whileTrue(m_intake.run(() -> m_intake.shoot()));
+ new Trigger(() -> m_controller1.getRawAxis(6) > 0).whileTrue(m_shooter.run(() -> m_shooter.atPercentage(1)));
+ new Trigger(() -> m_controller1.getRawAxis(7) > 0).whileTrue(m_intake.run(() -> m_intake.atPercentage(1)));
+ new Trigger(() -> m_controller2.getRawButton(2)).whileTrue(m_intake.run(() -> m_intake.atPercentage(0.2)));
- new Trigger(() -> m_controller2.getRawButton(1)).whileTrue(m_mech.toState(MechCmd.MANUAL));
new Trigger(() -> m_controller2.getRawAxis(6) > 0).whileTrue(m_mech.toState(MechCmd.INTAKE));
new Trigger(() -> m_controller2.getRawAxis(7) > 0).whileTrue(m_mech.toState(MechCmd.DEFAULT));
new Trigger(() -> m_controller2.getRawButton(4)).whileTrue(m_mech.toState(MechCmd.AMP));