[examples] Update all examples to use NWU coordinate conventions (#4725)

This commit is contained in:
Ryan Blue
2022-11-28 16:49:49 -05:00
committed by GitHub
parent cb38bacfe8
commit 2b2aa8eef7
40 changed files with 55 additions and 56 deletions

View File

@@ -27,7 +27,7 @@ class Robot : public frc::TimedRobot {
void TeleopPeriodic() override {
// Drive with arcade style
m_robotDrive.ArcadeDrive(-m_stick.GetY(), m_stick.GetX());
m_robotDrive.ArcadeDrive(-m_stick.GetY(), -m_stick.GetX());
}
};

View File

@@ -30,7 +30,7 @@ class Robot : public frc::TimedRobot {
// 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.GetLeftY(),
m_driverController.GetRightX());
-m_driverController.GetRightX());
}
};

View File

@@ -22,7 +22,7 @@ RobotContainer::RobotContainer() {
m_drive.SetDefaultCommand(frc2::cmd::Run(
[this] {
m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
m_driverController.GetRightX());
-m_driverController.GetRightX());
},
{&m_drive}));
}

View File

@@ -15,7 +15,7 @@ RobotContainer::RobotContainer() {
// Set up default drive command
m_drive.SetDefaultCommand(m_drive.ArcadeDriveCommand(
[this] { return -m_driverController.GetLeftY(); },
[this] { return m_driverController.GetRightX(); }));
[this] { return -m_driverController.GetRightX(); }));
}
void RobotContainer::ConfigureButtonBindings() {

View File

@@ -16,7 +16,7 @@ RobotContainer::RobotContainer() {
m_drive.SetDefaultCommand(frc2::cmd::Run(
[this] {
m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
m_driverController.GetRightX());
-m_driverController.GetRightX());
},
{&m_drive}));
}

View File

@@ -14,7 +14,7 @@ RobotContainer::RobotContainer() {
m_drive.SetDefaultCommand(frc2::cmd::Run(
[this] {
m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
m_driverController.GetRightX());
-m_driverController.GetRightX());
},
{&m_drive}));
}

View File

@@ -22,9 +22,9 @@ RobotContainer::RobotContainer()
frc::SmartDashboard::PutData(&m_wrist);
frc::SmartDashboard::PutData(&m_claw);
m_drivetrain.SetDefaultCommand(TankDrive([this] { return m_joy.GetLeftY(); },
[this] { return m_joy.GetRightY(); },
m_drivetrain));
m_drivetrain.SetDefaultCommand(
TankDrive([this] { return -m_joy.GetLeftY(); },
[this] { return -m_joy.GetRightY(); }, m_drivetrain));
// Configure the button bindings
ConfigureButtonBindings();

View File

@@ -11,11 +11,11 @@
class Robot : public frc::TimedRobot {
public:
Robot() {
m_right.SetInverted(true);
m_robotDrive.SetExpiration(100_ms);
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
m_right.SetInverted(true);
m_robotDrive.SetExpiration(100_ms);
m_timer.Start();
}

View File

@@ -32,9 +32,7 @@ class Robot : public frc::TimedRobot {
*/
void TeleopPeriodic() override {
double turningValue = (kAngleSetpoint - m_gyro.GetAngle()) * kP;
// Invert the direction of the turn if we are going backwards
turningValue = std::copysign(turningValue, m_joystick.GetY());
m_robotDrive.ArcadeDrive(-m_joystick.GetY(), turningValue);
m_drive.ArcadeDrive(-m_joystick.GetY(), -turningValue);
}
private:
@@ -52,7 +50,7 @@ class Robot : public frc::TimedRobot {
frc::PWMSparkMax m_left{kLeftMotorPort};
frc::PWMSparkMax m_right{kRightMotorPort};
frc::DifferentialDrive m_robotDrive{m_left, m_right};
frc::DifferentialDrive m_drive{m_left, m_right};
frc::AnalogGyro m_gyro{kGyroPort};
frc::Joystick m_joystick{kJoystickPort};

View File

@@ -21,7 +21,7 @@ RobotContainer::RobotContainer() {
m_drive.SetDefaultCommand(frc2::RunCommand(
[this] {
m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
m_driverController.GetRightX());
-m_driverController.GetRightX());
},
{&m_drive}));
}

View File

@@ -28,8 +28,8 @@ class Robot : public frc::TimedRobot {
* Mecanum drive is used with the gyro angle as an input.
*/
void TeleopPeriodic() override {
m_robotDrive.DriveCartesian(-m_joystick.GetY(), m_joystick.GetX(),
m_joystick.GetZ(), m_gyro.GetRotation2d());
m_robotDrive.DriveCartesian(-m_joystick.GetY(), -m_joystick.GetX(),
-m_joystick.GetZ(), m_gyro.GetRotation2d());
}
private:

View File

@@ -24,7 +24,7 @@ RobotContainer::RobotContainer() {
m_drive.SetDefaultCommand(frc2::cmd::Run(
[this] {
m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
m_driverController.GetRightX());
-m_driverController.GetRightX());
},
{&m_drive}));
}

View File

@@ -28,7 +28,7 @@ RobotContainer::RobotContainer() {
// Set up default drive command
m_drive.SetDefaultCommand(DefaultDrive(
&m_drive, [this] { return -m_driverController.GetLeftY(); },
[this] { return m_driverController.GetRightX(); }));
[this] { return -m_driverController.GetRightX(); }));
}
void RobotContainer::ConfigureButtonBindings() {

View File

@@ -30,9 +30,9 @@ RobotContainer::RobotContainer() {
// Set up default drive command
m_drive.SetDefaultCommand(frc2::RunCommand(
[this] {
m_drive.Drive(m_driverController.GetLeftY(),
m_driverController.GetRightX(),
m_driverController.GetLeftX(), false);
m_drive.Drive(-m_driverController.GetLeftY(),
-m_driverController.GetRightX(),
-m_driverController.GetLeftX(), false);
},
{&m_drive}));
}

View File

@@ -24,8 +24,8 @@ class Robot : public frc::TimedRobot {
/* Use the joystick X axis for forward movement, Y axis for lateral
* movement, and Z axis for rotation.
*/
m_robotDrive.DriveCartesian(-m_stick.GetY(), m_stick.GetX(),
m_stick.GetZ());
m_robotDrive.DriveCartesian(-m_stick.GetY(), -m_stick.GetX(),
-m_stick.GetZ());
}
private:

View File

@@ -28,8 +28,8 @@ RobotContainer::RobotContainer() {
// Set up default drive command
m_drive.SetDefaultCommand(frc2::RunCommand(
[this] {
m_drive.ArcadeDrive(m_driverController.GetLeftY(),
m_driverController.GetRightX());
m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
-m_driverController.GetRightX());
},
{&m_drive}));
}

View File

@@ -25,8 +25,8 @@ void RapidReactCommandBot::ConfigureBindings() {
// Control the drive with split-stick arcade controls
m_drive.SetDefaultCommand(m_drive.ArcadeDriveCommand(
[this] { return m_driverController.GetLeftY(); },
[this] { return m_driverController.GetRightX(); }));
[this] { return -m_driverController.GetLeftY(); },
[this] { return -m_driverController.GetRightX(); }));
// Deploy the intake with the X button
m_driverController.X().OnTrue(m_intake.IntakeCommand());

View File

@@ -19,7 +19,7 @@ void RobotContainer::ConfigureButtonBindings() {
// Also set default commands here
m_drive.SetDefaultCommand(TeleopArcadeDrive(
&m_drive, [this] { return -m_controller.GetRawAxis(1); },
[this] { return m_controller.GetRawAxis(2); }));
[this] { return -m_controller.GetRawAxis(2); }));
// Example of how to use the onboard IO
m_onboardButtonA.OnTrue(frc2::cmd::Print("Button A Pressed"))

View File

@@ -34,7 +34,7 @@ RobotContainer::RobotContainer() {
m_drive.SetDefaultCommand(frc2::RunCommand(
[this] {
m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
m_driverController.GetRightX());
-m_driverController.GetLeftX());
},
{&m_drive}));
}

View File

@@ -28,7 +28,7 @@ class Robot : public frc::TimedRobot {
void TeleopPeriodic() override {
// Drive with tank style
m_robotDrive.TankDrive(m_leftStick.GetY(), m_rightStick.GetY());
m_robotDrive.TankDrive(-m_leftStick.GetY(), -m_rightStick.GetY());
}
};