mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[examples] Fix Swerve and Mecanum examples (#3359)
Fix encoder allocation and default command. Fixes #3349
This commit is contained in:
@@ -34,7 +34,7 @@ constexpr int kRearRightMotorPort = 3;
|
||||
constexpr int kFrontLeftEncoderPorts[]{0, 1};
|
||||
constexpr int kRearLeftEncoderPorts[]{2, 3};
|
||||
constexpr int kFrontRightEncoderPorts[]{4, 5};
|
||||
constexpr int kRearRightEncoderPorts[]{5, 6};
|
||||
constexpr int kRearRightEncoderPorts[]{6, 7};
|
||||
|
||||
constexpr bool kFrontLeftEncoderReversed = false;
|
||||
constexpr bool kRearLeftEncoderReversed = true;
|
||||
|
||||
@@ -36,8 +36,8 @@ class SwerveModule {
|
||||
frc::PWMSparkMax m_driveMotor;
|
||||
frc::PWMSparkMax m_turningMotor;
|
||||
|
||||
frc::Encoder m_driveEncoder{0, 1};
|
||||
frc::Encoder m_turningEncoder{2, 3};
|
||||
frc::Encoder m_driveEncoder;
|
||||
frc::Encoder m_turningEncoder;
|
||||
|
||||
frc2::PIDController m_drivePIDController{1.0, 0, 0};
|
||||
frc::ProfiledPIDController<units::radians> m_turningPIDController{
|
||||
|
||||
@@ -39,17 +39,17 @@ constexpr int kRearRightTurningMotorPort = 7;
|
||||
constexpr int kFrontLeftTurningEncoderPorts[2]{0, 1};
|
||||
constexpr int kRearLeftTurningEncoderPorts[2]{2, 3};
|
||||
constexpr int kFrontRightTurningEncoderPorts[2]{4, 5};
|
||||
constexpr int kRearRightTurningEncoderPorts[2]{5, 6};
|
||||
constexpr int kRearRightTurningEncoderPorts[2]{6, 7};
|
||||
|
||||
constexpr bool kFrontLeftTurningEncoderReversed = false;
|
||||
constexpr bool kRearLeftTurningEncoderReversed = true;
|
||||
constexpr bool kFrontRightTurningEncoderReversed = false;
|
||||
constexpr bool kRearRightTurningEncoderReversed = true;
|
||||
|
||||
constexpr int kFrontLeftDriveEncoderPorts[2]{0, 1};
|
||||
constexpr int kRearLeftDriveEncoderPorts[2]{2, 3};
|
||||
constexpr int kFrontRightDriveEncoderPorts[2]{4, 5};
|
||||
constexpr int kRearRightDriveEncoderPorts[2]{5, 6};
|
||||
constexpr int kFrontLeftDriveEncoderPorts[2]{8, 9};
|
||||
constexpr int kRearLeftDriveEncoderPorts[2]{10, 11};
|
||||
constexpr int kFrontRightDriveEncoderPorts[2]{12, 13};
|
||||
constexpr int kRearRightDriveEncoderPorts[2]{14, 15};
|
||||
|
||||
constexpr bool kFrontLeftDriveEncoderReversed = false;
|
||||
constexpr bool kRearLeftDriveEncoderReversed = true;
|
||||
|
||||
@@ -8,8 +8,15 @@
|
||||
#include <wpi/math>
|
||||
|
||||
SwerveModule::SwerveModule(const int driveMotorChannel,
|
||||
const int turningMotorChannel)
|
||||
: m_driveMotor(driveMotorChannel), m_turningMotor(turningMotorChannel) {
|
||||
const int turningMotorChannel,
|
||||
const int driveEncoderChannelA,
|
||||
const int driveEncoderChannelB,
|
||||
const int turningEncoderChannelA,
|
||||
const int turningEncoderChannelB)
|
||||
: m_driveMotor(driveMotorChannel),
|
||||
m_turningMotor(turningMotorChannel),
|
||||
m_driveEncoder(driveEncoderChannelA, driveEncoderChannelB),
|
||||
m_turningEncoder(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.
|
||||
|
||||
@@ -35,10 +35,10 @@ class Drivetrain {
|
||||
frc::Translation2d m_backLeftLocation{-0.381_m, +0.381_m};
|
||||
frc::Translation2d m_backRightLocation{-0.381_m, -0.381_m};
|
||||
|
||||
SwerveModule m_frontLeft{1, 2};
|
||||
SwerveModule m_frontRight{2, 3};
|
||||
SwerveModule m_backLeft{5, 6};
|
||||
SwerveModule m_backRight{7, 8};
|
||||
SwerveModule m_frontLeft{1, 2, 0, 1, 2, 3};
|
||||
SwerveModule m_frontRight{2, 3, 4, 5, 6, 7};
|
||||
SwerveModule m_backLeft{5, 6, 8, 9, 10, 11};
|
||||
SwerveModule m_backRight{7, 8, 12, 13, 14, 15};
|
||||
|
||||
frc::AnalogGyro m_gyro{0};
|
||||
|
||||
|
||||
@@ -18,7 +18,9 @@
|
||||
|
||||
class SwerveModule {
|
||||
public:
|
||||
SwerveModule(int driveMotorChannel, int turningMotorChannel);
|
||||
SwerveModule(int driveMotorChannel, int turningMotorChannel,
|
||||
int driveEncoderChannelA, int driveEncoderChannelB,
|
||||
int turningEncoderChannelA, int turningEncoderChannelB);
|
||||
frc::SwerveModuleState GetState() const;
|
||||
void SetDesiredState(const frc::SwerveModuleState& state);
|
||||
|
||||
@@ -34,8 +36,8 @@ class SwerveModule {
|
||||
frc::PWMSparkMax m_driveMotor;
|
||||
frc::PWMSparkMax m_turningMotor;
|
||||
|
||||
frc::Encoder m_driveEncoder{0, 1};
|
||||
frc::Encoder m_turningEncoder{2, 3};
|
||||
frc::Encoder m_driveEncoder;
|
||||
frc::Encoder m_turningEncoder;
|
||||
|
||||
frc2::PIDController m_drivePIDController{1.0, 0, 0};
|
||||
frc::ProfiledPIDController<units::radians> m_turningPIDController{
|
||||
|
||||
Reference in New Issue
Block a user