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