WPILibC++ 2024.3.2
Pose2d.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 <initializer_list>
8#include <span>
9
10#include <wpi/SymbolExports.h>
11#include <wpi/json_fwd.h>
12
17
18namespace frc {
19
20/**
21 * Represents a 2D pose containing translational and rotational elements.
22 */
24 public:
25 /**
26 * Constructs a pose at the origin facing toward the positive X axis.
27 */
28 constexpr Pose2d() = default;
29
30 /**
31 * Constructs a pose with the specified translation and rotation.
32 *
33 * @param translation The translational component of the pose.
34 * @param rotation The rotational component of the pose.
35 */
36 constexpr Pose2d(Translation2d translation, Rotation2d rotation);
37
38 /**
39 * Constructs a pose with x and y translations instead of a separate
40 * Translation2d.
41 *
42 * @param x The x component of the translational component of the pose.
43 * @param y The y component of the translational component of the pose.
44 * @param rotation The rotational component of the pose.
45 */
46 constexpr Pose2d(units::meter_t x, units::meter_t y, Rotation2d rotation);
47
48 /**
49 * Transforms the pose by the given transformation and returns the new
50 * transformed pose.
51 *
52 * <pre>
53 * [x_new] [cos, -sin, 0][transform.x]
54 * [y_new] += [sin, cos, 0][transform.y]
55 * [t_new] [ 0, 0, 1][transform.t]
56 * </pre>
57 *
58 * @param other The transform to transform the pose by.
59 *
60 * @return The transformed pose.
61 */
62 constexpr Pose2d operator+(const Transform2d& other) const;
63
64 /**
65 * Returns the Transform2d that maps the one pose to another.
66 *
67 * @param other The initial pose of the transformation.
68 * @return The transform that maps the other pose to the current pose.
69 */
70 Transform2d operator-(const Pose2d& other) const;
71
72 /**
73 * Checks equality between this Pose2d and another object.
74 */
75 bool operator==(const Pose2d&) const = default;
76
77 /**
78 * Returns the underlying translation.
79 *
80 * @return Reference to the translational component of the pose.
81 */
82 constexpr const Translation2d& Translation() const { return m_translation; }
83
84 /**
85 * Returns the X component of the pose's translation.
86 *
87 * @return The x component of the pose's translation.
88 */
89 constexpr units::meter_t X() const { return m_translation.X(); }
90
91 /**
92 * Returns the Y component of the pose's translation.
93 *
94 * @return The y component of the pose's translation.
95 */
96 constexpr units::meter_t Y() const { return m_translation.Y(); }
97
98 /**
99 * Returns the underlying rotation.
100 *
101 * @return Reference to the rotational component of the pose.
102 */
103 constexpr const Rotation2d& Rotation() const { return m_rotation; }
104
105 /**
106 * Multiplies the current pose by a scalar.
107 *
108 * @param scalar The scalar.
109 *
110 * @return The new scaled Pose2d.
111 */
112 constexpr Pose2d operator*(double scalar) const;
113
114 /**
115 * Divides the current pose by a scalar.
116 *
117 * @param scalar The scalar.
118 *
119 * @return The new scaled Pose2d.
120 */
121 constexpr Pose2d operator/(double scalar) const;
122
123 /**
124 * Rotates the pose around the origin and returns the new pose.
125 *
126 * @param other The rotation to transform the pose by.
127 *
128 * @return The rotated pose.
129 */
130 constexpr Pose2d RotateBy(const Rotation2d& other) const;
131
132 /**
133 * Transforms the pose by the given transformation and returns the new pose.
134 * See + operator for the matrix multiplication performed.
135 *
136 * @param other The transform to transform the pose by.
137 *
138 * @return The transformed pose.
139 */
140 constexpr Pose2d TransformBy(const Transform2d& other) const;
141
142 /**
143 * Returns the current pose relative to the given pose.
144 *
145 * This function can often be used for trajectory tracking or pose
146 * stabilization algorithms to get the error between the reference and the
147 * current pose.
148 *
149 * @param other The pose that is the origin of the new coordinate frame that
150 * the current pose will be converted into.
151 *
152 * @return The current pose relative to the new origin pose.
153 */
154 Pose2d RelativeTo(const Pose2d& other) const;
155
156 /**
157 * Obtain a new Pose2d from a (constant curvature) velocity.
158 *
159 * See https://file.tavsys.net/control/controls-engineering-in-frc.pdf section
160 * 10.2 "Pose exponential" for a derivation.
161 *
162 * The twist is a change in pose in the robot's coordinate frame since the
163 * previous pose update. When the user runs exp() on the previous known
164 * field-relative pose with the argument being the twist, the user will
165 * receive the new field-relative pose.
166 *
167 * "Exp" represents the pose exponential, which is solving a differential
168 * equation moving the pose forward in time.
169 *
170 * @param twist The change in pose in the robot's coordinate frame since the
171 * previous pose update. For example, if a non-holonomic robot moves forward
172 * 0.01 meters and changes angle by 0.5 degrees since the previous pose
173 * update, the twist would be Twist2d{0.01_m, 0_m, 0.5_deg}.
174 *
175 * @return The new pose of the robot.
176 */
177 Pose2d Exp(const Twist2d& twist) const;
178
179 /**
180 * Returns a Twist2d that maps this pose to the end pose. If c is the output
181 * of a.Log(b), then a.Exp(c) would yield b.
182 *
183 * @param end The end pose for the transformation.
184 *
185 * @return The twist that maps this to end.
186 */
187 Twist2d Log(const Pose2d& end) const;
188
189 /**
190 * Returns the nearest Pose2d from a collection of poses
191 * @param poses The collection of poses.
192 * @return The nearest Pose2d from the collection.
193 */
194 Pose2d Nearest(std::span<const Pose2d> poses) const;
195
196 /**
197 * Returns the nearest Pose2d from a collection of poses
198 * @param poses The collection of poses.
199 * @return The nearest Pose2d from the collection.
200 */
201 Pose2d Nearest(std::initializer_list<Pose2d> poses) const;
202
203 private:
204 Translation2d m_translation;
205 Rotation2d m_rotation;
206};
207
209void to_json(wpi::json& json, const Pose2d& pose);
210
212void from_json(const wpi::json& json, Pose2d& pose);
213
214} // namespace frc
215
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
a class to store JSON values
Definition: json.h:96
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
Pose2d Nearest(std::span< const Pose2d > poses) const
Returns the nearest Pose2d from a collection of poses.
Transform2d operator-(const Pose2d &other) const
Returns the Transform2d that maps the one pose to another.
Pose2d Nearest(std::initializer_list< Pose2d > poses) const
Returns the nearest Pose2d from a collection of poses.
Twist2d Log(const Pose2d &end) const
Returns a Twist2d that maps this pose to the end pose.
constexpr Pose2d()=default
Constructs a pose at the origin facing toward the positive X axis.
constexpr const Rotation2d & Rotation() const
Returns the underlying rotation.
Definition: Pose2d.h:103
constexpr units::meter_t Y() const
Returns the Y component of the pose's translation.
Definition: Pose2d.h:96
constexpr units::meter_t X() const
Returns the X component of the pose's translation.
Definition: Pose2d.h:89
Pose2d Exp(const Twist2d &twist) const
Obtain a new Pose2d from a (constant curvature) velocity.
bool operator==(const Pose2d &) const =default
Checks equality between this Pose2d and another object.
Pose2d RelativeTo(const Pose2d &other) const
Returns the current pose relative to the given pose.
constexpr const Translation2d & Translation() const
Returns the underlying translation.
Definition: Pose2d.h:82
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:23
Represents a transformation for a Pose2d in the pose's frame.
Definition: Transform2d.h:18
Represents a translation in 2D space.
Definition: Translation2d.h:27
Definition: AprilTagPoseEstimator.h:15
WPILIB_DLLEXPORT void from_json(const wpi::json &json, AprilTagFieldLayout &layout)
class WPILIB_DLLEXPORT Pose2d
Definition: Transform2d.h:13
WPILIB_DLLEXPORT void to_json(wpi::json &json, const AprilTagFieldLayout &layout)
unit< std::ratio< 1 >, units::category::scalar_unit > scalar
Definition: base.h:2510
constexpr dimensionless::scalar_t operator/(const UnitTypeLhs &lhs, const UnitTypeRhs &rhs) noexcept
Division for convertible unit_t types with a linear scale.
Definition: base.h:2644
constexpr unit_t< Units, T, NonLinearScale > operator+(const unit_t< Units, T, NonLinearScale > &u) noexcept
Definition: base.h:2328
constexpr auto operator*(const UnitTypeLhs &lhs, const UnitTypeRhs &rhs) noexcept -> unit_t< compound_unit< squared< typename units::traits::unit_t_traits< UnitTypeLhs >::unit_type > > >
Multiplication type for convertible unit_t types with a linear scale.
Definition: base.h:2588
A change in distance along a 2D arc since the last pose update.
Definition: Twist2d.h:21