[examples] Fix Swerve and Mecanum examples (#3359)

Fix encoder allocation and default command.
Fixes #3349
This commit is contained in:
sciencewhiz
2021-05-15 21:39:00 -07:00
committed by GitHub
parent 80b479e502
commit 1873fbefba
12 changed files with 61 additions and 35 deletions

View File

@@ -27,7 +27,7 @@ public final class Constants {
public static final int[] kFrontLeftEncoderPorts = new int[] {0, 1};
public static final int[] kRearLeftEncoderPorts = new int[] {2, 3};
public static final int[] kFrontRightEncoderPorts = new int[] {4, 5};
public static final int[] kRearRightEncoderPorts = new int[] {5, 6};
public static final int[] kRearRightEncoderPorts = new int[] {6, 7};
public static final boolean kFrontLeftEncoderReversed = false;
public static final boolean kRearLeftEncoderReversed = true;

View File

@@ -55,7 +55,8 @@ public class RobotContainer {
m_driverController.getY(GenericHID.Hand.kLeft),
m_driverController.getX(GenericHID.Hand.kRight),
m_driverController.getX(GenericHID.Hand.kLeft),
false)));
false),
m_robotDrive));
}
/**

View File

@@ -31,17 +31,17 @@ public final class Constants {
public static final int[] kFrontLeftTurningEncoderPorts = new int[] {0, 1};
public static final int[] kRearLeftTurningEncoderPorts = new int[] {2, 3};
public static final int[] kFrontRightTurningEncoderPorts = new int[] {4, 5};
public static final int[] kRearRightTurningEncoderPorts = new int[] {5, 6};
public static final int[] kRearRightTurningEncoderPorts = new int[] {6, 7};
public static final boolean kFrontLeftTurningEncoderReversed = false;
public static final boolean kRearLeftTurningEncoderReversed = true;
public static final boolean kFrontRightTurningEncoderReversed = false;
public static final boolean kRearRightTurningEncoderReversed = true;
public static final int[] kFrontLeftDriveEncoderPorts = new int[] {7, 8};
public static final int[] kRearLeftDriveEncoderPorts = new int[] {9, 10};
public static final int[] kFrontRightDriveEncoderPorts = new int[] {11, 12};
public static final int[] kRearRightDriveEncoderPorts = new int[] {13, 14};
public static final int[] kFrontLeftDriveEncoderPorts = new int[] {8, 9};
public static final int[] kRearLeftDriveEncoderPorts = new int[] {10, 11};
public static final int[] kFrontRightDriveEncoderPorts = new int[] {12, 13};
public static final int[] kRearRightDriveEncoderPorts = new int[] {14, 15};
public static final boolean kFrontLeftDriveEncoderReversed = false;
public static final boolean kRearLeftDriveEncoderReversed = true;

View File

@@ -53,7 +53,8 @@ public class RobotContainer {
m_driverController.getY(GenericHID.Hand.kLeft),
m_driverController.getX(GenericHID.Hand.kRight),
m_driverController.getX(GenericHID.Hand.kLeft),
false)));
false),
m_robotDrive));
}
/**

View File

@@ -24,10 +24,10 @@ public class Drivetrain {
private final Translation2d m_backLeftLocation = new Translation2d(-0.381, 0.381);
private final Translation2d m_backRightLocation = new Translation2d(-0.381, -0.381);
private final SwerveModule m_frontLeft = new SwerveModule(1, 2);
private final SwerveModule m_frontRight = new SwerveModule(3, 4);
private final SwerveModule m_backLeft = new SwerveModule(5, 6);
private final SwerveModule m_backRight = new SwerveModule(7, 8);
private final SwerveModule m_frontLeft = new SwerveModule(1, 2, 0, 1, 2, 3);
private final SwerveModule m_frontRight = new SwerveModule(3, 4, 4, 5, 6, 7);
private final SwerveModule m_backLeft = new SwerveModule(5, 6, 8, 9, 10, 11);
private final SwerveModule m_backRight = new SwerveModule(7, 8, 12, 13, 14, 15);
private final AnalogGyro m_gyro = new AnalogGyro(0);

View File

@@ -25,11 +25,13 @@ public class SwerveModule {
private final MotorController m_driveMotor;
private final MotorController m_turningMotor;
private final Encoder m_driveEncoder = new Encoder(0, 1);
private final Encoder m_turningEncoder = new Encoder(2, 3);
private final Encoder m_driveEncoder;
private final Encoder m_turningEncoder;
// Gains are for example purposes only - must be determined for your own robot!
private final PIDController m_drivePIDController = new PIDController(1, 0, 0);
// Gains are for example purposes only - must be determined for your own robot!
private final ProfiledPIDController m_turningPIDController =
new ProfiledPIDController(
1,
@@ -43,15 +45,28 @@ public class SwerveModule {
private final SimpleMotorFeedforward m_turnFeedforward = new SimpleMotorFeedforward(1, 0.5);
/**
* Constructs a SwerveModule.
* Constructs a SwerveModule with a drive motor, turning motor, drive encoder and turning encoder.
*
* @param driveMotorChannel ID for the drive motor.
* @param turningMotorChannel ID for the turning motor.
* @param driveMotorChannel PWM output for the drive motor.
* @param turningMotorChannel PWM output for the turning motor.
* @param driveEncoderChannelA DIO input for the drive encoder channel A
* @param driveEncoderChannelB DIO input for the drive encoder channel B
* @param turningEncoderChannelA DIO input for the turning encoder channel A
* @param turningEncoderChannelB DIO input for the turning encoder channel B
*/
public SwerveModule(int driveMotorChannel, int turningMotorChannel) {
public SwerveModule(
int driveMotorChannel,
int turningMotorChannel,
int driveEncoderChannelA,
int driveEncoderChannelB,
int turningEncoderChannelA,
int turningEncoderChannelB) {
m_driveMotor = new PWMSparkMax(driveMotorChannel);
m_turningMotor = new PWMSparkMax(turningMotorChannel);
m_driveEncoder = new Encoder(driveEncoderChannelA, driveEncoderChannelB);
m_turningEncoder = new Encoder(turningEncoderChannelA, turningEncoderChannelB);
// Set the distance per pulse for the drive encoder. We can simply use the
// distance traveled for one rotation of the wheel divided by the encoder
// resolution.