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