diff options
author | kartofen <mladenovnasko0@gmail.com> | 2024-02-24 14:05:20 +0200 |
---|---|---|
committer | kartofen <mladenovnasko0@gmail.com> | 2024-02-24 14:05:20 +0200 |
commit | b929a1d34690d3d7fed6686459ff803962ce907f (patch) | |
tree | 1f6747fface1dc7e2dc0f19d762d37a54ba8edf0 /src/main/java/frc/robot/RobotContainer.java | |
parent | c6d58f5fafb56f8ae295366eadbc247e0217acc8 (diff) |
controlle change
Diffstat (limited to 'src/main/java/frc/robot/RobotContainer.java')
-rw-r--r-- | src/main/java/frc/robot/RobotContainer.java | 45 |
1 files changed, 10 insertions, 35 deletions
diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 3580633..ed6afe9 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -4,13 +4,10 @@ package frc.robot; -import javax.smartcardio.CommandAPDU; - import edu.wpi.first.math.geometry.Pose2d; -import edu.wpi.first.wpilibj.GenericHID; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; -import edu.wpi.first.wpilibj2.command.button.Trigger; +import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine; import frc.robot.subsystems.Drivetrain; @@ -18,7 +15,7 @@ public class RobotContainer { private final Drivetrain m_drive = new Drivetrain(); - private final GenericHID m_controller = Constants.controller; + private final CommandXboxController m_controller = Constants.controller; public RobotContainer() { @@ -34,59 +31,37 @@ public class RobotContainer { m_drive.setDefaultCommand(m_drive.run(() -> m_drive.tank( - deadzone(-0.09, 0.09, m_controller.getRawAxis(1)) * Constants.DriveMaxSpeed, - deadzone(-0.09, 0.09, m_controller.getRawAxis(3)) * Constants.DriveMaxSpeed + deadzone(-0.09, 0.09, m_controller.getLeftY()) * Constants.DriveMaxSpeed, + deadzone(-0.09, 0.09, m_controller.getRightY()) * Constants.DriveMaxSpeed ))); // debug controls - new Trigger(() -> m_controller.getRawButton(1)).onTrue(Commands.runOnce(() -> { + m_controller.a().onTrue(Commands.runOnce(() -> { Pose2d pose = m_drive.pose2d(); System.out.println("x: " + pose.getX() +" y: "+ pose.getY()); System.out.println("yaw: " + Constants.gyro.toRotation2d().getDegrees()); })); - new Trigger(() -> m_controller.getRawButton(2)).onTrue(Commands.runOnce(() -> { + m_controller.b().onTrue(Commands.runOnce(() -> { System.out.println("Reset"); m_drive.reset(); })); - - new Trigger(() -> m_controller.getRawButton(3) && m_controller.getRawButton(8)) + m_controller.x().and(m_controller.leftBumper()) .onTrue(Commands.sequence(Commands.runOnce(() -> System.out.println("Quasistatic Forward")), m_drive.sysIdQausistatic(SysIdRoutine.Direction.kForward))); - new Trigger(() -> m_controller.getRawButton(3) && m_controller.getRawButton(7)) + m_controller.x().and(m_controller.rightBumper()) .onTrue(Commands.sequence(Commands.runOnce(() -> System.out.println("Quasistatic Reverse")), m_drive.sysIdQausistatic(SysIdRoutine.Direction.kReverse))); - new Trigger(() -> m_controller.getRawButton(4) && m_controller.getRawButton(8)) + m_controller.y().and(m_controller.leftBumper()) .onTrue(Commands.sequence(Commands.runOnce(() -> System.out.println("Dynamic Forward")), m_drive.sysIdQausistatic(SysIdRoutine.Direction.kForward))); - new Trigger(() -> m_controller.getRawButton(4) && m_controller.getRawButton(7)) + m_controller.y().and(m_controller.rightBumper()) .onTrue(Commands.sequence(Commands.runOnce(() -> System.out.println("Dynamic Reverse")), m_drive.sysIdQausistatic(SysIdRoutine.Direction.kReverse))); - - // new Trigger(() -> m_controller.getRawButton(3)).onTrue(Commands.runOnce(() -> { - // System.out.println("Running Quasistatis routine"); - // if(m_controller.getRawButton(8)) { - // System.out.println("Reverse"); - // Commands.sequence(m_drive.sysIdQausistatic(SysIdRoutine.Direction.kReverse)); - // } else { - // System.out.println("Forward"); - // Commands.sequence(m_drive.sysIdQausistatic(SysIdRoutine.Direction.kForward)); - // } - // })); - // new Trigger(() -> m_controller.getRawButton(4) && m_controller()).onTrue(() -> { - // System.out.println("Running Dynamic routine"); - // if(m_controller.getRawButton(8)) { - // System.out.println("Reverse"); - // return m_drive.sysIdDynamic(SysIdRoutine.Direction.kReverse); - // } else { - // System.out.println("Forward"); - // return m_drive.sysIdDynamic(SysIdRoutine.Direction.kForward); - // } - // }()); } public Command getAutonomousCommand() |