mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[examples] Fix SwerveBot example to use unique encoder ports (#3358)
Fixes #3089
This commit is contained in:
@@ -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);
|
||||
|
||||
|
||||
Reference in New Issue
Block a user