mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[wpimath] Position Delta Odometry for Swerve (#4493)
This commit is contained in:
@@ -36,13 +36,17 @@ DriveSubsystem::DriveSubsystem()
|
||||
kRearRightDriveEncoderPorts, kRearRightTurningEncoderPorts,
|
||||
kRearRightDriveEncoderReversed, kRearRightTurningEncoderReversed},
|
||||
|
||||
m_odometry{kDriveKinematics, m_gyro.GetRotation2d(), frc::Pose2d{}} {}
|
||||
m_odometry{kDriveKinematics,
|
||||
m_gyro.GetRotation2d(),
|
||||
{m_frontLeft.GetPosition(), m_frontRight.GetPosition(),
|
||||
m_rearLeft.GetPosition(), m_rearRight.GetPosition()},
|
||||
frc::Pose2d{}} {}
|
||||
|
||||
void DriveSubsystem::Periodic() {
|
||||
// Implementation of subsystem periodic method goes here.
|
||||
m_odometry.Update(m_gyro.GetRotation2d(), m_frontLeft.GetState(),
|
||||
m_rearLeft.GetState(), m_frontRight.GetState(),
|
||||
m_rearRight.GetState());
|
||||
m_odometry.Update(m_gyro.GetRotation2d(), m_frontLeft.GetPosition(),
|
||||
m_rearLeft.GetPosition(), m_frontRight.GetPosition(),
|
||||
m_rearRight.GetPosition());
|
||||
}
|
||||
|
||||
void DriveSubsystem::Drive(units::meters_per_second_t xSpeed,
|
||||
@@ -98,5 +102,8 @@ frc::Pose2d DriveSubsystem::GetPose() {
|
||||
}
|
||||
|
||||
void DriveSubsystem::ResetOdometry(frc::Pose2d pose) {
|
||||
m_odometry.ResetPosition(pose, units::degree_t{GetHeading()});
|
||||
m_odometry.ResetPosition(
|
||||
pose, units::degree_t{GetHeading()},
|
||||
{m_frontLeft.GetPosition(), m_frontRight.GetPosition(),
|
||||
m_rearLeft.GetPosition(), m_rearRight.GetPosition()});
|
||||
}
|
||||
|
||||
@@ -44,6 +44,11 @@ frc::SwerveModuleState SwerveModule::GetState() {
|
||||
units::radian_t{m_turningEncoder.GetDistance()}};
|
||||
}
|
||||
|
||||
frc::SwerveModulePosition SwerveModule::GetPosition() {
|
||||
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
|
||||
|
||||
@@ -10,6 +10,7 @@
|
||||
#include <frc/controller/PIDController.h>
|
||||
#include <frc/controller/ProfiledPIDController.h>
|
||||
#include <frc/geometry/Rotation2d.h>
|
||||
#include <frc/kinematics/SwerveModulePosition.h>
|
||||
#include <frc/kinematics/SwerveModuleState.h>
|
||||
#include <frc/motorcontrol/Spark.h>
|
||||
#include <frc/trajectory/TrapezoidProfile.h>
|
||||
@@ -24,6 +25,8 @@ class SwerveModule {
|
||||
|
||||
frc::SwerveModuleState GetState();
|
||||
|
||||
frc::SwerveModulePosition GetPosition();
|
||||
|
||||
void SetDesiredState(const frc::SwerveModuleState& state);
|
||||
|
||||
void ResetEncoders();
|
||||
|
||||
Reference in New Issue
Block a user