WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
Odometry.hpp
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
12
13namespace wpi::math {
14
15/**
16 * Class for odometry. Robot code should not use this directly- Instead, use the
17 * particular type for your drivetrain (e.g., DifferentialDriveOdometry).
18 * Odometry allows you to track the robot's position on the field over a course
19 * of a match using readings from your wheel encoders.
20 *
21 * Teams can use odometry during the autonomous period for complex tasks like
22 * path following. Furthermore, odometry can be used for latency compensation
23 * when using computer-vision systems.
24 *
25 * @tparam WheelPositions Wheel positions type.
26 * @tparam WheelVelocities Wheel velocities type.
27 * @tparam WheelAccelerations Wheel accelerations type.
28 */
29template <typename WheelPositions, typename WheelVelocities,
30 typename WheelAccelerations>
32 public:
33 /**
34 * Constructs an Odometry object.
35 *
36 * @param kinematics The kinematics for your drivetrain.
37 * @param gyroAngle The angle reported by the gyroscope.
38 * @param wheelPositions The current distances measured by each wheel.
39 * @param initialPose The starting position of the robot on the field.
40 */
41 explicit Odometry(const Kinematics<WheelPositions, WheelVelocities,
42 WheelAccelerations>& kinematics,
43 const Rotation2d& gyroAngle,
44 const WheelPositions& wheelPositions,
45 const Pose2d& initialPose = Pose2d{})
46 : m_kinematics(kinematics),
47 m_pose(initialPose),
48 m_previousWheelPositions(wheelPositions) {
49 m_previousAngle = m_pose.Rotation();
50 m_gyroOffset = (-gyroAngle).RotateBy(m_pose.Rotation());
51 }
52
53 /**
54 * Resets the robot's position on the field.
55 *
56 * The gyroscope angle does not need to be reset here on the user's robot
57 * code. The library automatically takes care of offsetting the gyro angle.
58 *
59 * @param gyroAngle The angle reported by the gyroscope.
60 * @param wheelPositions The current distances measured by each wheel.
61 * @param pose The position on the field that your robot is at.
62 */
63 void ResetPosition(const Rotation2d& gyroAngle,
64 const WheelPositions& wheelPositions, const Pose2d& pose) {
65 m_pose = pose;
66 m_previousAngle = pose.Rotation();
67 m_gyroOffset = (-gyroAngle).RotateBy(m_pose.Rotation());
68 m_previousWheelPositions = wheelPositions;
69 }
70
71 /**
72 * Resets the pose.
73 *
74 * @param pose The pose to reset to.
75 */
76 void ResetPose(const Pose2d& pose) {
77 m_gyroOffset =
78 m_gyroOffset.RotateBy(-m_pose.Rotation()).RotateBy(pose.Rotation());
79 m_pose = pose;
80 m_previousAngle = pose.Rotation();
81 }
82
83 /**
84 * Resets the translation of the pose.
85 *
86 * @param translation The translation to reset to.
87 */
88 void ResetTranslation(const Translation2d& translation) {
89 m_pose = Pose2d{translation, m_pose.Rotation()};
90 }
91
92 /**
93 * Resets the rotation of the pose.
94 *
95 * @param rotation The rotation to reset to.
96 */
97 void ResetRotation(const Rotation2d& rotation) {
98 m_gyroOffset = m_gyroOffset.RotateBy(m_pose.Rotation()).RotateBy(rotation);
99 m_pose = Pose2d{m_pose.Translation(), rotation};
100 m_previousAngle = rotation;
101 }
102
103 /**
104 * Returns the position of the robot on the field.
105 * @return The pose of the robot.
106 */
107 const Pose2d& GetPose() const { return m_pose; }
108
109 /**
110 * Updates the robot's position on the field using forward kinematics and
111 * integration of the pose over time. This method takes in an angle parameter
112 * which is used instead of the angular rate that is calculated from forward
113 * kinematics, in addition to the current distance measurement at each wheel.
114 *
115 * @param gyroAngle The angle reported by the gyroscope.
116 * @param wheelPositions The current distances measured by each wheel.
117 *
118 * @return The new pose of the robot.
119 */
120 const Pose2d& Update(const Rotation2d& gyroAngle,
121 const WheelPositions& wheelPositions) {
122 auto angle = gyroAngle.RotateBy(m_gyroOffset);
123
124 auto twist =
125 m_kinematics.ToTwist2d(m_previousWheelPositions, wheelPositions);
126 twist.dtheta = (angle - m_previousAngle).Radians();
127
128 auto newPose = m_pose + twist.Exp();
129
130 m_previousAngle = angle;
131 m_previousWheelPositions = wheelPositions;
132 m_pose = {newPose.Translation(), angle};
133
134 return m_pose;
135 }
136
137 private:
139 m_kinematics;
140 Pose2d m_pose;
141
142 WheelPositions m_previousWheelPositions;
143
144 // Always equal to m_pose.Rotation()
145 Rotation2d m_previousAngle;
146
147 Rotation2d m_gyroOffset;
148};
149
150} // namespace wpi::math
#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