32template <
typename WheelSpeeds,
typename WheelPositions>
45 const WheelPositions& wheelPositions,
47 : m_kinematics(kinematics),
49 m_previousWheelPositions(wheelPositions) {
50 m_previousAngle = m_pose.Rotation();
53 m_gyroOffset = (-gyroAngle).RotateBy(m_pose.Rotation());
67 const WheelPositions& wheelPositions,
const Pose3d& pose) {
72 m_gyroOffset = (-gyroAngle).RotateBy(m_pose.Rotation());
73 m_previousWheelPositions = wheelPositions;
84 m_gyroOffset.RotateBy(-m_pose.Rotation()).RotateBy(pose.
Rotation());
95 m_pose =
Pose3d{translation, m_pose.Rotation()};
105 m_gyroOffset = m_gyroOffset.RotateBy(-m_pose.Rotation()).RotateBy(rotation);
106 m_pose =
Pose3d{m_pose.Translation(), rotation};
107 m_previousAngle = rotation;
128 const WheelPositions& wheelPositions) {
129 auto angle = gyroAngle.
RotateBy(m_gyroOffset);
130 auto angle_difference = (angle - m_previousAngle).ToVector();
133 m_kinematics.ToTwist2d(m_previousWheelPositions, wheelPositions);
137 units::radian_t{angle_difference(0)},
138 units::radian_t{angle_difference(1)},
139 units::radian_t{angle_difference(2)}};
141 auto newPose = m_pose.Exp(twist);
143 m_previousWheelPositions = wheelPositions;
144 m_previousAngle = angle;
145 m_pose = {newPose.Translation(), angle};
154 WheelPositions m_previousWheelPositions;
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel s...
Definition Kinematics.h:25
Class for odometry.
Definition Odometry3d.h:33
void ResetRotation(const Rotation3d &rotation)
Resets the rotation of the pose.
Definition Odometry3d.h:103
void ResetPose(const Pose3d &pose)
Resets the pose.
Definition Odometry3d.h:81
Odometry3d(const Kinematics< WheelSpeeds, WheelPositions > &kinematics, const Rotation3d &gyroAngle, const WheelPositions &wheelPositions, const Pose3d &initialPose=Pose3d{})
Constructs an Odometry3d object.
Definition Odometry3d.h:43
void ResetTranslation(const Translation3d &translation)
Resets the translation of the pose.
Definition Odometry3d.h:94
void ResetPosition(const Rotation3d &gyroAngle, const WheelPositions &wheelPositions, const Pose3d &pose)
Resets the robot's position on the field.
Definition Odometry3d.h:66
const Pose3d & GetPose() const
Returns the position of the robot on the field.
Definition Odometry3d.h:114
const Pose3d & Update(const Rotation3d &gyroAngle, const WheelPositions &wheelPositions)
Updates the robot's position on the field using forward kinematics and integration of the pose over t...
Definition Odometry3d.h:127
Represents a 3D pose containing translational and rotational elements.
Definition Pose3d.h:31
constexpr const Rotation3d & Rotation() const
Returns the underlying rotation.
Definition Pose3d.h:151
A rotation in a 3D coordinate frame, represented by a quaternion.
Definition Rotation3d.h:72
constexpr Rotation3d RotateBy(const Rotation3d &other) const
Adds the new rotation to the current rotation.
Definition Rotation3d.h:383
Represents a translation in 3D space.
Definition Translation3d.h:31
A change in distance along a 3D arc since the last pose update.
Definition Twist3d.h:22