29template <
typename WheelPositions,
typename WheelVelocities,
30 typename WheelAccelerations>
42 WheelAccelerations>& kinematics,
44 const WheelPositions& wheelPositions,
46 : m_kinematics(kinematics),
48 m_previousWheelPositions(wheelPositions) {
49 m_previousAngle = m_pose.Rotation();
50 m_gyroOffset = (-gyroAngle).RotateBy(m_pose.Rotation());
64 const WheelPositions& wheelPositions,
const Pose2d& pose) {
67 m_gyroOffset = (-gyroAngle).RotateBy(m_pose.Rotation());
68 m_previousWheelPositions = wheelPositions;
78 m_gyroOffset.RotateBy(-m_pose.Rotation()).RotateBy(pose.
Rotation());
89 m_pose =
Pose2d{translation, m_pose.Rotation()};
98 m_gyroOffset = m_gyroOffset.RotateBy(m_pose.Rotation()).RotateBy(rotation);
99 m_pose =
Pose2d{m_pose.Translation(), rotation};
100 m_previousAngle = rotation;
121 const WheelPositions& wheelPositions) {
122 auto angle = gyroAngle.
RotateBy(m_gyroOffset);
125 m_kinematics.ToTwist2d(m_previousWheelPositions, wheelPositions);
126 twist.dtheta = (angle - m_previousAngle).Radians();
128 auto newPose = m_pose + twist.Exp();
130 m_previousAngle = angle;
131 m_previousWheelPositions = wheelPositions;
132 m_pose = {newPose.Translation(), angle};
142 WheelPositions m_previousWheelPositions;
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel v...
Definition Kinematics.hpp:26
void ResetRotation(const Rotation2d &rotation)
Resets the rotation of the pose.
Definition Odometry.hpp:97
const Pose2d & Update(const Rotation2d &gyroAngle, const WheelPositions &wheelPositions)
Updates the robot's position on the field using forward kinematics and integration of the pose over t...
Definition Odometry.hpp:120
void ResetPosition(const Rotation2d &gyroAngle, const WheelPositions &wheelPositions, const Pose2d &pose)
Resets the robot's position on the field.
Definition Odometry.hpp:63
const Pose2d & GetPose() const
Returns the position of the robot on the field.
Definition Odometry.hpp:107
void ResetTranslation(const Translation2d &translation)
Resets the translation of the pose.
Definition Odometry.hpp:88
void ResetPose(const Pose2d &pose)
Resets the pose.
Definition Odometry.hpp:76
Odometry(const Kinematics< WheelPositions, WheelVelocities, WheelAccelerations > &kinematics, const Rotation2d &gyroAngle, const WheelPositions &wheelPositions, const Pose2d &initialPose=Pose2d{})
Constructs an Odometry object.
Definition Odometry.hpp:41
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.hpp:27
constexpr const Rotation2d & Rotation() const
Returns the underlying rotation.
Definition Pose2d.hpp:128
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.hpp:26
constexpr Rotation2d RotateBy(const Rotation2d &other) const
Adds the new rotation to the current rotation using a rotation matrix.
Definition Rotation2d.hpp:187
Represents a translation in 2D space.
Definition Translation2d.hpp:30
Definition LinearSystem.hpp:20