WPILibC++ 2026.2.1
Loading...
Searching...
No Matches
Odometry3d.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <wpi/SymbolExports.h>
8
10#include "frc/geometry/Pose3d.h"
16
17namespace frc {
18
19/**
20 * Class for odometry. Robot code should not use this directly- Instead, use the
21 * particular type for your drivetrain (e.g., DifferentialDriveOdometry3d).
22 * Odometry allows you to track the robot's position on the field over a course
23 * of a match using readings from your wheel encoders.
24 *
25 * Teams can use odometry during the autonomous period for complex tasks like
26 * path following. Furthermore, odometry can be used for latency compensation
27 * when using computer-vision systems.
28 *
29 * @tparam WheelSpeeds Wheel speeds type.
30 * @tparam WheelPositions Wheel positions type.
31 */
32template <typename WheelSpeeds, typename WheelPositions>
34 public:
35 /**
36 * Constructs an Odometry3d object.
37 *
38 * @param kinematics The kinematics for your drivetrain.
39 * @param gyroAngle The angle reported by the gyroscope.
40 * @param wheelPositions The current distances measured by each wheel.
41 * @param initialPose The starting position of the robot on the field.
42 */
44 const Rotation3d& gyroAngle,
45 const WheelPositions& wheelPositions,
46 const Pose3d& initialPose = Pose3d{})
47 : m_kinematics(kinematics),
48 m_pose(initialPose),
49 m_previousWheelPositions(wheelPositions) {
50 m_previousAngle = m_pose.Rotation();
51 // When applied extrinsically, m_gyroOffset cancels the
52 // current gyroAngle and then rotates to m_pose.Rotation()
53 m_gyroOffset = (-gyroAngle).RotateBy(m_pose.Rotation());
54 }
55
56 /**
57 * Resets the robot's position on the field.
58 *
59 * The gyroscope angle does not need to be reset here on the user's robot
60 * code. The library automatically takes care of offsetting the gyro angle.
61 *
62 * @param gyroAngle The angle reported by the gyroscope.
63 * @param wheelPositions The current distances measured by each wheel.
64 * @param pose The position on the field that your robot is at.
65 */
66 void ResetPosition(const Rotation3d& gyroAngle,
67 const WheelPositions& wheelPositions, const Pose3d& pose) {
68 m_pose = pose;
69 m_previousAngle = pose.Rotation();
70 // When applied extrinsically, m_gyroOffset cancels the
71 // current gyroAngle and then rotates to m_pose.Rotation()
72 m_gyroOffset = (-gyroAngle).RotateBy(m_pose.Rotation());
73 m_previousWheelPositions = wheelPositions;
74 }
75
76 /**
77 * Resets the pose.
78 *
79 * @param pose The pose to reset to.
80 */
81 void ResetPose(const Pose3d& pose) {
82 // Cancel the previous m_pose.Rotation() and then rotate to the new angle
83 m_gyroOffset =
84 m_gyroOffset.RotateBy(-m_pose.Rotation()).RotateBy(pose.Rotation());
85 m_pose = pose;
86 m_previousAngle = pose.Rotation();
87 }
88
89 /**
90 * Resets the translation of the pose.
91 *
92 * @param translation The translation to reset to.
93 */
94 void ResetTranslation(const Translation3d& translation) {
95 m_pose = Pose3d{translation, m_pose.Rotation()};
96 }
97
98 /**
99 * Resets the rotation of the pose.
100 *
101 * @param rotation The rotation to reset to.
102 */
103 void ResetRotation(const Rotation3d& rotation) {
104 // Cancel the previous m_pose.Rotation() and then rotate to the new angle
105 m_gyroOffset = m_gyroOffset.RotateBy(-m_pose.Rotation()).RotateBy(rotation);
106 m_pose = Pose3d{m_pose.Translation(), rotation};
107 m_previousAngle = rotation;
108 }
109
110 /**
111 * Returns the position of the robot on the field.
112 * @return The pose of the robot.
113 */
114 const Pose3d& GetPose() const { return m_pose; }
115
116 /**
117 * Updates the robot's position on the field using forward kinematics and
118 * integration of the pose over time. This method takes in an angle parameter
119 * which is used instead of the angular rate that is calculated from forward
120 * kinematics, in addition to the current distance measurement at each wheel.
121 *
122 * @param gyroAngle The angle reported by the gyroscope.
123 * @param wheelPositions The current distances measured by each wheel.
124 *
125 * @return The new pose of the robot.
126 */
127 const Pose3d& Update(const Rotation3d& gyroAngle,
128 const WheelPositions& wheelPositions) {
129 auto angle = gyroAngle.RotateBy(m_gyroOffset);
130 auto angle_difference = (angle - m_previousAngle).ToVector();
131
132 auto twist2d =
133 m_kinematics.ToTwist2d(m_previousWheelPositions, wheelPositions);
134 Twist3d twist{twist2d.dx,
135 twist2d.dy,
136 0_m,
137 units::radian_t{angle_difference(0)},
138 units::radian_t{angle_difference(1)},
139 units::radian_t{angle_difference(2)}};
140
141 auto newPose = m_pose.Exp(twist);
142
143 m_previousWheelPositions = wheelPositions;
144 m_previousAngle = angle;
145 m_pose = {newPose.Translation(), angle};
146
147 return m_pose;
148 }
149
150 private:
151 const Kinematics<WheelSpeeds, WheelPositions>& m_kinematics;
152 Pose3d m_pose;
153
154 WheelPositions m_previousWheelPositions;
155
156 // Always equal to m_pose.Rotation()
157 Rotation3d m_previousAngle;
158
159 // Applying a rotation intrinsically to the measured gyro angle should cause
160 // the corrected angle to be rotated intrinsically in the same way, so the
161 // measured gyro angle must be applied intrinsically. This is equivalent to
162 // applying the offset extrinsically to the measured gyro angle.
163 Rotation3d m_gyroOffset;
164};
165
166} // namespace frc
#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
Definition CAN.h:11
A change in distance along a 3D arc since the last pose update.
Definition Twist3d.h:22