WPILibC++ 2024.3.2
Transform3d.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
10
11namespace frc {
12
14
15/**
16 * Represents a transformation for a Pose3d in the pose's frame.
17 */
19 public:
20 /**
21 * Constructs the transform that maps the initial pose to the final pose.
22 *
23 * @param initial The initial pose for the transformation.
24 * @param final The final pose for the transformation.
25 */
26 Transform3d(Pose3d initial, Pose3d final);
27
28 /**
29 * Constructs a transform with the given translation and rotation components.
30 *
31 * @param translation Translational component of the transform.
32 * @param rotation Rotational component of the transform.
33 */
34 Transform3d(Translation3d translation, Rotation3d rotation);
35
36 /**
37 * Constructs a transform with x, y, and z translations instead of a separate
38 * Translation3d.
39 *
40 * @param x The x component of the translational component of the transform.
41 * @param y The y component of the translational component of the transform.
42 * @param z The z component of the translational component of the transform.
43 * @param rotation The rotational component of the transform.
44 */
45 Transform3d(units::meter_t x, units::meter_t y, units::meter_t z,
46 Rotation3d rotation);
47
48 /**
49 * Constructs the identity transform -- maps an initial pose to itself.
50 */
51 constexpr Transform3d() = default;
52
53 /**
54 * Returns the translation component of the transformation.
55 *
56 * @return Reference to the translational component of the transform.
57 */
58 const Translation3d& Translation() const { return m_translation; }
59
60 /**
61 * Returns the X component of the transformation's translation.
62 *
63 * @return The x component of the transformation's translation.
64 */
65 units::meter_t X() const { return m_translation.X(); }
66
67 /**
68 * Returns the Y component of the transformation's translation.
69 *
70 * @return The y component of the transformation's translation.
71 */
72 units::meter_t Y() const { return m_translation.Y(); }
73
74 /**
75 * Returns the Z component of the transformation's translation.
76 *
77 * @return The z component of the transformation's translation.
78 */
79 units::meter_t Z() const { return m_translation.Z(); }
80
81 /**
82 * Returns the rotational component of the transformation.
83 *
84 * @return Reference to the rotational component of the transform.
85 */
86 const Rotation3d& Rotation() const { return m_rotation; }
87
88 /**
89 * Invert the transformation. This is useful for undoing a transformation.
90 *
91 * @return The inverted transformation.
92 */
94
95 /**
96 * Multiplies the transform by the scalar.
97 *
98 * @param scalar The scalar.
99 * @return The scaled Transform3d.
100 */
102 return Transform3d(m_translation * scalar, m_rotation * scalar);
103 }
104
105 /**
106 * Divides the transform by the scalar.
107 *
108 * @param scalar The scalar.
109 * @return The scaled Transform3d.
110 */
111 Transform3d operator/(double scalar) const { return *this * (1.0 / scalar); }
112
113 /**
114 * Composes two transformations. The second transform is applied relative to
115 * the orientation of the first.
116 *
117 * @param other The transform to compose with this one.
118 * @return The composition of the two transformations.
119 */
120 Transform3d operator+(const Transform3d& other) const;
121
122 /**
123 * Checks equality between this Transform3d and another object.
124 */
125 bool operator==(const Transform3d&) const = default;
126
127 private:
128 Translation3d m_translation;
129 Rotation3d m_rotation;
130};
131} // namespace frc
132
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Represents a 3D pose containing translational and rotational elements.
Definition: Pose3d.h:21
A rotation in a 3D coordinate frame represented by a quaternion.
Definition: Rotation3d.h:20
Represents a transformation for a Pose3d in the pose's frame.
Definition: Transform3d.h:18
Transform3d operator+(const Transform3d &other) const
Composes two transformations.
Transform3d(units::meter_t x, units::meter_t y, units::meter_t z, Rotation3d rotation)
Constructs a transform with x, y, and z translations instead of a separate Translation3d.
Transform3d(Pose3d initial, Pose3d final)
Constructs the transform that maps the initial pose to the final pose.
constexpr Transform3d()=default
Constructs the identity transform – maps an initial pose to itself.
const Translation3d & Translation() const
Returns the translation component of the transformation.
Definition: Transform3d.h:58
units::meter_t Y() const
Returns the Y component of the transformation's translation.
Definition: Transform3d.h:72
const Rotation3d & Rotation() const
Returns the rotational component of the transformation.
Definition: Transform3d.h:86
bool operator==(const Transform3d &) const =default
Checks equality between this Transform3d and another object.
units::meter_t X() const
Returns the X component of the transformation's translation.
Definition: Transform3d.h:65
Transform3d Inverse() const
Invert the transformation.
Transform3d(Translation3d translation, Rotation3d rotation)
Constructs a transform with the given translation and rotation components.
units::meter_t Z() const
Returns the Z component of the transformation's translation.
Definition: Transform3d.h:79
Transform3d operator*(double scalar) const
Multiplies the transform by the scalar.
Definition: Transform3d.h:101
Transform3d operator/(double scalar) const
Divides the transform by the scalar.
Definition: Transform3d.h:111
Represents a translation in 3D space.
Definition: Translation3d.h:25
Definition: AprilTagPoseEstimator.h:15
unit< std::ratio< 1 >, units::category::scalar_unit > scalar
Definition: base.h:2510