[wpilib] Add PS4Controller, remove Hand from GenericHID/XboxController (#3345)

- GenericHID is now concrete, and has only getRawAxis/Button(int) functionality
- getXxx() has been moved into Joystick as that's the only place where it makes sense
- Hand (and therefore getXxx(Hand)) has been removed, replaced by specific getLeft/RightXxx() methods in XboxController and the new PS4Controller class
- C++ ::Button:: and ::Axis:: enums have been converted to identically-namespaced static constexpr ints
This commit is contained in:
Starlight220
2021-08-14 20:00:46 +03:00
committed by GitHub
parent 25f6f478a5
commit 031962608b
82 changed files with 2548 additions and 934 deletions

View File

@@ -4,7 +4,6 @@
package edu.wpi.first.wpilibj.examples.arcadedrivexboxcontroller;
import edu.wpi.first.wpilibj.GenericHID.Hand;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
@@ -25,7 +24,6 @@ public class Robot extends TimedRobot {
// Drive with split arcade drive.
// That means that the Y axis of the left stick moves forward
// and backward, and the X of the right stick turns left and right.
m_robotDrive.arcadeDrive(
m_driverController.getY(Hand.kLeft), m_driverController.getX(Hand.kRight));
m_robotDrive.arcadeDrive(m_driverController.getLeftY(), m_driverController.getRightX());
}
}

View File

@@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj.examples.armbot;
import static edu.wpi.first.wpilibj.XboxController.Button;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.examples.armbot.Constants.OIConstants;
import edu.wpi.first.wpilibj.examples.armbot.subsystems.ArmSubsystem;
@@ -43,14 +42,13 @@ public class RobotContainer {
new RunCommand(
() ->
m_robotDrive.arcadeDrive(
m_driverController.getY(GenericHID.Hand.kLeft),
m_driverController.getX(GenericHID.Hand.kRight)),
m_driverController.getLeftY(), m_driverController.getRightX()),
m_robotDrive));
}
/**
* Use this method to define your button->command mappings. Buttons can be created by
* instantiating a {@link GenericHID} or one of its subclasses ({@link
* instantiating a {@link edu.wpi.first.wpilibj.GenericHID} or one of its subclasses ({@link
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a {@link
* JoystickButton}.
*/
@@ -77,7 +75,7 @@ public class RobotContainer {
new JoystickButton(m_driverController, Button.kY.value).whenPressed(m_robotArm::disable);
// Drive at half speed when the bumper is held
new JoystickButton(m_driverController, Button.kBumperRight.value)
new JoystickButton(m_driverController, Button.kRightBumper.value)
.whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
.whenReleased(() -> m_robotDrive.setMaxOutput(1));
}

View File

@@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj.examples.armbotoffboard;
import static edu.wpi.first.wpilibj.XboxController.Button;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.examples.armbotoffboard.Constants.OIConstants;
import edu.wpi.first.wpilibj.examples.armbotoffboard.subsystems.ArmSubsystem;
@@ -43,14 +42,13 @@ public class RobotContainer {
new RunCommand(
() ->
m_robotDrive.arcadeDrive(
m_driverController.getY(GenericHID.Hand.kLeft),
m_driverController.getX(GenericHID.Hand.kRight)),
m_driverController.getLeftY(), m_driverController.getRightX()),
m_robotDrive));
}
/**
* Use this method to define your button->command mappings. Buttons can be created by
* instantiating a {@link GenericHID} or one of its subclasses ({@link
* instantiating a {@link edu.wpi.first.wpilibj.GenericHID} or one of its subclasses ({@link
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a {@link
* JoystickButton}.
*/
@@ -64,7 +62,7 @@ public class RobotContainer {
.whenPressed(() -> m_robotArm.setGoal(Constants.ArmConstants.kArmOffsetRads), m_robotArm);
// Drive at half speed when the bumper is held
new JoystickButton(m_driverController, Button.kBumperRight.value)
new JoystickButton(m_driverController, Button.kRightBumper.value)
.whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
.whenReleased(() -> m_robotDrive.setMaxOutput(1));
}

View File

@@ -5,7 +5,6 @@
package edu.wpi.first.wpilibj.examples.differentialdrivebot;
import edu.wpi.first.math.filter.SlewRateLimiter;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.XboxController;
@@ -27,16 +26,13 @@ public class Robot extends TimedRobot {
public void teleopPeriodic() {
// Get the x speed. We are inverting this because Xbox controllers return
// negative values when we push forward.
final var xSpeed =
-m_speedLimiter.calculate(m_controller.getY(GenericHID.Hand.kLeft)) * Drivetrain.kMaxSpeed;
final var xSpeed = -m_speedLimiter.calculate(m_controller.getLeftY()) * Drivetrain.kMaxSpeed;
// Get the rate of angular rotation. We are inverting this because we want a
// positive value when we pull to the left (remember, CCW is positive in
// mathematics). Xbox controllers return positive values when you pull to
// the right by default.
final var rot =
-m_rotLimiter.calculate(m_controller.getX(GenericHID.Hand.kRight))
* Drivetrain.kMaxAngularSpeed;
final var rot = -m_rotLimiter.calculate(m_controller.getRightX()) * Drivetrain.kMaxAngularSpeed;
m_drive.drive(xSpeed, rot);
}

View File

@@ -5,7 +5,6 @@
package edu.wpi.first.wpilibj.examples.differentialdriveposeestimator;
import edu.wpi.first.math.filter.SlewRateLimiter;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.XboxController;
@@ -27,16 +26,13 @@ public class Robot extends TimedRobot {
public void teleopPeriodic() {
// Get the x speed. We are inverting this because Xbox controllers return
// negative values when we push forward.
final var xSpeed =
-m_speedLimiter.calculate(m_controller.getY(GenericHID.Hand.kLeft)) * Drivetrain.kMaxSpeed;
final var xSpeed = -m_speedLimiter.calculate(m_controller.getLeftY()) * Drivetrain.kMaxSpeed;
// Get the rate of angular rotation. We are inverting this because we want a
// positive value when we pull to the left (remember, CCW is positive in
// mathematics). Xbox controllers return positive values when you pull to
// the right by default.
final var rot =
-m_rotLimiter.calculate(m_controller.getX(GenericHID.Hand.kRight))
* Drivetrain.kMaxAngularSpeed;
final var rot = -m_rotLimiter.calculate(m_controller.getRightX()) * Drivetrain.kMaxAngularSpeed;
m_drive.drive(xSpeed, rot);
}

View File

@@ -7,7 +7,6 @@ package edu.wpi.first.wpilibj.examples.drivedistanceoffboard;
import static edu.wpi.first.wpilibj.XboxController.Button;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.Constants.DriveConstants;
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.Constants.OIConstants;
@@ -45,14 +44,13 @@ public class RobotContainer {
new RunCommand(
() ->
m_robotDrive.arcadeDrive(
m_driverController.getY(GenericHID.Hand.kLeft),
m_driverController.getX(GenericHID.Hand.kRight)),
m_driverController.getLeftY(), m_driverController.getRightX()),
m_robotDrive));
}
/**
* Use this method to define your button->command mappings. Buttons can be created by
* instantiating a {@link GenericHID} or one of its subclasses ({@link
* instantiating a {@link edu.wpi.first.wpilibj.GenericHID} or one of its subclasses ({@link
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a {@link
* JoystickButton}.
*/
@@ -80,7 +78,7 @@ public class RobotContainer {
.withTimeout(10));
// Drive at half speed when the bumper is held
new JoystickButton(m_driverController, Button.kBumperRight.value)
new JoystickButton(m_driverController, Button.kRightBumper.value)
.whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
.whenReleased(() -> m_robotDrive.setMaxOutput(1));
}

View File

@@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj.examples.frisbeebot;
import static edu.wpi.first.wpilibj.XboxController.Button;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.AutoConstants;
import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.OIConstants;
@@ -68,14 +67,13 @@ public class RobotContainer {
new RunCommand(
() ->
m_robotDrive.arcadeDrive(
m_driverController.getY(GenericHID.Hand.kLeft),
m_driverController.getX(GenericHID.Hand.kRight)),
m_driverController.getLeftY(), m_driverController.getRightX()),
m_robotDrive));
}
/**
* Use this method to define your button->command mappings. Buttons can be created by
* instantiating a {@link GenericHID} or one of its subclasses ({@link
* instantiating a {@link edu.wpi.first.wpilibj.GenericHID} or one of its subclasses ({@link
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a {@link
* edu.wpi.first.wpilibj2.command.button.JoystickButton}.
*/
@@ -102,7 +100,7 @@ public class RobotContainer {
.whenReleased(new InstantCommand(m_shooter::stopFeeder, m_shooter));
// Drive at half speed when the bumper is held
new JoystickButton(m_driverController, Button.kBumperRight.value)
new JoystickButton(m_driverController, Button.kRightBumper.value)
.whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
.whenReleased(() -> m_robotDrive.setMaxOutput(1));
}

View File

@@ -4,9 +4,6 @@
package edu.wpi.first.wpilibj.examples.gearsbot;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.GenericHID.Hand;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.examples.gearsbot.commands.Autonomous;
import edu.wpi.first.wpilibj.examples.gearsbot.commands.CloseClaw;
@@ -39,7 +36,7 @@ public class RobotContainer {
private final Wrist m_wrist = new Wrist();
private final Claw m_claw = new Claw();
private final Joystick m_joystick = new Joystick(0);
private final XboxController m_joystick = new XboxController(0);
private final CommandBase m_autonomousCommand =
new Autonomous(m_drivetrain, m_claw, m_wrist, m_elevator);
@@ -61,8 +58,7 @@ public class RobotContainer {
// Assign default commands
m_drivetrain.setDefaultCommand(
new TankDrive(
() -> m_joystick.getY(Hand.kLeft), () -> m_joystick.getY(Hand.kRight), m_drivetrain));
new TankDrive(m_joystick::getLeftY, m_joystick::getRightY, m_drivetrain));
// Show what command your subsystem is running on the SmartDashboard
SmartDashboard.putData(m_drivetrain);
@@ -76,7 +72,7 @@ public class RobotContainer {
/**
* Use this method to define your button->command mappings. Buttons can be created by
* instantiating a {@link GenericHID} or one of its subclasses ({@link
* instantiating a {@link edu.wpi.first.wpilibj.GenericHID} or one of its subclasses ({@link
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a {@link
* edu.wpi.first.wpilibj2.command.button.JoystickButton}.
*/

View File

@@ -4,11 +4,10 @@
package edu.wpi.first.wpilibj.examples.gyrodrivecommands;
import static edu.wpi.first.wpilibj.XboxController.Button;
import static edu.wpi.first.wpilibj.PS4Controller.Button;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.PS4Controller;
import edu.wpi.first.wpilibj.examples.gyrodrivecommands.Constants.DriveConstants;
import edu.wpi.first.wpilibj.examples.gyrodrivecommands.Constants.OIConstants;
import edu.wpi.first.wpilibj.examples.gyrodrivecommands.commands.TurnToAngle;
@@ -31,7 +30,7 @@ public class RobotContainer {
private final DriveSubsystem m_robotDrive = new DriveSubsystem();
// The driver's controller
XboxController m_driverController = new XboxController(OIConstants.kDriverControllerPort);
PS4Controller m_driverController = new PS4Controller(OIConstants.kDriverControllerPort);
/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {
@@ -46,25 +45,24 @@ public class RobotContainer {
new RunCommand(
() ->
m_robotDrive.arcadeDrive(
m_driverController.getY(GenericHID.Hand.kLeft),
m_driverController.getX(GenericHID.Hand.kRight)),
m_driverController.getLeftY(), m_driverController.getRightX()),
m_robotDrive));
}
/**
* Use this method to define your button->command mappings. Buttons can be created by
* instantiating a {@link GenericHID} or one of its subclasses ({@link
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a {@link
* instantiating a {@link edu.wpi.first.wpilibj.GenericHID} or one of its subclasses ({@link
* edu.wpi.first.wpilibj.Joystick} or {@link PS4Controller}), and then passing it to a {@link
* edu.wpi.first.wpilibj2.command.button.JoystickButton}.
*/
private void configureButtonBindings() {
// Drive at half speed when the right bumper is held
new JoystickButton(m_driverController, Button.kBumperRight.value)
new JoystickButton(m_driverController, Button.kR1.value)
.whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
.whenReleased(() -> m_robotDrive.setMaxOutput(1));
// Stabilize robot to drive straight with gyro when left bumper is held
new JoystickButton(m_driverController, Button.kBumperLeft.value)
new JoystickButton(m_driverController, Button.kL1.value)
.whenHeld(
new PIDCommand(
new PIDController(
@@ -76,18 +74,16 @@ public class RobotContainer {
// Setpoint is 0
0,
// Pipe the output to the turning controls
output ->
m_robotDrive.arcadeDrive(
m_driverController.getY(GenericHID.Hand.kLeft), output),
output -> m_robotDrive.arcadeDrive(m_driverController.getLeftY(), output),
// Require the robot drive
m_robotDrive));
// Turn to 90 degrees when the 'X' button is pressed, with a 5 second timeout
new JoystickButton(m_driverController, Button.kX.value)
new JoystickButton(m_driverController, Button.kCross.value)
.whenPressed(new TurnToAngle(90, m_robotDrive).withTimeout(5));
// Turn to -90 degrees with a profile when the 'A' button is pressed, with a 5 second timeout
new JoystickButton(m_driverController, Button.kA.value)
// Turn to -90 degrees with a profile when the Circle button is pressed, with a 5 second timeout
new JoystickButton(m_driverController, Button.kCircle.value)
.whenPressed(new TurnToAngleProfiled(-90, m_robotDrive).withTimeout(5));
}

View File

@@ -4,10 +4,9 @@
package edu.wpi.first.wpilibj.examples.hatchbotinlined;
import static edu.wpi.first.wpilibj.XboxController.Button;
import static edu.wpi.first.wpilibj.PS4Controller.Button;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.PS4Controller;
import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.AutoConstants;
import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.OIConstants;
import edu.wpi.first.wpilibj.examples.hatchbotinlined.commands.ComplexAutoCommand;
@@ -55,7 +54,7 @@ public class RobotContainer {
SendableChooser<Command> m_chooser = new SendableChooser<>();
// The driver's controller
XboxController m_driverController = new XboxController(OIConstants.kDriverControllerPort);
PS4Controller m_driverController = new PS4Controller(OIConstants.kDriverControllerPort);
/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {
@@ -70,8 +69,7 @@ public class RobotContainer {
new RunCommand(
() ->
m_robotDrive.arcadeDrive(
m_driverController.getY(GenericHID.Hand.kLeft),
m_driverController.getX(GenericHID.Hand.kRight)),
m_driverController.getLeftY(), m_driverController.getRightX()),
m_robotDrive));
// Add commands to the autonomous command chooser
@@ -84,19 +82,19 @@ public class RobotContainer {
/**
* Use this method to define your button->command mappings. Buttons can be created by
* instantiating a {@link GenericHID} or one of its subclasses ({@link
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a {@link
* instantiating a {@link edu.wpi.first.wpilibj.GenericHID} or one of its subclasses ({@link
* edu.wpi.first.wpilibj.Joystick} or {@link PS4Controller}), and then passing it to a {@link
* edu.wpi.first.wpilibj2.command.button.JoystickButton}.
*/
private void configureButtonBindings() {
// Grab the hatch when the 'A' button is pressed.
new JoystickButton(m_driverController, Button.kA.value)
// Grab the hatch when the Circle button is pressed.
new JoystickButton(m_driverController, Button.kCircle.value)
.whenPressed(new InstantCommand(m_hatchSubsystem::grabHatch, m_hatchSubsystem));
// Release the hatch when the 'B' button is pressed.
new JoystickButton(m_driverController, Button.kB.value)
// Release the hatch when the Square button is pressed.
new JoystickButton(m_driverController, Button.kSquare.value)
.whenPressed(new InstantCommand(m_hatchSubsystem::releaseHatch, m_hatchSubsystem));
// While holding the shoulder button, drive at half speed
new JoystickButton(m_driverController, Button.kBumperRight.value)
// While holding R1, drive at half speed
new JoystickButton(m_driverController, Button.kR1.value)
.whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
.whenReleased(() -> m_robotDrive.setMaxOutput(1));
}

View File

@@ -6,7 +6,6 @@ package edu.wpi.first.wpilibj.examples.hatchbottraditional;
import static edu.wpi.first.wpilibj.XboxController.Button;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.examples.hatchbottraditional.Constants.AutoConstants;
import edu.wpi.first.wpilibj.examples.hatchbottraditional.Constants.OIConstants;
@@ -61,9 +60,7 @@ public class RobotContainer {
// A split-stick arcade command, with forward/backward controlled by the left
// hand, and turning controlled by the right.
new DefaultDrive(
m_robotDrive,
() -> m_driverController.getY(GenericHID.Hand.kLeft),
() -> m_driverController.getX(GenericHID.Hand.kRight)));
m_robotDrive, m_driverController::getLeftY, m_driverController::getRightX));
// Add commands to the autonomous command chooser
m_chooser.setDefaultOption("Simple Auto", m_simpleAuto);
@@ -75,7 +72,7 @@ public class RobotContainer {
/**
* Use this method to define your button->command mappings. Buttons can be created by
* instantiating a {@link GenericHID} or one of its subclasses ({@link
* instantiating a {@link edu.wpi.first.wpilibj.GenericHID} or one of its subclasses ({@link
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a {@link
* edu.wpi.first.wpilibj2.command.button.JoystickButton}.
*/
@@ -87,7 +84,7 @@ public class RobotContainer {
new JoystickButton(m_driverController, Button.kB.value)
.whenPressed(new ReleaseHatch(m_hatchSubsystem));
// While holding the shoulder button, drive at half speed
new JoystickButton(m_driverController, Button.kBumperRight.value)
new JoystickButton(m_driverController, Button.kRightBumper.value)
.whenHeld(new HalveDriveSpeed(m_robotDrive));
}

View File

@@ -5,7 +5,6 @@
package edu.wpi.first.wpilibj.examples.mecanumbot;
import edu.wpi.first.math.filter.SlewRateLimiter;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.XboxController;
@@ -32,22 +31,18 @@ public class Robot extends TimedRobot {
private void driveWithJoystick(boolean fieldRelative) {
// Get the x speed. We are inverting this because Xbox controllers return
// negative values when we push forward.
final var xSpeed =
-m_xspeedLimiter.calculate(m_controller.getY(GenericHID.Hand.kLeft)) * Drivetrain.kMaxSpeed;
final var xSpeed = -m_xspeedLimiter.calculate(m_controller.getLeftY()) * Drivetrain.kMaxSpeed;
// Get the y speed or sideways/strafe speed. We are inverting this because
// we want a positive value when we pull to the left. Xbox controllers
// return positive values when you pull to the right by default.
final var ySpeed =
-m_yspeedLimiter.calculate(m_controller.getX(GenericHID.Hand.kLeft)) * Drivetrain.kMaxSpeed;
final var ySpeed = -m_yspeedLimiter.calculate(m_controller.getLeftX()) * Drivetrain.kMaxSpeed;
// Get the rate of angular rotation. We are inverting this because we want a
// positive value when we pull to the left (remember, CCW is positive in
// mathematics). Xbox controllers return positive values when you pull to
// the right by default.
final var rot =
-m_rotLimiter.calculate(m_controller.getX(GenericHID.Hand.kRight))
* Drivetrain.kMaxAngularSpeed;
final var rot = -m_rotLimiter.calculate(m_controller.getRightX()) * Drivetrain.kMaxAngularSpeed;
m_mecanum.drive(xSpeed, ySpeed, rot, fieldRelative);
}

View File

@@ -12,7 +12,6 @@ import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.trajectory.Trajectory;
import edu.wpi.first.math.trajectory.TrajectoryConfig;
import edu.wpi.first.math.trajectory.TrajectoryGenerator;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.XboxController.Button;
import edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.Constants.AutoConstants;
@@ -51,22 +50,22 @@ public class RobotContainer {
new RunCommand(
() ->
m_robotDrive.drive(
m_driverController.getY(GenericHID.Hand.kLeft),
m_driverController.getX(GenericHID.Hand.kRight),
m_driverController.getX(GenericHID.Hand.kLeft),
m_driverController.getLeftY(),
m_driverController.getRightX(),
m_driverController.getLeftX(),
false),
m_robotDrive));
}
/**
* Use this method to define your button->command mappings. Buttons can be created by
* instantiating a {@link GenericHID} or one of its subclasses ({@link
* instantiating a {@link edu.wpi.first.wpilibj.GenericHID} or one of its subclasses ({@link
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then calling passing it to a
* {@link JoystickButton}.
*/
private void configureButtonBindings() {
// Drive at half speed when the right bumper is held
new JoystickButton(m_driverController, Button.kBumperRight.value)
new JoystickButton(m_driverController, Button.kRightBumper.value)
.whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
.whenReleased(() -> m_robotDrive.setMaxOutput(1));
}

View File

@@ -5,7 +5,6 @@
package edu.wpi.first.wpilibj.examples.mecanumdriveposeestimator;
import edu.wpi.first.math.filter.SlewRateLimiter;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.XboxController;
@@ -32,22 +31,18 @@ public class Robot extends TimedRobot {
private void driveWithJoystick(boolean fieldRelative) {
// Get the x speed. We are inverting this because Xbox controllers return
// negative values when we push forward.
final var xSpeed =
-m_xspeedLimiter.calculate(m_controller.getY(GenericHID.Hand.kLeft)) * Drivetrain.kMaxSpeed;
final var xSpeed = -m_xspeedLimiter.calculate(m_controller.getLeftY()) * Drivetrain.kMaxSpeed;
// Get the y speed or sideways/strafe speed. We are inverting this because
// we want a positive value when we pull to the left. Xbox controllers
// return positive values when you pull to the right by default.
final var ySpeed =
-m_yspeedLimiter.calculate(m_controller.getX(GenericHID.Hand.kLeft)) * Drivetrain.kMaxSpeed;
final var ySpeed = -m_yspeedLimiter.calculate(m_controller.getLeftX()) * Drivetrain.kMaxSpeed;
// Get the rate of angular rotation. We are inverting this because we want a
// positive value when we pull to the left (remember, CCW is positive in
// mathematics). Xbox controllers return positive values when you pull to
// the right by default.
final var rot =
-m_rotLimiter.calculate(m_controller.getX(GenericHID.Hand.kRight))
* Drivetrain.kMaxAngularSpeed;
final var rot = -m_rotLimiter.calculate(m_controller.getRightX()) * Drivetrain.kMaxAngularSpeed;
m_mecanum.drive(xSpeed, ySpeed, rot, fieldRelative);
}

View File

@@ -4,12 +4,12 @@
package edu.wpi.first.wpilibj.examples.pacgoat.triggers;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.buttons.Trigger;
/** A custom button that is triggered when TWO buttons on a Joystick are simultaneously pressed. */
public class DoubleButton extends Trigger {
private final Joystick m_joy;
private final GenericHID m_joy;
private final int m_button1;
private final int m_button2;
@@ -20,7 +20,7 @@ public class DoubleButton extends Trigger {
* @param button1 The first button
* @param button2 The second button
*/
public DoubleButton(Joystick joy, int button1, int button2) {
public DoubleButton(GenericHID joy, int button1, int button2) {
this.m_joy = joy;
this.m_button1 = button1;
this.m_button2 = button2;

View File

@@ -16,7 +16,6 @@ import edu.wpi.first.math.trajectory.Trajectory;
import edu.wpi.first.math.trajectory.TrajectoryConfig;
import edu.wpi.first.math.trajectory.TrajectoryGenerator;
import edu.wpi.first.math.trajectory.constraint.DifferentialDriveVoltageConstraint;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.examples.ramsetecommand.Constants.AutoConstants;
import edu.wpi.first.wpilibj.examples.ramsetecommand.Constants.DriveConstants;
@@ -54,20 +53,19 @@ public class RobotContainer {
new RunCommand(
() ->
m_robotDrive.arcadeDrive(
m_driverController.getY(GenericHID.Hand.kLeft),
m_driverController.getX(GenericHID.Hand.kRight)),
m_driverController.getLeftY(), m_driverController.getRightX()),
m_robotDrive));
}
/**
* Use this method to define your button->command mappings. Buttons can be created by
* instantiating a {@link GenericHID} or one of its subclasses ({@link
* instantiating a {@link edu.wpi.first.wpilibj.GenericHID} or one of its subclasses ({@link
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then calling passing it to a
* {@link JoystickButton}.
*/
private void configureButtonBindings() {
// Drive at half speed when the right bumper is held
new JoystickButton(m_driverController, Button.kBumperRight.value)
new JoystickButton(m_driverController, Button.kRightBumper.value)
.whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
.whenReleased(() -> m_robotDrive.setMaxOutput(1));
}

View File

@@ -13,7 +13,6 @@ import edu.wpi.first.math.trajectory.Trajectory;
import edu.wpi.first.math.trajectory.TrajectoryConfig;
import edu.wpi.first.math.trajectory.TrajectoryGenerator;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.XboxController;
@@ -96,16 +95,13 @@ public class Robot extends TimedRobot {
public void teleopPeriodic() {
// Get the x speed. We are inverting this because Xbox controllers return
// negative values when we push forward.
final var xSpeed =
-m_speedLimiter.calculate(m_controller.getY(GenericHID.Hand.kLeft)) * Drivetrain.kMaxSpeed;
final var xSpeed = -m_speedLimiter.calculate(m_controller.getLeftY()) * Drivetrain.kMaxSpeed;
// Get the rate of angular rotation. We are inverting this because we want a
// positive value when we pull to the left (remember, CCW is positive in
// mathematics). Xbox controllers return positive values when you pull to
// the right by default.
final var rot =
-m_rotLimiter.calculate(m_controller.getX(GenericHID.Hand.kRight))
* Drivetrain.kMaxAngularSpeed;
final var rot = -m_rotLimiter.calculate(m_controller.getRightX()) * Drivetrain.kMaxAngularSpeed;
m_drive.drive(xSpeed, rot);
}

View File

@@ -12,7 +12,6 @@ import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.math.trajectory.Trajectory;
import edu.wpi.first.math.trajectory.TrajectoryConfig;
import edu.wpi.first.math.trajectory.TrajectoryGenerator;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.XboxController;
@@ -70,16 +69,13 @@ public class Robot extends TimedRobot {
public void teleopPeriodic() {
// Get the x speed. We are inverting this because Xbox controllers return
// negative values when we push forward.
double xSpeed =
-m_speedLimiter.calculate(m_controller.getY(GenericHID.Hand.kLeft)) * Drivetrain.kMaxSpeed;
double xSpeed = -m_speedLimiter.calculate(m_controller.getLeftY()) * Drivetrain.kMaxSpeed;
// Get the rate of angular rotation. We are inverting this because we want a
// positive value when we pull to the left (remember, CCW is positive in
// mathematics). Xbox controllers return positive values when you pull to
// the right by default.
double rot =
-m_rotLimiter.calculate(m_controller.getX(GenericHID.Hand.kRight))
* Drivetrain.kMaxAngularSpeed;
double rot = -m_rotLimiter.calculate(m_controller.getRightX()) * Drivetrain.kMaxAngularSpeed;
m_drive.drive(xSpeed, rot);
}

View File

@@ -14,7 +14,6 @@ import edu.wpi.first.math.trajectory.Trajectory;
import edu.wpi.first.math.trajectory.TrajectoryConfig;
import edu.wpi.first.math.trajectory.TrajectoryGenerator;
import edu.wpi.first.math.trajectory.constraint.DifferentialDriveVoltageConstraint;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.XboxController.Button;
import edu.wpi.first.wpilibj.examples.statespacedifferentialdrivesimulation.subsystems.DriveSubsystem;
@@ -51,20 +50,19 @@ public class RobotContainer {
new RunCommand(
() ->
m_robotDrive.arcadeDrive(
-m_driverController.getY(GenericHID.Hand.kRight),
m_driverController.getX(GenericHID.Hand.kLeft)),
-m_driverController.getRightY(), m_driverController.getLeftX()),
m_robotDrive));
}
/**
* Use this method to define your button->command mappings. Buttons can be created by
* instantiating a {@link GenericHID} or one of its subclasses ({@link
* instantiating a {@link edu.wpi.first.wpilibj.GenericHID} or one of its subclasses ({@link
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then calling passing it to a
* {@link JoystickButton}.
*/
private void configureButtonBindings() {
// Drive at half speed when the right bumper is held
new JoystickButton(m_driverController, Button.kBumperRight.value)
new JoystickButton(m_driverController, Button.kRightBumper.value)
.whenPressed(() -> m_robotDrive.setMaxOutput(0.5))
.whenReleased(() -> m_robotDrive.setMaxOutput(1));
}

View File

@@ -5,7 +5,6 @@
package edu.wpi.first.wpilibj.examples.swervebot;
import edu.wpi.first.math.filter.SlewRateLimiter;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.XboxController;
@@ -32,22 +31,18 @@ public class Robot extends TimedRobot {
private void driveWithJoystick(boolean fieldRelative) {
// Get the x speed. We are inverting this because Xbox controllers return
// negative values when we push forward.
final var xSpeed =
-m_xspeedLimiter.calculate(m_controller.getY(GenericHID.Hand.kLeft)) * Drivetrain.kMaxSpeed;
final var xSpeed = -m_xspeedLimiter.calculate(m_controller.getLeftY()) * Drivetrain.kMaxSpeed;
// Get the y speed or sideways/strafe speed. We are inverting this because
// we want a positive value when we pull to the left. Xbox controllers
// return positive values when you pull to the right by default.
final var ySpeed =
-m_yspeedLimiter.calculate(m_controller.getX(GenericHID.Hand.kLeft)) * Drivetrain.kMaxSpeed;
final var ySpeed = -m_yspeedLimiter.calculate(m_controller.getLeftX()) * Drivetrain.kMaxSpeed;
// Get the rate of angular rotation. We are inverting this because we want a
// positive value when we pull to the left (remember, CCW is positive in
// mathematics). Xbox controllers return positive values when you pull to
// the right by default.
final var rot =
-m_rotLimiter.calculate(m_controller.getX(GenericHID.Hand.kRight))
* Drivetrain.kMaxAngularSpeed;
final var rot = -m_rotLimiter.calculate(m_controller.getRightX()) * Drivetrain.kMaxAngularSpeed;
m_swerve.drive(xSpeed, ySpeed, rot, fieldRelative);
}

View File

@@ -12,7 +12,6 @@ import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.trajectory.Trajectory;
import edu.wpi.first.math.trajectory.TrajectoryConfig;
import edu.wpi.first.math.trajectory.TrajectoryGenerator;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.examples.swervecontrollercommand.Constants.AutoConstants;
import edu.wpi.first.wpilibj.examples.swervecontrollercommand.Constants.DriveConstants;
@@ -50,16 +49,16 @@ public class RobotContainer {
new RunCommand(
() ->
m_robotDrive.drive(
m_driverController.getY(GenericHID.Hand.kLeft),
m_driverController.getX(GenericHID.Hand.kRight),
m_driverController.getX(GenericHID.Hand.kLeft),
m_driverController.getLeftY(),
m_driverController.getRightX(),
m_driverController.getLeftX(),
false),
m_robotDrive));
}
/**
* Use this method to define your button->command mappings. Buttons can be created by
* instantiating a {@link GenericHID} or one of its subclasses ({@link
* instantiating a {@link edu.wpi.first.wpilibj.GenericHID} or one of its subclasses ({@link
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then calling passing it to a
* {@link JoystickButton}.
*/

View File

@@ -5,7 +5,6 @@
package edu.wpi.first.wpilibj.examples.swervedriveposeestimator;
import edu.wpi.first.math.filter.SlewRateLimiter;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.XboxController;
@@ -32,22 +31,18 @@ public class Robot extends TimedRobot {
private void driveWithJoystick(boolean fieldRelative) {
// Get the x speed. We are inverting this because Xbox controllers return
// negative values when we push forward.
final var xSpeed =
-m_xspeedLimiter.calculate(m_controller.getY(GenericHID.Hand.kLeft)) * Drivetrain.kMaxSpeed;
final var xSpeed = -m_xspeedLimiter.calculate(m_controller.getLeftY()) * Drivetrain.kMaxSpeed;
// Get the y speed or sideways/strafe speed. We are inverting this because
// we want a positive value when we pull to the left. Xbox controllers
// return positive values when you pull to the right by default.
final var ySpeed =
-m_yspeedLimiter.calculate(m_controller.getX(GenericHID.Hand.kLeft)) * Drivetrain.kMaxSpeed;
final var ySpeed = -m_yspeedLimiter.calculate(m_controller.getLeftX()) * Drivetrain.kMaxSpeed;
// Get the rate of angular rotation. We are inverting this because we want a
// positive value when we pull to the left (remember, CCW is positive in
// mathematics). Xbox controllers return positive values when you pull to
// the right by default.
final var rot =
-m_rotLimiter.calculate(m_controller.getX(GenericHID.Hand.kRight))
* Drivetrain.kMaxAngularSpeed;
final var rot = -m_rotLimiter.calculate(m_controller.getRightX()) * Drivetrain.kMaxAngularSpeed;
m_swerve.drive(xSpeed, ySpeed, rot, fieldRelative);
}

View File

@@ -4,7 +4,6 @@
package edu.wpi.first.wpilibj.examples.tankdrivexboxcontroller;
import edu.wpi.first.wpilibj.GenericHID.Hand;
import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
@@ -34,7 +33,6 @@ public class Robot extends TimedRobot {
// That means that the Y axis of the left stick moves the left side
// of the robot forward and backward, and the Y axis of the right stick
// moves the right side of the robot forward and backward.
m_robotDrive.tankDrive(
m_driverController.getY(Hand.kLeft), m_driverController.getY(Hand.kRight));
m_robotDrive.tankDrive(m_driverController.getLeftY(), m_driverController.getRightY());
}
}

View File

@@ -4,7 +4,6 @@
package edu.wpi.first.wpilibj.templates.romicommandbased;
import edu.wpi.first.wpilibj.GenericHID;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.templates.romicommandbased.commands.ExampleCommand;
import edu.wpi.first.wpilibj.templates.romicommandbased.subsystems.RomiDrivetrain;
@@ -30,7 +29,7 @@ public class RobotContainer {
/**
* Use this method to define your button->command mappings. Buttons can be created by
* instantiating a {@link GenericHID} or one of its subclasses ({@link
* instantiating a {@link edu.wpi.first.wpilibj.GenericHID} or one of its subclasses ({@link
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a {@link
* edu.wpi.first.wpilibj2.command.button.JoystickButton}.
*/