WPILibC++ 2025.3.1
Loading...
Searching...
No Matches
Translation2d.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 <algorithm>
8#include <initializer_list>
9#include <span>
10
11#include <Eigen/Core>
12#include <wpi/SymbolExports.h>
13#include <wpi/json_fwd.h>
14
16#include "units/length.h"
17#include "units/math.h"
18
19namespace frc {
20
21/**
22 * Represents a translation in 2D space.
23 * This object can be used to represent a point or a vector.
24 *
25 * This assumes that you are using conventional mathematical axes.
26 * When the robot is at the origin facing in the positive X direction, forward
27 * is positive X and left is positive Y.
28 */
30 public:
31 /**
32 * Constructs a Translation2d with X and Y components equal to zero.
33 */
34 constexpr Translation2d() = default;
35
36 /**
37 * Constructs a Translation2d with the X and Y components equal to the
38 * provided values.
39 *
40 * @param x The x component of the translation.
41 * @param y The y component of the translation.
42 */
43 constexpr Translation2d(units::meter_t x, units::meter_t y)
44 : m_x{x}, m_y{y} {}
45
46 /**
47 * Constructs a Translation2d with the provided distance and angle. This is
48 * essentially converting from polar coordinates to Cartesian coordinates.
49 *
50 * @param distance The distance from the origin to the end of the translation.
51 * @param angle The angle between the x-axis and the translation vector.
52 */
53 constexpr Translation2d(units::meter_t distance, const Rotation2d& angle)
54 : m_x{distance * angle.Cos()}, m_y{distance * angle.Sin()} {}
55
56 /**
57 * Constructs a Translation2d from a 2D translation vector. The values are
58 * assumed to be in meters.
59 *
60 * @param vector The translation vector.
61 */
62 constexpr explicit Translation2d(const Eigen::Vector2d& vector)
63 : m_x{units::meter_t{vector.x()}}, m_y{units::meter_t{vector.y()}} {}
64
65 /**
66 * Calculates the distance between two translations in 2D space.
67 *
68 * The distance between translations is defined as √((x₂−x₁)²+(y₂−y₁)²).
69 *
70 * @param other The translation to compute the distance to.
71 *
72 * @return The distance between the two translations.
73 */
74 constexpr units::meter_t Distance(const Translation2d& other) const {
75 return units::math::hypot(other.m_x - m_x, other.m_y - m_y);
76 }
77
78 /**
79 * Returns the X component of the translation.
80 *
81 * @return The X component of the translation.
82 */
83 constexpr units::meter_t X() const { return m_x; }
84
85 /**
86 * Returns the Y component of the translation.
87 *
88 * @return The Y component of the translation.
89 */
90 constexpr units::meter_t Y() const { return m_y; }
91
92 /**
93 * Returns a 2D translation vector representation of this translation.
94 *
95 * @return A 2D translation vector representation of this translation.
96 */
97 constexpr Eigen::Vector2d ToVector() const {
98 return Eigen::Vector2d{{m_x.value(), m_y.value()}};
99 }
100
101 /**
102 * Returns the norm, or distance from the origin to the translation.
103 *
104 * @return The norm of the translation.
105 */
106 constexpr units::meter_t Norm() const { return units::math::hypot(m_x, m_y); }
107
108 /**
109 * Returns the angle this translation forms with the positive X axis.
110 *
111 * @return The angle of the translation
112 */
113 constexpr Rotation2d Angle() const {
114 return Rotation2d{m_x.value(), m_y.value()};
115 }
116
117 /**
118 * Applies a rotation to the translation in 2D space.
119 *
120 * This multiplies the translation vector by a counterclockwise rotation
121 * matrix of the given angle.
122 *
123 * <pre>
124 * [x_new] [other.cos, -other.sin][x]
125 * [y_new] = [other.sin, other.cos][y]
126 * </pre>
127 *
128 * For example, rotating a Translation2d of &lt;2, 0&gt; by 90 degrees will
129 * return a Translation2d of &lt;0, 2&gt;.
130 *
131 * @param other The rotation to rotate the translation by.
132 *
133 * @return The new rotated translation.
134 */
135 constexpr Translation2d RotateBy(const Rotation2d& other) const {
136 return {m_x * other.Cos() - m_y * other.Sin(),
137 m_x * other.Sin() + m_y * other.Cos()};
138 }
139
140 /**
141 * Rotates this translation around another translation in 2D space.
142 *
143 * <pre>
144 * [x_new] [rot.cos, -rot.sin][x - other.x] [other.x]
145 * [y_new] = [rot.sin, rot.cos][y - other.y] + [other.y]
146 * </pre>
147 *
148 * @param other The other translation to rotate around.
149 * @param rot The rotation to rotate the translation by.
150 * @return The new rotated translation.
151 */
153 const Rotation2d& rot) const {
154 return {(m_x - other.X()) * rot.Cos() - (m_y - other.Y()) * rot.Sin() +
155 other.X(),
156 (m_x - other.X()) * rot.Sin() + (m_y - other.Y()) * rot.Cos() +
157 other.Y()};
158 }
159
160 /**
161 * Returns the sum of two translations in 2D space.
162 *
163 * For example, Translation3d{1.0, 2.5} + Translation3d{2.0, 5.5} =
164 * Translation3d{3.0, 8.0}.
165 *
166 * @param other The translation to add.
167 *
168 * @return The sum of the translations.
169 */
170 constexpr Translation2d operator+(const Translation2d& other) const {
171 return {X() + other.X(), Y() + other.Y()};
172 }
173
174 /**
175 * Returns the difference between two translations.
176 *
177 * For example, Translation2d{5.0, 4.0} - Translation2d{1.0, 2.0} =
178 * Translation2d{4.0, 2.0}.
179 *
180 * @param other The translation to subtract.
181 *
182 * @return The difference between the two translations.
183 */
184 constexpr Translation2d operator-(const Translation2d& other) const {
185 return *this + -other;
186 }
187
188 /**
189 * Returns the inverse of the current translation. This is equivalent to
190 * rotating by 180 degrees, flipping the point over both axes, or negating all
191 * components of the translation.
192 *
193 * @return The inverse of the current translation.
194 */
195 constexpr Translation2d operator-() const { return {-m_x, -m_y}; }
196
197 /**
198 * Returns the translation multiplied by a scalar.
199 *
200 * For example, Translation2d{2.0, 2.5} * 2 = Translation2d{4.0, 5.0}.
201 *
202 * @param scalar The scalar to multiply by.
203 *
204 * @return The scaled translation.
205 */
206 constexpr Translation2d operator*(double scalar) const {
207 return {scalar * m_x, scalar * m_y};
208 }
209
210 /**
211 * Returns the translation divided by a scalar.
212 *
213 * For example, Translation2d{2.0, 2.5} / 2 = Translation2d{1.0, 1.25}.
214 *
215 * @param scalar The scalar to divide by.
216 *
217 * @return The scaled translation.
218 */
219 constexpr Translation2d operator/(double scalar) const {
220 return operator*(1.0 / scalar);
221 }
222
223 /**
224 * Checks equality between this Translation2d and another object.
225 *
226 * @param other The other object.
227 * @return Whether the two objects are equal.
228 */
229 constexpr bool operator==(const Translation2d& other) const {
230 return units::math::abs(m_x - other.m_x) < 1E-9_m &&
231 units::math::abs(m_y - other.m_y) < 1E-9_m;
232 }
233
234 /**
235 * Returns the nearest Translation2d from a collection of translations
236 * @param translations The collection of translations.
237 * @return The nearest Translation2d from the collection.
238 */
240 std::span<const Translation2d> translations) const {
241 return *std::min_element(translations.begin(), translations.end(),
242 [this](Translation2d a, Translation2d b) {
243 return this->Distance(a) < this->Distance(b);
244 });
245 }
246
247 /**
248 * Returns the nearest Translation2d from a collection of translations
249 * @param translations The collection of translations.
250 * @return The nearest Translation2d from the collection.
251 */
253 std::initializer_list<Translation2d> translations) const {
254 return *std::min_element(translations.begin(), translations.end(),
255 [this](Translation2d a, Translation2d b) {
256 return this->Distance(a) < this->Distance(b);
257 });
258 }
259
260 private:
261 units::meter_t m_x = 0_m;
262 units::meter_t m_y = 0_m;
263};
264
266void to_json(wpi::json& json, const Translation2d& state);
267
269void from_json(const wpi::json& json, Translation2d& state);
270
271} // namespace frc
272
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
namespace for Niels Lohmann
Definition json.h:99
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition Rotation2d.h:31
constexpr double Cos() const
Returns the cosine of the rotation.
Definition Rotation2d.h:231
constexpr double Sin() const
Returns the sine of the rotation.
Definition Rotation2d.h:238
Represents a translation in 2D space.
Definition Translation2d.h:29
constexpr Translation2d(const Eigen::Vector2d &vector)
Constructs a Translation2d from a 2D translation vector.
Definition Translation2d.h:62
constexpr units::meter_t Norm() const
Returns the norm, or distance from the origin to the translation.
Definition Translation2d.h:106
constexpr Translation2d Nearest(std::initializer_list< Translation2d > translations) const
Returns the nearest Translation2d from a collection of translations.
Definition Translation2d.h:252
constexpr Translation2d()=default
Constructs a Translation2d with X and Y components equal to zero.
constexpr Translation2d RotateAround(const Translation2d &other, const Rotation2d &rot) const
Rotates this translation around another translation in 2D space.
Definition Translation2d.h:152
constexpr Translation2d operator-() const
Returns the inverse of the current translation.
Definition Translation2d.h:195
constexpr Translation2d operator/(double scalar) const
Returns the translation divided by a scalar.
Definition Translation2d.h:219
constexpr units::meter_t X() const
Returns the X component of the translation.
Definition Translation2d.h:83
constexpr Translation2d RotateBy(const Rotation2d &other) const
Applies a rotation to the translation in 2D space.
Definition Translation2d.h:135
constexpr Translation2d operator*(double scalar) const
Returns the translation multiplied by a scalar.
Definition Translation2d.h:206
constexpr units::meter_t Y() const
Returns the Y component of the translation.
Definition Translation2d.h:90
constexpr units::meter_t Distance(const Translation2d &other) const
Calculates the distance between two translations in 2D space.
Definition Translation2d.h:74
constexpr Translation2d operator-(const Translation2d &other) const
Returns the difference between two translations.
Definition Translation2d.h:184
constexpr Rotation2d Angle() const
Returns the angle this translation forms with the positive X axis.
Definition Translation2d.h:113
constexpr Eigen::Vector2d ToVector() const
Returns a 2D translation vector representation of this translation.
Definition Translation2d.h:97
constexpr bool operator==(const Translation2d &other) const
Checks equality between this Translation2d and another object.
Definition Translation2d.h:229
constexpr Translation2d operator+(const Translation2d &other) const
Returns the sum of two translations in 2D space.
Definition Translation2d.h:170
constexpr Translation2d(units::meter_t distance, const Rotation2d &angle)
Constructs a Translation2d with the provided distance and angle.
Definition Translation2d.h:53
constexpr Translation2d Nearest(std::span< const Translation2d > translations) const
Returns the nearest Translation2d from a collection of translations.
Definition Translation2d.h:239
constexpr Translation2d(units::meter_t x, units::meter_t y)
Constructs a Translation2d with the X and Y components equal to the provided values.
Definition Translation2d.h:43
constexpr UnitType abs(const UnitType x) noexcept
Compute absolute value.
Definition math.h:726
constexpr UnitTypeLhs hypot(const UnitTypeLhs &x, const UnitTypeRhs &y)
Computes the square root of the sum-of-squares of x and y.
Definition math.h:508
Definition CAN.h:11
WPILIB_DLLEXPORT void to_json(wpi::json &json, const Rotation3d &rotation)
WPILIB_DLLEXPORT void from_json(const wpi::json &json, Rotation3d &rotation)
Unit Conversion Library namespace.
Definition acceleration.h:33
Type representing an arbitrary unit.
Definition base.h:888