WPILibC++ 2025.1.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 m_gyroOffset = m_pose.Rotation() - gyroAngle;
52 }
53
54 /**
55 * Resets the robot's position on the field.
56 *
57 * The gyroscope angle does not need to be reset here on the user's robot
58 * code. The library automatically takes care of offsetting the gyro angle.
59 *
60 * @param gyroAngle The angle reported by the gyroscope.
61 * @param wheelPositions The current distances measured by each wheel.
62 * @param pose The position on the field that your robot is at.
63 */
64 void ResetPosition(const Rotation3d& gyroAngle,
65 const WheelPositions& wheelPositions, const Pose3d& pose) {
66 m_pose = pose;
67 m_previousAngle = pose.Rotation();
68 m_gyroOffset = m_pose.Rotation() - gyroAngle;
69 m_previousWheelPositions = wheelPositions;
70 }
71
72 /**
73 * Resets the pose.
74 *
75 * @param pose The pose to reset to.
76 */
77 void ResetPose(const Pose3d& pose) {
78 m_gyroOffset = m_gyroOffset + (pose.Rotation() - m_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 Translation3d& translation) {
89 m_pose = Pose3d{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 Rotation3d& rotation) {
98 m_gyroOffset = m_gyroOffset + (rotation - m_pose.Rotation());
99 m_pose = Pose3d{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 Pose3d& 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 Pose3d& Update(const Rotation3d& gyroAngle,
121 const WheelPositions& wheelPositions) {
122 auto angle = gyroAngle + m_gyroOffset;
123 auto angle_difference = (angle - m_previousAngle).ToVector();
124
125 auto twist2d =
126 m_kinematics.ToTwist2d(m_previousWheelPositions, wheelPositions);
127 Twist3d twist{twist2d.dx,
128 twist2d.dy,
129 0_m,
130 units::radian_t{angle_difference(0)},
131 units::radian_t{angle_difference(1)},
132 units::radian_t{angle_difference(2)}};
133
134 auto newPose = m_pose.Exp(twist);
135
136 m_previousWheelPositions = wheelPositions;
137 m_previousAngle = angle;
138 m_pose = {newPose.Translation(), angle};
139
140 return m_pose;
141 }
142
143 private:
144 const Kinematics<WheelSpeeds, WheelPositions>& m_kinematics;
145 Pose3d m_pose;
146
147 WheelPositions m_previousWheelPositions;
148 Rotation3d m_previousAngle;
149 Rotation3d m_gyroOffset;
150};
151
152} // 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:97
void ResetPose(const Pose3d &pose)
Resets the pose.
Definition Odometry3d.h:77
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:88
void ResetPosition(const Rotation3d &gyroAngle, const WheelPositions &wheelPositions, const Pose3d &pose)
Resets the robot's position on the field.
Definition Odometry3d.h:64
const Pose3d & GetPose() const
Returns the position of the robot on the field.
Definition Odometry3d.h:107
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:120
Represents a 3D pose containing translational and rotational elements.
Definition Pose3d.h:28
constexpr const Rotation3d & Rotation() const
Returns the underlying rotation.
Definition Pose3d.h:148
A rotation in a 3D coordinate frame represented by a quaternion.
Definition Rotation3d.h:29
Represents a translation in 3D space.
Definition Translation3d.h:26
Definition CAN.h:11
A change in distance along a 3D arc since the last pose update.
Definition Twist3d.h:22