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