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