WPILibC++ 2024.3.2
Translation3d.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 <Eigen/Core>
8#include <wpi/SymbolExports.h>
9#include <wpi/json_fwd.h>
10
13#include "units/length.h"
14
15namespace frc {
16
17/**
18 * Represents a translation in 3D space.
19 * This object can be used to represent a point or a vector.
20 *
21 * This assumes that you are using conventional mathematical axes. When the
22 * robot is at the origin facing in the positive X direction, forward is
23 * positive X, left is positive Y, and up is positive Z.
24 */
26 public:
27 /**
28 * Constructs a Translation3d with X, Y, and Z components equal to zero.
29 */
30 constexpr Translation3d() = default;
31
32 /**
33 * Constructs a Translation3d with the X, Y, and Z components equal to the
34 * provided values.
35 *
36 * @param x The x component of the translation.
37 * @param y The y component of the translation.
38 * @param z The z component of the translation.
39 */
40 constexpr Translation3d(units::meter_t x, units::meter_t y, units::meter_t z);
41
42 /**
43 * Constructs a Translation3d 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 Translation3d(units::meter_t distance, const Rotation3d& angle);
50
51 /**
52 * Constructs a Translation3d from the provided translation vector's X, Y, and
53 * Z components. The values are assumed to be in meters.
54 *
55 * @param vector The translation vector to represent.
56 */
57 explicit Translation3d(const Eigen::Vector3d& vector);
58
59 /**
60 * Calculates the distance between two translations in 3D space.
61 *
62 * The distance between translations is defined as
63 * √((x₂−x₁)²+(y₂−y₁)²+(z₂−z₁)²).
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 Translation3d& other) const;
70
71 /**
72 * Returns the X component of the translation.
73 *
74 * @return The Z 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 the Z component of the translation.
87 *
88 * @return The Z component of the translation.
89 */
90 constexpr units::meter_t Z() const { return m_z; }
91
92 /**
93 * Returns a vector representation of this translation.
94 *
95 * @return A Vector representation of this translation.
96 */
97 constexpr Eigen::Vector3d ToVector() const;
98
99 /**
100 * Returns the norm, or distance from the origin to the translation.
101 *
102 * @return The norm of the translation.
103 */
104 units::meter_t Norm() const;
105
106 /**
107 * Applies a rotation to the translation in 3D space.
108 *
109 * For example, rotating a Translation3d of &lt;2, 0, 0&gt; by 90 degrees
110 * around the Z axis will return a Translation3d of &lt;0, 2, 0&gt;.
111 *
112 * @param other The rotation to rotate the translation by.
113 *
114 * @return The new rotated translation.
115 */
116 Translation3d RotateBy(const Rotation3d& other) const;
117
118 /**
119 * Returns a Translation2d representing this Translation3d projected into the
120 * X-Y plane.
121 */
122 constexpr Translation2d ToTranslation2d() const;
123
124 /**
125 * Returns the sum of two translations in 3D space.
126 *
127 * For example, Translation3d{1.0, 2.5, 3.5} + Translation3d{2.0, 5.5, 7.5} =
128 * Translation3d{3.0, 8.0, 11.0}.
129 *
130 * @param other The translation to add.
131 *
132 * @return The sum of the translations.
133 */
134 constexpr Translation3d operator+(const Translation3d& other) const;
135
136 /**
137 * Returns the difference between two translations.
138 *
139 * For example, Translation3d{5.0, 4.0, 3.0} - Translation3d{1.0, 2.0, 3.0} =
140 * Translation3d{4.0, 2.0, 0.0}.
141 *
142 * @param other The translation to subtract.
143 *
144 * @return The difference between the two translations.
145 */
146 constexpr Translation3d operator-(const Translation3d& other) const;
147
148 /**
149 * Returns the inverse of the current translation. This is equivalent to
150 * negating all components of the translation.
151 *
152 * @return The inverse of the current translation.
153 */
154 constexpr Translation3d operator-() const;
155
156 /**
157 * Returns the translation multiplied by a scalar.
158 *
159 * For example, Translation3d{2.0, 2.5, 4.5} * 2 = Translation3d{4.0, 5.0,
160 * 9.0}.
161 *
162 * @param scalar The scalar to multiply by.
163 *
164 * @return The scaled translation.
165 */
166 constexpr Translation3d operator*(double scalar) const;
167
168 /**
169 * Returns the translation divided by a scalar.
170 *
171 * For example, Translation3d{2.0, 2.5, 4.5} / 2 = Translation3d{1.0, 1.25,
172 * 2.25}.
173 *
174 * @param scalar The scalar to divide by.
175 *
176 * @return The scaled translation.
177 */
178 constexpr Translation3d operator/(double scalar) const;
179
180 /**
181 * Checks equality between this Translation3d and another object.
182 *
183 * @param other The other object.
184 * @return Whether the two objects are equal.
185 */
186 bool operator==(const Translation3d& other) const;
187
188 private:
189 units::meter_t m_x = 0_m;
190 units::meter_t m_y = 0_m;
191 units::meter_t m_z = 0_m;
192};
193
195void to_json(wpi::json& json, const Translation3d& state);
196
198void from_json(const wpi::json& json, Translation3d& state);
199
200} // namespace frc
201
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
a class to store JSON values
Definition: json.h:96
A rotation in a 3D coordinate frame represented by a quaternion.
Definition: Rotation3d.h:20
Represents a translation in 2D space.
Definition: Translation2d.h:27
Represents a translation in 3D space.
Definition: Translation3d.h:25
bool operator==(const Translation3d &other) const
Checks equality between this Translation3d and another object.
Translation3d(const Eigen::Vector3d &vector)
Constructs a Translation3d from the provided translation vector's X, Y, and Z components.
constexpr units::meter_t Y() const
Returns the Y component of the translation.
Definition: Translation3d.h:83
constexpr units::meter_t X() const
Returns the X component of the translation.
Definition: Translation3d.h:76
Translation3d(units::meter_t distance, const Rotation3d &angle)
Constructs a Translation3d with the provided distance and angle.
constexpr units::meter_t Z() const
Returns the Z component of the translation.
Definition: Translation3d.h:90
units::meter_t Norm() const
Returns the norm, or distance from the origin to the translation.
constexpr Translation3d()=default
Constructs a Translation3d with X, Y, and Z components equal to zero.
Translation3d RotateBy(const Rotation3d &other) const
Applies a rotation to the translation in 3D space.
units::meter_t Distance(const Translation3d &other) const
Calculates the distance between two translations in 3D space.
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