mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[wpilib] Prefix all NI DS specific controller classes (#8596)
Easier then the last one that put everything in a sub namespace. By prefixing the name less things break, and intellisense will be less confusing to new users during the transition.
This commit is contained in:
@@ -3,13 +3,13 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include "wpi/drive/DifferentialDrive.hpp"
|
||||
#include "wpi/driverstation/XboxController.hpp"
|
||||
#include "wpi/driverstation/Gamepad.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/hardware/motor/PWMSparkMax.hpp"
|
||||
|
||||
/**
|
||||
* This is a demo program showing the use of the DifferentialDrive class.
|
||||
* Runs the motors with split arcade steering and an Xbox controller.
|
||||
* Runs the motors with split arcade steering and a Gamepad.
|
||||
*/
|
||||
class Robot : public wpi::TimedRobot {
|
||||
wpi::PWMSparkMax m_leftMotor{0};
|
||||
@@ -17,7 +17,7 @@ class Robot : public wpi::TimedRobot {
|
||||
wpi::DifferentialDrive m_robotDrive{
|
||||
[&](double output) { m_leftMotor.Set(output); },
|
||||
[&](double output) { m_rightMotor.Set(output); }};
|
||||
wpi::XboxController m_driverController{0};
|
||||
wpi::Gamepad m_driverController{0};
|
||||
|
||||
public:
|
||||
Robot() {
|
||||
@@ -3,7 +3,7 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include "Drivetrain.hpp"
|
||||
#include "wpi/driverstation/XboxController.hpp"
|
||||
#include "wpi/driverstation/Gamepad.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/math/filter/SlewRateLimiter.hpp"
|
||||
|
||||
@@ -15,14 +15,14 @@ class Robot : public wpi::TimedRobot {
|
||||
}
|
||||
|
||||
void TeleopPeriodic() override {
|
||||
// Get the x speed. We are inverting this because Xbox controllers return
|
||||
// Get the x speed. We are inverting this because gamepads return
|
||||
// negative values when we push forward.
|
||||
const auto 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
|
||||
// mathematics). Gamepads return positive values when you pull to
|
||||
// the right by default.
|
||||
const auto rot = -m_rotLimiter.Calculate(m_controller.GetRightX()) *
|
||||
Drivetrain::kMaxAngularSpeed;
|
||||
@@ -31,7 +31,7 @@ class Robot : public wpi::TimedRobot {
|
||||
}
|
||||
|
||||
private:
|
||||
wpi::XboxController m_controller{0};
|
||||
wpi::Gamepad m_controller{0};
|
||||
|
||||
// Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0
|
||||
// to 1.
|
||||
|
||||
@@ -3,7 +3,7 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include "Drivetrain.hpp"
|
||||
#include "wpi/driverstation/XboxController.hpp"
|
||||
#include "wpi/driverstation/Gamepad.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/math/filter/SlewRateLimiter.hpp"
|
||||
|
||||
@@ -17,14 +17,14 @@ class Robot : public wpi::TimedRobot {
|
||||
void RobotPeriodic() override { m_drive.Periodic(); }
|
||||
|
||||
void TeleopPeriodic() override {
|
||||
// Get the x speed. We are inverting this because Xbox controllers return
|
||||
// Get the x speed. We are inverting this because gamepads return
|
||||
// negative values when we push forward.
|
||||
const auto 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
|
||||
// mathematics). Gamepads return positive values when you pull to
|
||||
// the right by default.
|
||||
const auto rot = -m_rotLimiter.Calculate(m_controller.GetRightX()) *
|
||||
Drivetrain::kMaxAngularSpeed;
|
||||
@@ -35,7 +35,7 @@ class Robot : public wpi::TimedRobot {
|
||||
void SimulationPeriodic() override { m_drive.SimulationPeriodic(); }
|
||||
|
||||
private:
|
||||
wpi::XboxController m_controller{0};
|
||||
wpi::Gamepad m_controller{0};
|
||||
|
||||
// Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0
|
||||
// to 1.
|
||||
|
||||
@@ -25,18 +25,18 @@ void RobotContainer::ConfigureButtonBindings() {
|
||||
// Configure your button bindings here
|
||||
|
||||
// While holding the shoulder button, drive at half speed
|
||||
m_driverController.RightBumper()
|
||||
m_driverController.RightShoulder()
|
||||
.OnTrue(m_driveHalfSpeed.get())
|
||||
.OnFalse(m_driveFullSpeed.get());
|
||||
|
||||
// Drive forward by 3 meters when the 'A' button is pressed, with a timeout of
|
||||
// 10 seconds
|
||||
m_driverController.A().OnTrue(
|
||||
// Drive forward by 3 meters when the 'South Face' button is pressed, with a
|
||||
// timeout of 10 seconds
|
||||
m_driverController.SouthFace().OnTrue(
|
||||
m_drive.ProfiledDriveDistance(3_m).WithTimeout(10_s));
|
||||
|
||||
// Do the same thing as above when the 'B' button is pressed, but without
|
||||
// resetting the encoders
|
||||
m_driverController.B().OnTrue(
|
||||
// Do the same thing as above when the 'East Face' button is pressed, but
|
||||
// without resetting the encoders
|
||||
m_driverController.EastFace().OnTrue(
|
||||
m_drive.DynamicProfiledDriveDistance(3_m).WithTimeout(10_s));
|
||||
}
|
||||
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
#include "wpi/commands2/Command.hpp"
|
||||
#include "wpi/commands2/CommandPtr.hpp"
|
||||
#include "wpi/commands2/Commands.hpp"
|
||||
#include "wpi/commands2/button/CommandXboxController.hpp"
|
||||
#include "wpi/commands2/button/CommandGamepad.hpp"
|
||||
|
||||
/**
|
||||
* This class is where the bulk of the robot should be declared. Since
|
||||
@@ -26,7 +26,7 @@ class RobotContainer {
|
||||
|
||||
private:
|
||||
// The driver's controller
|
||||
wpi::cmd::CommandXboxController m_driverController{
|
||||
wpi::cmd::CommandGamepad m_driverController{
|
||||
OIConstants::kDriverControllerPort};
|
||||
|
||||
// The robot's subsystems and commands are defined here...
|
||||
|
||||
@@ -3,7 +3,7 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include "wpi/drive/DifferentialDrive.hpp"
|
||||
#include "wpi/driverstation/XboxController.hpp"
|
||||
#include "wpi/driverstation/Gamepad.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/hardware/motor/PWMSparkMax.hpp"
|
||||
#include "wpi/system/Timer.hpp"
|
||||
@@ -55,7 +55,7 @@ class Robot : public wpi::TimedRobot {
|
||||
[&](double output) { m_left.Set(output); },
|
||||
[&](double output) { m_right.Set(output); }};
|
||||
|
||||
wpi::XboxController m_controller{0};
|
||||
wpi::Gamepad m_controller{0};
|
||||
wpi::Timer m_timer;
|
||||
};
|
||||
|
||||
|
||||
@@ -35,12 +35,12 @@ RobotContainer::RobotContainer() {
|
||||
void RobotContainer::ConfigureButtonBindings() {
|
||||
// Configure your button bindings here
|
||||
|
||||
// Grab the hatch when the 'Circle' button is pressed.
|
||||
m_driverController.Circle().OnTrue(m_hatch.GrabHatchCommand());
|
||||
// Release the hatch when the 'Square' button is pressed.
|
||||
m_driverController.Square().OnTrue(m_hatch.ReleaseHatchCommand());
|
||||
// While holding R1, drive at half speed
|
||||
m_driverController.R1()
|
||||
// Grab the hatch when the 'East Face' button is pressed.
|
||||
m_driverController.EastFace().OnTrue(m_hatch.GrabHatchCommand());
|
||||
// Release the hatch when the 'West Face' button is pressed.
|
||||
m_driverController.WestFace().OnTrue(m_hatch.ReleaseHatchCommand());
|
||||
// While holding Right Bumper, drive at half speed
|
||||
m_driverController.RightShoulder()
|
||||
.OnTrue(wpi::cmd::cmd::RunOnce([this] { m_drive.SetMaxOutput(0.5); }, {}))
|
||||
.OnFalse(
|
||||
wpi::cmd::cmd::RunOnce([this] { m_drive.SetMaxOutput(1.0); }, {}));
|
||||
|
||||
@@ -10,7 +10,7 @@
|
||||
#include "subsystems/HatchSubsystem.hpp"
|
||||
#include "wpi/commands2/Command.hpp"
|
||||
#include "wpi/commands2/Commands.hpp"
|
||||
#include "wpi/commands2/button/CommandPS4Controller.hpp"
|
||||
#include "wpi/commands2/button/CommandGamepad.hpp"
|
||||
#include "wpi/smartdashboard/SendableChooser.hpp"
|
||||
|
||||
namespace ac = AutoConstants;
|
||||
@@ -30,7 +30,7 @@ class RobotContainer {
|
||||
|
||||
private:
|
||||
// The driver's controller
|
||||
wpi::cmd::CommandPS4Controller m_driverController{
|
||||
wpi::cmd::CommandGamepad m_driverController{
|
||||
OIConstants::kDriverControllerPort};
|
||||
|
||||
// The robot's subsystems and commands are defined here...
|
||||
|
||||
@@ -39,15 +39,16 @@ void RobotContainer::ConfigureButtonBindings() {
|
||||
// NOTE: since we're binding a CommandPtr, command ownership here is moved to
|
||||
// the scheduler thus, no memory leaks!
|
||||
|
||||
// Grab the hatch when the 'A' button is pressed.
|
||||
wpi::cmd::JoystickButton(&m_driverController, wpi::XboxController::Button::kA)
|
||||
// Grab the hatch when the 'South Face' button is pressed.
|
||||
wpi::cmd::JoystickButton(&m_driverController,
|
||||
wpi::Gamepad::Button::kSouthFace)
|
||||
.OnTrue(GrabHatch(&m_hatch).ToPtr());
|
||||
// Release the hatch when the 'B' button is pressed.
|
||||
wpi::cmd::JoystickButton(&m_driverController, wpi::XboxController::Button::kB)
|
||||
// Release the hatch when the 'East Face' button is pressed.
|
||||
wpi::cmd::JoystickButton(&m_driverController, wpi::Gamepad::Button::kEastFace)
|
||||
.OnTrue(ReleaseHatch(&m_hatch).ToPtr());
|
||||
// While holding the shoulder button, drive at half speed
|
||||
wpi::cmd::JoystickButton(&m_driverController,
|
||||
wpi::XboxController::Button::kRightBumper)
|
||||
wpi::Gamepad::Button::kRightShoulder)
|
||||
.WhileTrue(HalveDriveSpeed(&m_drive).ToPtr());
|
||||
}
|
||||
|
||||
|
||||
@@ -11,7 +11,7 @@
|
||||
#include "subsystems/DriveSubsystem.hpp"
|
||||
#include "subsystems/HatchSubsystem.hpp"
|
||||
#include "wpi/commands2/Command.hpp"
|
||||
#include "wpi/driverstation/XboxController.hpp"
|
||||
#include "wpi/driverstation/Gamepad.hpp"
|
||||
#include "wpi/smartdashboard/SendableChooser.hpp"
|
||||
|
||||
/**
|
||||
@@ -43,7 +43,7 @@ class RobotContainer {
|
||||
wpi::SendableChooser<wpi::cmd::Command*> m_chooser;
|
||||
|
||||
// The driver's controller
|
||||
wpi::XboxController m_driverController{OIConstants::kDriverControllerPort};
|
||||
wpi::Gamepad m_driverController{OIConstants::kDriverControllerPort};
|
||||
|
||||
void ConfigureButtonBindings();
|
||||
};
|
||||
|
||||
@@ -2,7 +2,7 @@
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include "wpi/driverstation/XboxController.hpp"
|
||||
#include "wpi/driverstation/Gamepad.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
|
||||
/**
|
||||
|
||||
@@ -3,7 +3,7 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include "Drivetrain.hpp"
|
||||
#include "wpi/driverstation/XboxController.hpp"
|
||||
#include "wpi/driverstation/Gamepad.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/math/filter/SlewRateLimiter.hpp"
|
||||
|
||||
@@ -17,7 +17,7 @@ class Robot : public wpi::TimedRobot {
|
||||
void TeleopPeriodic() override { DriveWithJoystick(true); }
|
||||
|
||||
private:
|
||||
wpi::XboxController m_controller{0};
|
||||
wpi::Gamepad m_controller{0};
|
||||
Drivetrain m_mecanum;
|
||||
|
||||
// Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0
|
||||
@@ -27,20 +27,20 @@ class Robot : public wpi::TimedRobot {
|
||||
wpi::math::SlewRateLimiter<wpi::units::scalar> m_rotLimiter{3 / 1_s};
|
||||
|
||||
void DriveWithJoystick(bool fieldRelative) {
|
||||
// Get the x speed. We are inverting this because Xbox controllers return
|
||||
// Get the x speed. We are inverting this because gamepads return
|
||||
// negative values when we push forward.
|
||||
const auto 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
|
||||
// we want a positive value when we pull to the left. Gamepads
|
||||
// return positive values when you pull to the right by default.
|
||||
const auto 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
|
||||
// mathematics). Gamepads return positive values when you pull to
|
||||
// the right by default.
|
||||
const auto rot = -m_rotLimiter.Calculate(m_controller.GetRightX()) *
|
||||
Drivetrain::kMaxAngularSpeed;
|
||||
|
||||
@@ -3,7 +3,7 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include "Drivetrain.hpp"
|
||||
#include "wpi/driverstation/XboxController.hpp"
|
||||
#include "wpi/driverstation/Gamepad.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/math/filter/SlewRateLimiter.hpp"
|
||||
|
||||
@@ -17,7 +17,7 @@ class Robot : public wpi::TimedRobot {
|
||||
void TeleopPeriodic() override { DriveWithJoystick(true); }
|
||||
|
||||
private:
|
||||
wpi::XboxController m_controller{0};
|
||||
wpi::Gamepad m_controller{0};
|
||||
Drivetrain m_mecanum;
|
||||
|
||||
// Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0
|
||||
@@ -27,20 +27,20 @@ class Robot : public wpi::TimedRobot {
|
||||
wpi::math::SlewRateLimiter<wpi::units::scalar> m_rotLimiter{3 / 1_s};
|
||||
|
||||
void DriveWithJoystick(bool fieldRelative) {
|
||||
// Get the x speed. We are inverting this because Xbox controllers return
|
||||
// Get the x speed. We are inverting this because gamepads return
|
||||
// negative values when we push forward.
|
||||
const auto 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
|
||||
// we want a positive value when we pull to the left. Gamepads
|
||||
// return positive values when you pull to the right by default.
|
||||
const auto 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
|
||||
// mathematics). Gamepads return positive values when you pull to
|
||||
// the right by default.
|
||||
const auto rot = -m_rotLimiter.Calculate(m_controller.GetRightX()) *
|
||||
Drivetrain::kMaxAngularSpeed;
|
||||
|
||||
@@ -24,13 +24,13 @@ void RapidReactCommandBot::ConfigureBindings() {
|
||||
[this] { return -m_driverController.GetLeftY(); },
|
||||
[this] { return -m_driverController.GetRightX(); }));
|
||||
|
||||
// Deploy the intake with the X button
|
||||
m_driverController.X().OnTrue(m_intake.IntakeCommand());
|
||||
// Retract the intake with the Y button
|
||||
m_driverController.Y().OnTrue(m_intake.RetractCommand());
|
||||
// Deploy the intake with the West Face button
|
||||
m_driverController.WestFace().OnTrue(m_intake.IntakeCommand());
|
||||
// Retract the intake with the North Face button
|
||||
m_driverController.NorthFace().OnTrue(m_intake.RetractCommand());
|
||||
|
||||
// Fire the shooter with the A button
|
||||
m_driverController.A().OnTrue(
|
||||
// Fire the shooter with the South Face button
|
||||
m_driverController.SouthFace().OnTrue(
|
||||
wpi::cmd::cmd::Parallel(
|
||||
m_shooter.ShootCommand(ShooterConstants::kShooterTarget),
|
||||
m_storage.RunCommand())
|
||||
|
||||
@@ -11,7 +11,7 @@
|
||||
#include "subsystems/Shooter.hpp"
|
||||
#include "subsystems/Storage.hpp"
|
||||
#include "wpi/commands2/CommandPtr.hpp"
|
||||
#include "wpi/commands2/button/CommandXboxController.hpp"
|
||||
#include "wpi/commands2/button/CommandGamepad.hpp"
|
||||
|
||||
/**
|
||||
* This class is where the bulk of the robot should be declared. Since
|
||||
@@ -48,6 +48,6 @@ class RapidReactCommandBot {
|
||||
Pneumatics m_pneumatics;
|
||||
|
||||
// The driver's controller
|
||||
wpi::cmd::CommandXboxController m_driverController{
|
||||
wpi::cmd::CommandGamepad m_driverController{
|
||||
OIConstants::kDriverControllerPort};
|
||||
};
|
||||
|
||||
@@ -3,7 +3,7 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include "Drivetrain.hpp"
|
||||
#include "wpi/driverstation/XboxController.hpp"
|
||||
#include "wpi/driverstation/Gamepad.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/math/controller/LTVUnicycleController.hpp"
|
||||
#include "wpi/math/filter/SlewRateLimiter.hpp"
|
||||
@@ -52,7 +52,7 @@ class Robot : public wpi::TimedRobot {
|
||||
void SimulationPeriodic() override { m_drive.SimulationPeriodic(); }
|
||||
|
||||
private:
|
||||
wpi::XboxController m_controller{0};
|
||||
wpi::Gamepad m_controller{0};
|
||||
|
||||
// Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0
|
||||
// to 1.
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
|
||||
#include <numbers>
|
||||
|
||||
#include "wpi/driverstation/XboxController.hpp"
|
||||
#include "wpi/driverstation/Gamepad.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/hardware/motor/PWMSparkMax.hpp"
|
||||
#include "wpi/hardware/rotation/Encoder.hpp"
|
||||
@@ -85,7 +85,7 @@ class Robot : public wpi::TimedRobot {
|
||||
wpi::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel};
|
||||
|
||||
wpi::PWMSparkMax m_motor{kMotorPort};
|
||||
wpi::XboxController m_joystick{kJoystickPort};
|
||||
wpi::Gamepad m_joystick{kJoystickPort};
|
||||
|
||||
wpi::math::TrapezoidProfile<wpi::units::radians> m_profile{
|
||||
{45_deg_per_s, 90_deg_per_s / 1_s}};
|
||||
@@ -112,7 +112,7 @@ class Robot : public wpi::TimedRobot {
|
||||
// Sets the target position of our arm. This is similar to setting the
|
||||
// setpoint of a PID controller.
|
||||
wpi::math::TrapezoidProfile<wpi::units::radians>::State goal;
|
||||
if (m_joystick.GetRightBumperButton()) {
|
||||
if (m_joystick.GetRightShoulderButton()) {
|
||||
// We pressed the bumper, so let's set our next reference
|
||||
goal = {kRaisedPosition, 0_rad_per_s};
|
||||
} else {
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
|
||||
#include <numbers>
|
||||
|
||||
#include "wpi/driverstation/XboxController.hpp"
|
||||
#include "wpi/driverstation/Gamepad.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/hardware/motor/PWMSparkMax.hpp"
|
||||
#include "wpi/hardware/rotation/Encoder.hpp"
|
||||
@@ -84,7 +84,7 @@ class Robot : public wpi::TimedRobot {
|
||||
wpi::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel};
|
||||
|
||||
wpi::PWMSparkMax m_motor{kMotorPort};
|
||||
wpi::XboxController m_joystick{kJoystickPort};
|
||||
wpi::Gamepad m_joystick{kJoystickPort};
|
||||
|
||||
wpi::math::TrapezoidProfile<wpi::units::meters> m_profile{{3_fps, 6_fps_sq}};
|
||||
|
||||
@@ -112,7 +112,7 @@ class Robot : public wpi::TimedRobot {
|
||||
// Sets the target height of our elevator. This is similar to setting the
|
||||
// setpoint of a PID controller.
|
||||
wpi::math::TrapezoidProfile<wpi::units::meters>::State goal;
|
||||
if (m_joystick.GetRightBumperButton()) {
|
||||
if (m_joystick.GetRightShoulderButton()) {
|
||||
// We pressed the bumper, so let's set our next reference
|
||||
goal = {kRaisedPosition, 0_fps};
|
||||
} else {
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
|
||||
#include <numbers>
|
||||
|
||||
#include "wpi/driverstation/XboxController.hpp"
|
||||
#include "wpi/driverstation/Gamepad.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/hardware/motor/PWMSparkMax.hpp"
|
||||
#include "wpi/hardware/rotation/Encoder.hpp"
|
||||
@@ -76,7 +76,7 @@ class Robot : public wpi::TimedRobot {
|
||||
wpi::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel};
|
||||
|
||||
wpi::PWMSparkMax m_motor{kMotorPort};
|
||||
wpi::XboxController m_joystick{kJoystickPort};
|
||||
wpi::Gamepad m_joystick{kJoystickPort};
|
||||
|
||||
public:
|
||||
Robot() {
|
||||
@@ -91,7 +91,7 @@ class Robot : public wpi::TimedRobot {
|
||||
void TeleopPeriodic() override {
|
||||
// Sets the target speed of our flywheel. This is similar to setting the
|
||||
// setpoint of a PID controller.
|
||||
if (m_joystick.GetRightBumperButton()) {
|
||||
if (m_joystick.GetRightShoulderButton()) {
|
||||
// We pressed the bumper, so let's set our next reference
|
||||
m_loop.SetNextR(wpi::math::Vectord<1>{kSpinup.value()});
|
||||
} else {
|
||||
|
||||
@@ -4,7 +4,7 @@
|
||||
|
||||
#include <numbers>
|
||||
|
||||
#include "wpi/driverstation/XboxController.hpp"
|
||||
#include "wpi/driverstation/Gamepad.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/hardware/motor/PWMSparkMax.hpp"
|
||||
#include "wpi/hardware/rotation/Encoder.hpp"
|
||||
@@ -73,7 +73,7 @@ class Robot : public wpi::TimedRobot {
|
||||
wpi::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel};
|
||||
|
||||
wpi::PWMSparkMax m_motor{kMotorPort};
|
||||
wpi::XboxController m_joystick{kJoystickPort};
|
||||
wpi::Gamepad m_joystick{kJoystickPort};
|
||||
|
||||
public:
|
||||
Robot() {
|
||||
@@ -88,7 +88,7 @@ class Robot : public wpi::TimedRobot {
|
||||
void TeleopPeriodic() override {
|
||||
// Sets the target speed of our flywheel. This is similar to setting the
|
||||
// setpoint of a PID controller.
|
||||
if (m_joystick.GetRightBumperButton()) {
|
||||
if (m_joystick.GetRightShoulderButton()) {
|
||||
// We pressed the bumper, so let's set our next reference
|
||||
m_loop.SetNextR(wpi::math::Vectord<1>{kSpinup.value()});
|
||||
} else {
|
||||
|
||||
@@ -3,7 +3,7 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include "Drivetrain.hpp"
|
||||
#include "wpi/driverstation/XboxController.hpp"
|
||||
#include "wpi/driverstation/Gamepad.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/math/filter/SlewRateLimiter.hpp"
|
||||
#include "wpi/math/util/MathUtil.hpp"
|
||||
@@ -18,7 +18,7 @@ class Robot : public wpi::TimedRobot {
|
||||
void TeleopPeriodic() override { DriveWithJoystick(true); }
|
||||
|
||||
private:
|
||||
wpi::XboxController m_controller{0};
|
||||
wpi::Gamepad m_controller{0};
|
||||
Drivetrain m_swerve;
|
||||
|
||||
// Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0
|
||||
@@ -28,14 +28,14 @@ class Robot : public wpi::TimedRobot {
|
||||
wpi::math::SlewRateLimiter<wpi::units::scalar> m_rotLimiter{3 / 1_s};
|
||||
|
||||
void DriveWithJoystick(bool fieldRelative) {
|
||||
// Get the x speed. We are inverting this because Xbox controllers return
|
||||
// Get the x speed. We are inverting this because gamepads return
|
||||
// negative values when we push forward.
|
||||
const auto xSpeed = -m_xspeedLimiter.Calculate(wpi::math::ApplyDeadband(
|
||||
m_controller.GetLeftY(), 0.02)) *
|
||||
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
|
||||
// we want a positive value when we pull to the left. Gamepads
|
||||
// return positive values when you pull to the right by default.
|
||||
const auto ySpeed = -m_yspeedLimiter.Calculate(wpi::math::ApplyDeadband(
|
||||
m_controller.GetLeftX(), 0.02)) *
|
||||
@@ -43,7 +43,7 @@ class Robot : public wpi::TimedRobot {
|
||||
|
||||
// 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
|
||||
// mathematics). Gamepads return positive values when you pull to
|
||||
// the right by default.
|
||||
const auto rot = -m_rotLimiter.Calculate(wpi::math::ApplyDeadband(
|
||||
m_controller.GetRightX(), 0.02)) *
|
||||
|
||||
@@ -3,7 +3,7 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include "Drivetrain.hpp"
|
||||
#include "wpi/driverstation/XboxController.hpp"
|
||||
#include "wpi/driverstation/Gamepad.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/math/filter/SlewRateLimiter.hpp"
|
||||
|
||||
@@ -17,7 +17,7 @@ class Robot : public wpi::TimedRobot {
|
||||
void TeleopPeriodic() override { DriveWithJoystick(true); }
|
||||
|
||||
private:
|
||||
wpi::XboxController m_controller{0};
|
||||
wpi::Gamepad m_controller{0};
|
||||
Drivetrain m_swerve;
|
||||
|
||||
// Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0
|
||||
@@ -27,20 +27,20 @@ class Robot : public wpi::TimedRobot {
|
||||
wpi::math::SlewRateLimiter<wpi::units::scalar> m_rotLimiter{3 / 1_s};
|
||||
|
||||
void DriveWithJoystick(bool fieldRelative) {
|
||||
// Get the x speed. We are inverting this because Xbox controllers return
|
||||
// Get the x speed. We are inverting this because gamepads return
|
||||
// negative values when we push forward.
|
||||
const auto 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
|
||||
// we want a positive value when we pull to the left. Gamepads
|
||||
// return positive values when you pull to the right by default.
|
||||
const auto 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
|
||||
// mathematics). Gamepads return positive values when you pull to
|
||||
// the right by default.
|
||||
const auto rot = -m_rotLimiter.Calculate(m_controller.GetRightX()) *
|
||||
Drivetrain::kMaxAngularSpeed;
|
||||
|
||||
@@ -17,29 +17,29 @@ void SysIdRoutineBot::ConfigureBindings() {
|
||||
|
||||
// Using bumpers as a modifier and combining it with the buttons so that we
|
||||
// can have both sets of bindings at once
|
||||
(m_driverController.A() && m_driverController.RightBumper())
|
||||
(m_driverController.SouthFace() && m_driverController.RightShoulder())
|
||||
.WhileTrue(
|
||||
m_drive.SysIdQuasistatic(wpi::cmd::sysid::Direction::kForward));
|
||||
(m_driverController.B() && m_driverController.RightBumper())
|
||||
(m_driverController.EastFace() && m_driverController.RightShoulder())
|
||||
.WhileTrue(
|
||||
m_drive.SysIdQuasistatic(wpi::cmd::sysid::Direction::kReverse));
|
||||
(m_driverController.X() && m_driverController.RightBumper())
|
||||
(m_driverController.WestFace() && m_driverController.RightShoulder())
|
||||
.WhileTrue(m_drive.SysIdDynamic(wpi::cmd::sysid::Direction::kForward));
|
||||
(m_driverController.Y() && m_driverController.RightBumper())
|
||||
(m_driverController.NorthFace() && m_driverController.RightShoulder())
|
||||
.WhileTrue(m_drive.SysIdDynamic(wpi::cmd::sysid::Direction::kReverse));
|
||||
|
||||
m_shooter.SetDefaultCommand(m_shooter.RunShooterCommand(
|
||||
[this] { return m_driverController.GetLeftTriggerAxis(); }));
|
||||
|
||||
(m_driverController.A() && m_driverController.LeftBumper())
|
||||
(m_driverController.SouthFace() && m_driverController.LeftShoulder())
|
||||
.WhileTrue(
|
||||
m_shooter.SysIdQuasistatic(wpi::cmd::sysid::Direction::kForward));
|
||||
(m_driverController.B() && m_driverController.LeftBumper())
|
||||
(m_driverController.EastFace() && m_driverController.LeftShoulder())
|
||||
.WhileTrue(
|
||||
m_shooter.SysIdQuasistatic(wpi::cmd::sysid::Direction::kReverse));
|
||||
(m_driverController.X() && m_driverController.LeftBumper())
|
||||
(m_driverController.WestFace() && m_driverController.LeftShoulder())
|
||||
.WhileTrue(m_shooter.SysIdDynamic(wpi::cmd::sysid::Direction::kForward));
|
||||
(m_driverController.Y() && m_driverController.LeftBumper())
|
||||
(m_driverController.NorthFace() && m_driverController.LeftShoulder())
|
||||
.WhileTrue(m_shooter.SysIdDynamic(wpi::cmd::sysid::Direction::kReverse));
|
||||
}
|
||||
|
||||
|
||||
@@ -8,7 +8,7 @@
|
||||
#include "subsystems/Drive.hpp"
|
||||
#include "subsystems/Shooter.hpp"
|
||||
#include "wpi/commands2/CommandPtr.hpp"
|
||||
#include "wpi/commands2/button/CommandXboxController.hpp"
|
||||
#include "wpi/commands2/button/CommandGamepad.hpp"
|
||||
|
||||
class SysIdRoutineBot {
|
||||
public:
|
||||
@@ -18,7 +18,7 @@ class SysIdRoutineBot {
|
||||
|
||||
private:
|
||||
void ConfigureBindings();
|
||||
wpi::cmd::CommandXboxController m_driverController{
|
||||
wpi::cmd::CommandGamepad m_driverController{
|
||||
constants::oi::kDriverControllerPort};
|
||||
Drive m_drive;
|
||||
Shooter m_shooter;
|
||||
|
||||
@@ -3,13 +3,13 @@
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
#include "wpi/drive/DifferentialDrive.hpp"
|
||||
#include "wpi/driverstation/XboxController.hpp"
|
||||
#include "wpi/driverstation/Gamepad.hpp"
|
||||
#include "wpi/framework/TimedRobot.hpp"
|
||||
#include "wpi/hardware/motor/PWMSparkMax.hpp"
|
||||
|
||||
/**
|
||||
* This is a demo program showing the use of the DifferentialDrive class.
|
||||
* Runs the motors with tank steering and an Xbox controller.
|
||||
* Runs the motors with tank steering and a gamepad.
|
||||
*/
|
||||
class Robot : public wpi::TimedRobot {
|
||||
wpi::PWMSparkMax m_leftMotor{0};
|
||||
@@ -17,7 +17,7 @@ class Robot : public wpi::TimedRobot {
|
||||
wpi::DifferentialDrive m_robotDrive{
|
||||
[&](double output) { m_leftMotor.Set(output); },
|
||||
[&](double output) { m_rightMotor.Set(output); }};
|
||||
wpi::XboxController m_driverController{0};
|
||||
wpi::Gamepad m_driverController{0};
|
||||
|
||||
public:
|
||||
Robot() {
|
||||
@@ -146,7 +146,7 @@
|
||||
"description": "Make human interface devices (HID) rumble.",
|
||||
"tags": [
|
||||
"Hardware",
|
||||
"XboxController"
|
||||
"Gamepad"
|
||||
],
|
||||
"foldername": "HidRumble",
|
||||
"gradlebase": "cpp",
|
||||
@@ -305,7 +305,7 @@
|
||||
"Sendable",
|
||||
"DataLog",
|
||||
"Pneumatics",
|
||||
"XboxController"
|
||||
"Gamepad"
|
||||
],
|
||||
"foldername": "HatchbotTraditional",
|
||||
"gradlebase": "cpp",
|
||||
@@ -322,7 +322,7 @@
|
||||
"Sendable",
|
||||
"DataLog",
|
||||
"Pneumatics",
|
||||
"PS4Controller"
|
||||
"Gamepad"
|
||||
],
|
||||
"foldername": "HatchbotInlined",
|
||||
"gradlebase": "cpp",
|
||||
@@ -343,7 +343,7 @@
|
||||
"PID",
|
||||
"Gyro",
|
||||
"Profiled PID",
|
||||
"XboxController"
|
||||
"Gamepad"
|
||||
],
|
||||
"foldername": "RapidReactCommandBot",
|
||||
"gradlebase": "cpp",
|
||||
@@ -365,7 +365,7 @@
|
||||
"tags": [
|
||||
"Swerve Drive",
|
||||
"Odometry",
|
||||
"XboxController",
|
||||
"Gamepad",
|
||||
"Gyro",
|
||||
"Encoder"
|
||||
],
|
||||
@@ -381,7 +381,7 @@
|
||||
"Odometry",
|
||||
"Encoder",
|
||||
"Gyro",
|
||||
"XboxController"
|
||||
"Gamepad"
|
||||
],
|
||||
"foldername": "MecanumBot",
|
||||
"gradlebase": "cpp",
|
||||
@@ -395,7 +395,7 @@
|
||||
"Odometry",
|
||||
"Encoder",
|
||||
"Gyro",
|
||||
"XboxController"
|
||||
"Gamepad"
|
||||
],
|
||||
"foldername": "DifferentialDriveBot",
|
||||
"gradlebase": "cpp",
|
||||
@@ -407,21 +407,21 @@
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Differential Drive",
|
||||
"XboxController"
|
||||
"Gamepad"
|
||||
],
|
||||
"foldername": "ArcadeDriveXboxController",
|
||||
"foldername": "ArcadeDriveGamepad",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
{
|
||||
"name": "Tank Drive Xbox Controller",
|
||||
"description": "Control a differential drive with Xbox tank drive in teleop.",
|
||||
"name": "Tank Drive Gamepad",
|
||||
"description": "Control a differential drive with gamepad tank drive in teleop.",
|
||||
"tags": [
|
||||
"Basic Robot",
|
||||
"Differential Drive",
|
||||
"XboxController"
|
||||
"Gamepad"
|
||||
],
|
||||
"foldername": "TankDriveXboxController",
|
||||
"foldername": "TankDriveGamepad",
|
||||
"gradlebase": "cpp",
|
||||
"commandversion": 2
|
||||
},
|
||||
@@ -470,7 +470,7 @@
|
||||
"Differential Drive",
|
||||
"Trapezoid Profile",
|
||||
"Smart Motor Controller",
|
||||
"XboxController"
|
||||
"Gamepad"
|
||||
],
|
||||
"foldername": "DriveDistanceOffboard",
|
||||
"gradlebase": "cpp",
|
||||
@@ -611,7 +611,7 @@
|
||||
"Pose Estimator",
|
||||
"Vision",
|
||||
"PID",
|
||||
"XboxController"
|
||||
"Gamepad"
|
||||
],
|
||||
"foldername": "DifferentialDrivePoseEstimator",
|
||||
"gradlebase": "cpp",
|
||||
@@ -626,7 +626,7 @@
|
||||
"Pose Estimator",
|
||||
"Vision",
|
||||
"PID",
|
||||
"XboxController"
|
||||
"Gamepad"
|
||||
],
|
||||
"foldername": "MecanumDrivePoseEstimator",
|
||||
"gradlebase": "cpp",
|
||||
@@ -670,7 +670,7 @@
|
||||
"Path Following",
|
||||
"Trajectory",
|
||||
"Encoder",
|
||||
"XboxController",
|
||||
"Gamepad",
|
||||
"Simulation"
|
||||
],
|
||||
"foldername": "SimpleDifferentialDriveSimulation",
|
||||
@@ -686,7 +686,7 @@
|
||||
"Pose Estimator",
|
||||
"Vision",
|
||||
"PID",
|
||||
"XboxController"
|
||||
"Gamepad"
|
||||
],
|
||||
"foldername": "SwerveDrivePoseEstimator",
|
||||
"gradlebase": "cpp",
|
||||
|
||||
@@ -23,9 +23,9 @@ void RobotContainer::ConfigureBindings() {
|
||||
return m_subsystem.ExampleCondition();
|
||||
}).OnTrue(ExampleCommand(&m_subsystem).ToPtr());
|
||||
|
||||
// Schedule `ExampleMethodCommand` when the Xbox controller's B button is
|
||||
// Schedule `ExampleMethodCommand` when the Gamepad's East Face button is
|
||||
// pressed, cancelling on release.
|
||||
m_driverController.B().WhileTrue(m_subsystem.ExampleMethodCommand());
|
||||
m_driverController.EastFace().WhileTrue(m_subsystem.ExampleMethodCommand());
|
||||
}
|
||||
|
||||
wpi::cmd::CommandPtr RobotContainer::GetAutonomousCommand() {
|
||||
|
||||
@@ -7,7 +7,7 @@
|
||||
#include "Constants.hpp"
|
||||
#include "subsystems/ExampleSubsystem.hpp"
|
||||
#include "wpi/commands2/CommandPtr.hpp"
|
||||
#include "wpi/commands2/button/CommandXboxController.hpp"
|
||||
#include "wpi/commands2/button/CommandGamepad.hpp"
|
||||
|
||||
/**
|
||||
* This class is where the bulk of the robot should be declared. Since
|
||||
@@ -24,7 +24,7 @@ class RobotContainer {
|
||||
|
||||
private:
|
||||
// Replace with CommandPS4Controller or CommandJoystick if needed
|
||||
wpi::cmd::CommandXboxController m_driverController{
|
||||
wpi::cmd::CommandGamepad m_driverController{
|
||||
OperatorConstants::kDriverControllerPort};
|
||||
|
||||
// The robot's subsystems are defined here...
|
||||
|
||||
Reference in New Issue
Block a user