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