[wpimath] Position Delta Odometry for Swerve (#4493)

This commit is contained in:
Jordan McMichael
2022-10-25 15:28:36 -04:00
committed by GitHub
parent fe400f68c5
commit 4170ec6107
35 changed files with 1508 additions and 277 deletions

View File

@@ -23,7 +23,7 @@ void Drivetrain::Drive(units::meters_per_second_t xSpeed,
}
void Drivetrain::UpdateOdometry() {
m_odometry.Update(m_gyro.GetRotation2d(), m_frontLeft.GetState(),
m_frontRight.GetState(), m_backLeft.GetState(),
m_backRight.GetState());
m_odometry.Update(m_gyro.GetRotation2d(),
{m_frontLeft.GetPosition(), m_frontRight.GetPosition(),
m_backLeft.GetPosition(), m_backRight.GetPosition()});
}

View File

@@ -41,6 +41,11 @@ frc::SwerveModuleState SwerveModule::GetState() const {
units::radian_t{m_turningEncoder.GetDistance()}};
}
frc::SwerveModulePosition SwerveModule::GetPosition() const {
return {units::meter_t{m_driveEncoder.GetDistance()},
units::radian_t{m_turningEncoder.GetDistance()}};
}
void SwerveModule::SetDesiredState(
const frc::SwerveModuleState& referenceState) {
// Optimize the reference state to avoid spinning further than 90 degrees

View File

@@ -47,5 +47,9 @@ class Drivetrain {
m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation,
m_backRightLocation};
frc::SwerveDriveOdometry<4> m_odometry{m_kinematics, m_gyro.GetRotation2d()};
frc::SwerveDriveOdometry<4> m_odometry{
m_kinematics,
m_gyro.GetRotation2d(),
{m_frontLeft.GetPosition(), m_frontRight.GetPosition(),
m_backLeft.GetPosition(), m_backRight.GetPosition()}};
};

View File

@@ -10,6 +10,7 @@
#include <frc/controller/PIDController.h>
#include <frc/controller/ProfiledPIDController.h>
#include <frc/controller/SimpleMotorFeedforward.h>
#include <frc/kinematics/SwerveModulePosition.h>
#include <frc/kinematics/SwerveModuleState.h>
#include <frc/motorcontrol/PWMSparkMax.h>
#include <units/angular_velocity.h>
@@ -23,6 +24,7 @@ class SwerveModule {
int driveEncoderChannelA, int driveEncoderChannelB,
int turningEncoderChannelA, int turningEncoderChannelB);
frc::SwerveModuleState GetState() const;
frc::SwerveModulePosition GetPosition() const;
void SetDesiredState(const frc::SwerveModuleState& state);
private: