mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +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:
@@ -19,6 +19,14 @@ public class Robot extends TimedRobot {
|
||||
private final DifferentialDrive m_robotDrive = new DifferentialDrive(m_leftMotor, m_rightMotor);
|
||||
private final Joystick m_stick = new Joystick(0);
|
||||
|
||||
@Override
|
||||
public void robotInit() {
|
||||
// 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);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void teleopPeriodic() {
|
||||
// Drive with arcade drive.
|
||||
|
||||
@@ -19,11 +19,19 @@ public class Robot extends TimedRobot {
|
||||
private final DifferentialDrive m_robotDrive = new DifferentialDrive(m_leftMotor, m_rightMotor);
|
||||
private final XboxController m_driverController = new XboxController(0);
|
||||
|
||||
@Override
|
||||
public void robotInit() {
|
||||
// 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);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void teleopPeriodic() {
|
||||
// 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.getLeftY(), m_driverController.getRightX());
|
||||
m_robotDrive.arcadeDrive(-m_driverController.getLeftY(), -m_driverController.getRightX());
|
||||
}
|
||||
}
|
||||
|
||||
@@ -42,7 +42,7 @@ public class RobotContainer {
|
||||
new RunCommand(
|
||||
() ->
|
||||
m_robotDrive.arcadeDrive(
|
||||
m_driverController.getLeftY(), m_driverController.getRightX()),
|
||||
-m_driverController.getLeftY(), -m_driverController.getRightX()),
|
||||
m_robotDrive));
|
||||
}
|
||||
|
||||
|
||||
@@ -46,6 +46,11 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
// Sets the distance per pulse for the encoders
|
||||
m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
|
||||
m_rightEncoder.setDistancePerPulse(DriveConstants.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);
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
@@ -42,7 +42,7 @@ public class RobotContainer {
|
||||
new RunCommand(
|
||||
() ->
|
||||
m_robotDrive.arcadeDrive(
|
||||
m_driverController.getLeftY(), m_driverController.getRightX()),
|
||||
-m_driverController.getLeftY(), -m_driverController.getRightX()),
|
||||
m_robotDrive));
|
||||
}
|
||||
|
||||
|
||||
@@ -46,6 +46,11 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
// Sets the distance per pulse for the encoders
|
||||
m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
|
||||
m_rightEncoder.setDistancePerPulse(DriveConstants.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);
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
@@ -44,7 +44,7 @@ public class RobotContainer {
|
||||
new RunCommand(
|
||||
() ->
|
||||
m_robotDrive.arcadeDrive(
|
||||
m_driverController.getLeftY(), m_driverController.getRightX()),
|
||||
-m_driverController.getLeftY(), -m_driverController.getRightX()),
|
||||
m_robotDrive));
|
||||
}
|
||||
|
||||
|
||||
@@ -67,7 +67,7 @@ public class RobotContainer {
|
||||
new RunCommand(
|
||||
() ->
|
||||
m_robotDrive.arcadeDrive(
|
||||
m_driverController.getLeftY(), m_driverController.getRightX()),
|
||||
-m_driverController.getLeftY(), -m_driverController.getRightX()),
|
||||
m_robotDrive));
|
||||
}
|
||||
|
||||
|
||||
@@ -17,8 +17,9 @@ import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
* directory.
|
||||
*/
|
||||
public class Robot extends TimedRobot {
|
||||
private final DifferentialDrive m_robotDrive =
|
||||
new DifferentialDrive(new PWMSparkMax(0), new PWMSparkMax(1));
|
||||
private final PWMSparkMax m_leftDrive = new PWMSparkMax(0);
|
||||
private final PWMSparkMax m_rightDrive = new PWMSparkMax(1);
|
||||
private final DifferentialDrive m_robotDrive = new DifferentialDrive(m_leftDrive, m_rightDrive);
|
||||
private final Joystick m_stick = new Joystick(0);
|
||||
private final Timer m_timer = new Timer();
|
||||
|
||||
@@ -27,7 +28,12 @@ public class Robot extends TimedRobot {
|
||||
* initialization code.
|
||||
*/
|
||||
@Override
|
||||
public void robotInit() {}
|
||||
public void robotInit() {
|
||||
// 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_rightDrive.setInverted(true);
|
||||
}
|
||||
|
||||
/** This function is run once each time the robot enters autonomous mode. */
|
||||
@Override
|
||||
|
||||
@@ -28,14 +28,19 @@ public class Robot extends TimedRobot {
|
||||
private static final int kGyroPort = 0;
|
||||
private static final int kJoystickPort = 0;
|
||||
|
||||
private final DifferentialDrive m_myRobot =
|
||||
new DifferentialDrive(new PWMSparkMax(kLeftMotorPort), new PWMSparkMax(kRightMotorPort));
|
||||
private final PWMSparkMax m_leftDrive = new PWMSparkMax(kLeftMotorPort);
|
||||
private final PWMSparkMax m_rightDrive = new PWMSparkMax(kRightMotorPort);
|
||||
private final DifferentialDrive m_myRobot = new DifferentialDrive(m_leftDrive, m_rightDrive);
|
||||
private final AnalogGyro m_gyro = new AnalogGyro(kGyroPort);
|
||||
private final Joystick m_joystick = new Joystick(kJoystickPort);
|
||||
|
||||
@Override
|
||||
public void robotInit() {
|
||||
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_rightDrive.setInverted(true);
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
@@ -37,10 +37,10 @@ public class Robot extends TimedRobot {
|
||||
PWMSparkMax frontRight = new PWMSparkMax(kFrontRightChannel);
|
||||
PWMSparkMax rearRight = new PWMSparkMax(kRearRightChannel);
|
||||
|
||||
// Invert the left side motors.
|
||||
// Invert the right side motors.
|
||||
// You may need to change or remove this to match your robot.
|
||||
frontLeft.setInverted(true);
|
||||
rearLeft.setInverted(true);
|
||||
frontRight.setInverted(true);
|
||||
rearRight.setInverted(true);
|
||||
|
||||
m_robotDrive = new MecanumDrive(frontLeft, rearLeft, frontRight, rearRight);
|
||||
|
||||
|
||||
@@ -56,6 +56,11 @@ public class Drivetrain {
|
||||
/** Constructs a MecanumDrive and resets the gyro. */
|
||||
public 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);
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
@@ -67,6 +67,11 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
m_rearLeftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
|
||||
m_frontRightEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
|
||||
m_rearRightEncoder.setDistancePerPulse(DriveConstants.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);
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -28,10 +28,10 @@ public class Robot extends TimedRobot {
|
||||
PWMSparkMax frontRight = new PWMSparkMax(kFrontRightChannel);
|
||||
PWMSparkMax rearRight = new PWMSparkMax(kRearRightChannel);
|
||||
|
||||
// Invert the left side motors.
|
||||
// Invert the right side motors.
|
||||
// You may need to change or remove this to match your robot.
|
||||
frontLeft.setInverted(true);
|
||||
rearLeft.setInverted(true);
|
||||
frontRight.setInverted(true);
|
||||
rearRight.setInverted(true);
|
||||
|
||||
m_robotDrive = new MecanumDrive(frontLeft, rearLeft, frontRight, rearRight);
|
||||
|
||||
|
||||
@@ -68,6 +68,11 @@ public class Drivetrain {
|
||||
/** Constructs a MecanumDrive and resets the gyro. */
|
||||
public 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);
|
||||
}
|
||||
|
||||
/**
|
||||
|
||||
@@ -53,7 +53,7 @@ public class RobotContainer {
|
||||
new RunCommand(
|
||||
() ->
|
||||
m_robotDrive.arcadeDrive(
|
||||
m_driverController.getLeftY(), m_driverController.getRightX()),
|
||||
-m_driverController.getLeftY(), -m_driverController.getRightX()),
|
||||
m_robotDrive));
|
||||
}
|
||||
|
||||
|
||||
@@ -120,7 +120,7 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
*/
|
||||
public void tankDriveVolts(double leftVolts, double rightVolts) {
|
||||
m_leftMotors.setVoltage(leftVolts);
|
||||
m_rightMotors.setVoltage(-rightVolts);
|
||||
m_rightMotors.setVoltage(rightVolts);
|
||||
m_drive.feed();
|
||||
}
|
||||
|
||||
|
||||
@@ -145,7 +145,7 @@ public class Drivetrain {
|
||||
// voltages make the right side move forward.
|
||||
m_drivetrainSimulator.setInputs(
|
||||
m_leftLeader.get() * RobotController.getInputVoltage(),
|
||||
-m_rightLeader.get() * RobotController.getInputVoltage());
|
||||
m_rightLeader.get() * RobotController.getInputVoltage());
|
||||
m_drivetrainSimulator.update(0.02);
|
||||
|
||||
m_leftEncoderSim.setDistance(m_drivetrainSimulator.getLeftPositionMeters());
|
||||
|
||||
@@ -50,7 +50,7 @@ public class RobotContainer {
|
||||
new RunCommand(
|
||||
() ->
|
||||
m_robotDrive.arcadeDrive(
|
||||
-m_driverController.getLeftY(), m_driverController.getRightX()),
|
||||
-m_driverController.getLeftY(), -m_driverController.getRightX()),
|
||||
m_robotDrive));
|
||||
}
|
||||
|
||||
|
||||
@@ -122,7 +122,7 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
// move forward.
|
||||
m_drivetrainSimulator.setInputs(
|
||||
m_leftMotors.get() * RobotController.getBatteryVoltage(),
|
||||
-m_rightMotors.get() * RobotController.getBatteryVoltage());
|
||||
m_rightMotors.get() * RobotController.getBatteryVoltage());
|
||||
m_drivetrainSimulator.update(0.020);
|
||||
|
||||
m_leftEncoderSim.setDistance(m_drivetrainSimulator.getLeftPositionMeters());
|
||||
@@ -194,7 +194,7 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
rightVolts *= batteryVoltage / 12.0;
|
||||
}
|
||||
m_leftMotors.setVoltage(leftVolts);
|
||||
m_rightMotors.setVoltage(-rightVolts);
|
||||
m_rightMotors.setVoltage(rightVolts);
|
||||
m_drive.feed();
|
||||
}
|
||||
|
||||
|
||||
@@ -33,6 +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.getLeftY(), m_driverController.getRightY());
|
||||
m_robotDrive.tankDrive(-m_driverController.getLeftY(), -m_driverController.getRightY());
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user