mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
Use gyro angle instead of robot angle for odometry (#2081)
The odometry classes previously took in the robot angle as an argument, meaning that users had to take care of offsetting the gyro themselves to accurately report the robot angle. This change will make it so that users will not have to worry about resetting gyros and adding offsets themselves, as this will be handled by the odometry classes.
This commit is contained in:
committed by
Peter Johnson
parent
1b66ead49d
commit
841ef91c0f
@@ -10,18 +10,22 @@
|
||||
using namespace frc;
|
||||
|
||||
DifferentialDriveOdometry::DifferentialDriveOdometry(
|
||||
DifferentialDriveKinematics kinematics, const Pose2d& initialPose)
|
||||
DifferentialDriveKinematics kinematics, const Rotation2d& gyroAngle,
|
||||
const Pose2d& initialPose)
|
||||
: m_kinematics(kinematics), m_pose(initialPose) {
|
||||
m_previousAngle = m_pose.Rotation();
|
||||
m_gyroOffset = m_pose.Rotation() - gyroAngle;
|
||||
}
|
||||
|
||||
const Pose2d& DifferentialDriveOdometry::UpdateWithTime(
|
||||
units::second_t currentTime, const Rotation2d& angle,
|
||||
units::second_t currentTime, const Rotation2d& gyroAngle,
|
||||
const DifferentialDriveWheelSpeeds& wheelSpeeds) {
|
||||
units::second_t deltaTime =
|
||||
(m_previousTime >= 0_s) ? currentTime - m_previousTime : 0_s;
|
||||
m_previousTime = currentTime;
|
||||
|
||||
auto angle = gyroAngle + m_gyroOffset;
|
||||
|
||||
auto [dx, dy, dtheta] = m_kinematics.ToChassisSpeeds(wheelSpeeds);
|
||||
static_cast<void>(dtheta);
|
||||
|
||||
|
||||
@@ -10,18 +10,22 @@
|
||||
using namespace frc;
|
||||
|
||||
MecanumDriveOdometry::MecanumDriveOdometry(MecanumDriveKinematics kinematics,
|
||||
const Rotation2d& gyroAngle,
|
||||
const Pose2d& initialPose)
|
||||
: m_kinematics(kinematics), m_pose(initialPose) {
|
||||
m_previousAngle = m_pose.Rotation();
|
||||
m_gyroOffset = m_pose.Rotation() - gyroAngle;
|
||||
}
|
||||
|
||||
const Pose2d& MecanumDriveOdometry::UpdateWithTime(
|
||||
units::second_t currentTime, const Rotation2d& angle,
|
||||
units::second_t currentTime, const Rotation2d& gyroAngle,
|
||||
MecanumDriveWheelSpeeds wheelSpeeds) {
|
||||
units::second_t deltaTime =
|
||||
(m_previousTime >= 0_s) ? currentTime - m_previousTime : 0_s;
|
||||
m_previousTime = currentTime;
|
||||
|
||||
auto angle = gyroAngle + m_gyroOffset;
|
||||
|
||||
auto [dx, dy, dtheta] = m_kinematics.ToChassisSpeeds(wheelSpeeds);
|
||||
static_cast<void>(dtheta);
|
||||
|
||||
|
||||
Reference in New Issue
Block a user