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