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