WPILibC++ 2023.4.3-108-ge5452e3
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
9#include "Translation3d.h"
10
11namespace frc {
12
14
15/**
16 * Represents a transformation for a Pose3d.
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 the identity transform -- maps an initial pose to itself.
38 */
39 constexpr Transform3d() = default;
40
41 /**
42 * Returns the translation component of the transformation.
43 *
44 * @return Reference to the translational component of the transform.
45 */
46 const Translation3d& Translation() const { return m_translation; }
47
48 /**
49 * Returns the X component of the transformation's translation.
50 *
51 * @return The x component of the transformation's translation.
52 */
53 units::meter_t X() const { return m_translation.X(); }
54
55 /**
56 * Returns the Y component of the transformation's translation.
57 *
58 * @return The y component of the transformation's translation.
59 */
60 units::meter_t Y() const { return m_translation.Y(); }
61
62 /**
63 * Returns the Z component of the transformation's translation.
64 *
65 * @return The z component of the transformation's translation.
66 */
67 units::meter_t Z() const { return m_translation.Z(); }
68
69 /**
70 * Returns the rotational component of the transformation.
71 *
72 * @return Reference to the rotational component of the transform.
73 */
74 const Rotation3d& Rotation() const { return m_rotation; }
75
76 /**
77 * Invert the transformation. This is useful for undoing a transformation.
78 *
79 * @return The inverted transformation.
80 */
82
83 /**
84 * Multiplies the transform by the scalar.
85 *
86 * @param scalar The scalar.
87 * @return The scaled Transform3d.
88 */
90 return Transform3d(m_translation * scalar, m_rotation * scalar);
91 }
92
93 /**
94 * Divides the transform by the scalar.
95 *
96 * @param scalar The scalar.
97 * @return The scaled Transform3d.
98 */
99 Transform3d operator/(double scalar) const { return *this * (1.0 / scalar); }
100
101 /**
102 * Composes two transformations.
103 *
104 * @param other The transform to compose with this one.
105 * @return The composition of the two transformations.
106 */
107 Transform3d operator+(const Transform3d& other) const;
108
109 /**
110 * Checks equality between this Transform3d and another object.
111 */
112 bool operator==(const Transform3d&) const = default;
113
114 private:
115 Translation3d m_translation;
116 Rotation3d m_rotation;
117};
118} // namespace frc
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Represents a 3D pose containing translational and rotational elements.
Definition: Pose3d.h:23
A rotation in a 3D coordinate frame represented by a quaternion.
Definition: Rotation3d.h:23
Represents a transformation for a Pose3d.
Definition: Transform3d.h:18
Transform3d operator+(const Transform3d &other) const
Composes two transformations.
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:46
units::meter_t Y() const
Returns the Y component of the transformation's translation.
Definition: Transform3d.h:60
const Rotation3d & Rotation() const
Returns the rotational component of the transformation.
Definition: Transform3d.h:74
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:53
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:67
Transform3d operator*(double scalar) const
Multiplies the transform by the scalar.
Definition: Transform3d.h:89
Transform3d operator/(double scalar) const
Divides the transform by the scalar.
Definition: Transform3d.h:99
Represents a translation in 3D space.
Definition: Translation3d.h:27
Definition: AprilTagPoseEstimator.h:15
unit< std::ratio< 1 >, units::category::scalar_unit > scalar
Definition: base.h:2521