mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[examples] Ensure right side motors are inverted (#3836)
Fixes #3827 Adds MotorController inversion for right side, removes inversion in setVoltage methods. Also fixes various XboxController negations (was inconsistent throughout examples).
This commit is contained in:
@@ -18,6 +18,13 @@ class Robot : public frc::TimedRobot {
|
||||
frc::Joystick m_stick{0};
|
||||
|
||||
public:
|
||||
void RobotInit() override {
|
||||
// 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_rightMotor.SetInverted(true);
|
||||
}
|
||||
|
||||
void TeleopPeriodic() override {
|
||||
// Drive with arcade style
|
||||
m_robotDrive.ArcadeDrive(m_stick.GetY(), m_stick.GetX());
|
||||
|
||||
@@ -18,12 +18,19 @@ class Robot : public frc::TimedRobot {
|
||||
frc::XboxController m_driverController{0};
|
||||
|
||||
public:
|
||||
void RobotInit() override {
|
||||
// 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_rightMotor.SetInverted(true);
|
||||
}
|
||||
|
||||
void TeleopPeriodic() override {
|
||||
// Drive with split arcade style
|
||||
// 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_robotDrive.ArcadeDrive(-m_driverController.GetLeftY(),
|
||||
-m_driverController.GetRightX());
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
@@ -17,8 +17,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}));
|
||||
}
|
||||
|
||||
@@ -16,6 +16,10 @@ DriveSubsystem::DriveSubsystem()
|
||||
// Set the distance per pulse for the encoders
|
||||
m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
|
||||
m_rightEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
|
||||
// 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_rightMotors.SetInverted(true);
|
||||
}
|
||||
|
||||
void DriveSubsystem::Periodic() {
|
||||
|
||||
@@ -17,8 +17,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}));
|
||||
}
|
||||
|
||||
@@ -16,6 +16,10 @@ DriveSubsystem::DriveSubsystem()
|
||||
// Set the distance per pulse for the encoders
|
||||
m_leftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
|
||||
m_rightEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
|
||||
// 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_rightMotors.SetInverted(true);
|
||||
}
|
||||
|
||||
void DriveSubsystem::Periodic() {
|
||||
|
||||
@@ -18,8 +18,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}));
|
||||
}
|
||||
|
||||
@@ -16,8 +16,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}));
|
||||
}
|
||||
|
||||
@@ -11,7 +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_timer.Start();
|
||||
}
|
||||
|
||||
|
||||
@@ -17,7 +17,13 @@
|
||||
*/
|
||||
class Robot : public frc::TimedRobot {
|
||||
public:
|
||||
void RobotInit() override { m_gyro.SetSensitivity(kVoltsPerDegreePerSecond); }
|
||||
void RobotInit() override {
|
||||
m_gyro.SetSensitivity(kVoltsPerDegreePerSecond);
|
||||
// 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);
|
||||
}
|
||||
|
||||
/**
|
||||
* The motor speed is set from the joystick while the DifferentialDrive
|
||||
|
||||
@@ -16,10 +16,10 @@
|
||||
class Robot : public frc::TimedRobot {
|
||||
public:
|
||||
void RobotInit() override {
|
||||
// Invert the left side motors. You may need to change or remove this to
|
||||
// Invert the right side motors. You may need to change or remove this to
|
||||
// match your robot.
|
||||
m_frontLeft.SetInverted(true);
|
||||
m_rearLeft.SetInverted(true);
|
||||
m_frontRight.SetInverted(true);
|
||||
m_rearRight.SetInverted(true);
|
||||
|
||||
m_gyro.SetSensitivity(kVoltsPerDegreePerSecond);
|
||||
}
|
||||
|
||||
@@ -27,8 +27,8 @@ RobotContainer::RobotContainer() {
|
||||
|
||||
// Set up default drive command
|
||||
m_drive.SetDefaultCommand(DefaultDrive(
|
||||
&m_drive, [this] { return m_driverController.GetLeftY(); },
|
||||
[this] { return m_driverController.GetRightX(); }));
|
||||
&m_drive, [this] { return -m_driverController.GetLeftY(); },
|
||||
[this] { return -m_driverController.GetRightX(); }));
|
||||
}
|
||||
|
||||
void RobotContainer::ConfigureButtonBindings() {
|
||||
|
||||
@@ -20,7 +20,14 @@
|
||||
*/
|
||||
class Drivetrain {
|
||||
public:
|
||||
Drivetrain() { m_gyro.Reset(); }
|
||||
Drivetrain() {
|
||||
m_gyro.Reset();
|
||||
// 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_frontRightMotor.SetInverted(true);
|
||||
m_backRightMotor.SetInverted(true);
|
||||
}
|
||||
|
||||
frc::MecanumDriveWheelSpeeds GetCurrentState() const;
|
||||
void SetSpeeds(const frc::MecanumDriveWheelSpeeds& wheelSpeeds);
|
||||
|
||||
@@ -34,6 +34,11 @@ DriveSubsystem::DriveSubsystem()
|
||||
m_rearLeftEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
|
||||
m_frontRightEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
|
||||
m_rearRightEncoder.SetDistancePerPulse(kEncoderDistancePerPulse);
|
||||
// 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_frontRight.SetInverted(true);
|
||||
m_rearRight.SetInverted(true);
|
||||
}
|
||||
|
||||
void DriveSubsystem::Periodic() {
|
||||
|
||||
@@ -14,10 +14,10 @@
|
||||
class Robot : public frc::TimedRobot {
|
||||
public:
|
||||
void RobotInit() override {
|
||||
// Invert the left side motors. You may need to change or remove this to
|
||||
// Invert the right side motors. You may need to change or remove this to
|
||||
// match your robot.
|
||||
m_frontLeft.SetInverted(true);
|
||||
m_rearLeft.SetInverted(true);
|
||||
m_frontRight.SetInverted(true);
|
||||
m_rearRight.SetInverted(true);
|
||||
}
|
||||
|
||||
void TeleopPeriodic() override {
|
||||
|
||||
@@ -21,7 +21,14 @@
|
||||
*/
|
||||
class Drivetrain {
|
||||
public:
|
||||
Drivetrain() { m_gyro.Reset(); }
|
||||
Drivetrain() {
|
||||
m_gyro.Reset();
|
||||
// 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_frontRightMotor.SetInverted(true);
|
||||
m_backRightMotor.SetInverted(true);
|
||||
}
|
||||
|
||||
frc::MecanumDriveWheelSpeeds GetCurrentState() const;
|
||||
void SetSpeeds(const frc::MecanumDriveWheelSpeeds& wheelSpeeds);
|
||||
|
||||
@@ -42,7 +42,7 @@ void DriveSubsystem::ArcadeDrive(double fwd, double rot) {
|
||||
|
||||
void DriveSubsystem::TankDriveVolts(units::volt_t left, units::volt_t right) {
|
||||
m_leftMotors.SetVoltage(left);
|
||||
m_rightMotors.SetVoltage(-right);
|
||||
m_rightMotors.SetVoltage(right);
|
||||
m_drive.Feed();
|
||||
}
|
||||
|
||||
|
||||
@@ -43,7 +43,7 @@ void Drivetrain::SimulationPeriodic() {
|
||||
// voltages make the right side move forward.
|
||||
m_drivetrainSimulator.SetInputs(units::volt_t{m_leftLeader.Get()} *
|
||||
frc::RobotController::GetInputVoltage(),
|
||||
units::volt_t{-m_rightLeader.Get()} *
|
||||
units::volt_t{m_rightLeader.Get()} *
|
||||
frc::RobotController::GetInputVoltage());
|
||||
m_drivetrainSimulator.Update(20_ms);
|
||||
|
||||
|
||||
@@ -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}));
|
||||
}
|
||||
|
||||
@@ -42,7 +42,7 @@ void DriveSubsystem::SimulationPeriodic() {
|
||||
// voltages make the right side move forward.
|
||||
m_drivetrainSimulator.SetInputs(units::volt_t{m_leftMotors.Get()} *
|
||||
frc::RobotController::GetInputVoltage(),
|
||||
units::volt_t{-m_rightMotors.Get()} *
|
||||
units::volt_t{m_rightMotors.Get()} *
|
||||
frc::RobotController::GetInputVoltage());
|
||||
m_drivetrainSimulator.Update(20_ms);
|
||||
|
||||
@@ -64,7 +64,7 @@ void DriveSubsystem::ArcadeDrive(double fwd, double rot) {
|
||||
|
||||
void DriveSubsystem::TankDriveVolts(units::volt_t left, units::volt_t right) {
|
||||
m_leftMotors.SetVoltage(left);
|
||||
m_rightMotors.SetVoltage(-right);
|
||||
m_rightMotors.SetVoltage(right);
|
||||
m_drive.Feed();
|
||||
}
|
||||
|
||||
|
||||
@@ -27,8 +27,8 @@ class Robot : public frc::TimedRobot {
|
||||
|
||||
void TeleopPeriodic() override {
|
||||
// Drive with tank style
|
||||
m_robotDrive.TankDrive(m_driverController.GetLeftY(),
|
||||
m_driverController.GetRightY());
|
||||
m_robotDrive.TankDrive(-m_driverController.GetLeftY(),
|
||||
-m_driverController.GetRightY());
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
Reference in New Issue
Block a user