WPILibC++ 2023.4.3-108-ge5452e3
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 <wpi/SymbolExports.h>
11
12#include "Rotation2d.h"
13#include "units/length.h"
14
15namespace wpi {
16class json;
17} // namespace wpi
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
45 /**
46 * Constructs a Translation2d with the provided distance and angle. This is
47 * essentially converting from polar coordinates to Cartesian coordinates.
48 *
49 * @param distance The distance from the origin to the end of the translation.
50 * @param angle The angle between the x-axis and the translation vector.
51 */
52 constexpr Translation2d(units::meter_t distance, const Rotation2d& angle);
53
54 /**
55 * Calculates the distance between two translations in 2D space.
56 *
57 * The distance between translations is defined as √((x₂−x₁)²+(y₂−y₁)²).
58 *
59 * @param other The translation to compute the distance to.
60 *
61 * @return The distance between the two translations.
62 */
63 units::meter_t Distance(const Translation2d& other) const;
64
65 /**
66 * Returns the X component of the translation.
67 *
68 * @return The X component of the translation.
69 */
70 constexpr units::meter_t X() const { return m_x; }
71
72 /**
73 * Returns the Y component of the translation.
74 *
75 * @return The Y component of the translation.
76 */
77 constexpr units::meter_t Y() const { return m_y; }
78
79 /**
80 * Returns the norm, or distance from the origin to the translation.
81 *
82 * @return The norm of the translation.
83 */
84 units::meter_t Norm() const;
85
86 /**
87 * Returns the angle this translation forms with the positive X axis.
88 *
89 * @return The angle of the translation
90 */
91 constexpr Rotation2d Angle() const;
92
93 /**
94 * Applies a rotation to the translation in 2D space.
95 *
96 * This multiplies the translation vector by a counterclockwise rotation
97 * matrix of the given angle.
98 *
99 * <pre>
100 * [x_new] [other.cos, -other.sin][x]
101 * [y_new] = [other.sin, other.cos][y]
102 * </pre>
103 *
104 * For example, rotating a Translation2d of &lt;2, 0&gt; by 90 degrees will
105 * return a Translation2d of &lt;0, 2&gt;.
106 *
107 * @param other The rotation to rotate the translation by.
108 *
109 * @return The new rotated translation.
110 */
111 constexpr Translation2d RotateBy(const Rotation2d& other) const;
112
113 /**
114 * Returns the sum of two translations in 2D space.
115 *
116 * For example, Translation3d{1.0, 2.5} + Translation3d{2.0, 5.5} =
117 * Translation3d{3.0, 8.0}.
118 *
119 * @param other The translation to add.
120 *
121 * @return The sum of the translations.
122 */
123 constexpr Translation2d operator+(const Translation2d& other) const;
124
125 /**
126 * Returns the difference between two translations.
127 *
128 * For example, Translation2d{5.0, 4.0} - Translation2d{1.0, 2.0} =
129 * Translation2d{4.0, 2.0}.
130 *
131 * @param other The translation to subtract.
132 *
133 * @return The difference between the two translations.
134 */
135 constexpr Translation2d operator-(const Translation2d& other) const;
136
137 /**
138 * Returns the inverse of the current translation. This is equivalent to
139 * rotating by 180 degrees, flipping the point over both axes, or negating all
140 * components of the translation.
141 *
142 * @return The inverse of the current translation.
143 */
144 constexpr Translation2d operator-() const;
145
146 /**
147 * Returns the translation multiplied by a scalar.
148 *
149 * For example, Translation2d{2.0, 2.5} * 2 = Translation2d{4.0, 5.0}.
150 *
151 * @param scalar The scalar to multiply by.
152 *
153 * @return The scaled translation.
154 */
155 constexpr Translation2d operator*(double scalar) const;
156
157 /**
158 * Returns the translation divided by a scalar.
159 *
160 * For example, Translation2d{2.0, 2.5} / 2 = Translation2d{1.0, 1.25}.
161 *
162 * @param scalar The scalar to divide by.
163 *
164 * @return The scaled translation.
165 */
166 constexpr Translation2d operator/(double scalar) const;
167
168 /**
169 * Checks equality between this Translation2d and another object.
170 *
171 * @param other The other object.
172 * @return Whether the two objects are equal.
173 */
174 bool operator==(const Translation2d& other) const;
175
176 /**
177 * Returns the nearest Translation2d from a collection of translations
178 * @param translations The collection of translations.
179 * @return The nearest Translation2d from the collection.
180 */
181 Translation2d Nearest(std::span<const Translation2d> translations) const;
182
183 /**
184 * Returns the nearest Translation2d from a collection of translations
185 * @param translations The collection of translations.
186 * @return The nearest Translation2d from the collection.
187 */
189 std::initializer_list<Translation2d> translations) const;
190
191 private:
192 units::meter_t m_x = 0_m;
193 units::meter_t m_y = 0_m;
194};
195
197void to_json(wpi::json& json, const Translation2d& state);
198
200void from_json(const wpi::json& json, Translation2d& state);
201
202} // namespace frc
203
204#include "Translation2d.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
EIGEN_DEVICE_FUNC const NegativeReturnType operator-() const
Definition: CommonCwiseUnaryOps.h:45
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:26
Represents a translation in 2D space.
Definition: Translation2d.h:29
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:70
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:77
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.
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
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:2521
constexpr unit_t< Units, T, NonLinearScale > operator+(const unit_t< Units, T, NonLinearScale > &u) noexcept
Definition: base.h:2339
Definition: AprilTagFieldLayout.h:18