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