WPILibC++ 2023.4.3
Pose3d.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 "Pose2d.h"
10#include "Transform3d.h"
11#include "Translation3d.h"
12#include "Twist3d.h"
13
14namespace wpi {
15class json;
16} // namespace wpi
17
18namespace frc {
19
20/**
21 * Represents a 3D pose containing translational and rotational elements.
22 */
24 public:
25 /**
26 * Constructs a pose at the origin facing toward the positive X axis.
27 */
28 constexpr Pose3d() = default;
29
30 /**
31 * Constructs a pose with the specified translation and rotation.
32 *
33 * @param translation The translational component of the pose.
34 * @param rotation The rotational component of the pose.
35 */
36 Pose3d(Translation3d translation, Rotation3d rotation);
37
38 /**
39 * Constructs a pose with x, y, and z translations instead of a separate
40 * Translation3d.
41 *
42 * @param x The x component of the translational component of the pose.
43 * @param y The y component of the translational component of the pose.
44 * @param z The z component of the translational component of the pose.
45 * @param rotation The rotational component of the pose.
46 */
47 Pose3d(units::meter_t x, units::meter_t y, units::meter_t z,
48 Rotation3d rotation);
49
50 /**
51 * Constructs a 3D pose from a 2D pose in the X-Y plane.
52 *
53 * @param pose The 2D pose.
54 */
55 explicit Pose3d(const Pose2d& pose);
56
57 /**
58 * Transforms the pose by the given transformation and returns the new
59 * transformed pose.
60 *
61 * @param other The transform to transform the pose by.
62 *
63 * @return The transformed pose.
64 */
65 Pose3d operator+(const Transform3d& other) const;
66
67 /**
68 * Returns the Transform3d that maps the one pose to another.
69 *
70 * @param other The initial pose of the transformation.
71 * @return The transform that maps the other pose to the current pose.
72 */
73 Transform3d operator-(const Pose3d& other) const;
74
75 /**
76 * Checks equality between this Pose3d and another object.
77 */
78 bool operator==(const Pose3d&) const = default;
79
80 /**
81 * Returns the underlying translation.
82 *
83 * @return Reference to the translational component of the pose.
84 */
85 const Translation3d& Translation() const { return m_translation; }
86
87 /**
88 * Returns the X component of the pose's translation.
89 *
90 * @return The x component of the pose's translation.
91 */
92 units::meter_t X() const { return m_translation.X(); }
93
94 /**
95 * Returns the Y component of the pose's translation.
96 *
97 * @return The y component of the pose's translation.
98 */
99 units::meter_t Y() const { return m_translation.Y(); }
100
101 /**
102 * Returns the Z component of the pose's translation.
103 *
104 * @return The z component of the pose's translation.
105 */
106 units::meter_t Z() const { return m_translation.Z(); }
107
108 /**
109 * Returns the underlying rotation.
110 *
111 * @return Reference to the rotational component of the pose.
112 */
113 const Rotation3d& Rotation() const { return m_rotation; }
114
115 /**
116 * Multiplies the current pose by a scalar.
117 *
118 * @param scalar The scalar.
119 *
120 * @return The new scaled Pose2d.
121 */
122 Pose3d operator*(double scalar) const;
123
124 /**
125 * Divides the current pose by a scalar.
126 *
127 * @param scalar The scalar.
128 *
129 * @return The new scaled Pose2d.
130 */
131 Pose3d operator/(double scalar) const;
132
133 /**
134 * Transforms the pose by the given transformation and returns the new pose.
135 * See + operator for the matrix multiplication performed.
136 *
137 * @param other The transform to transform the pose by.
138 *
139 * @return The transformed pose.
140 */
141 Pose3d TransformBy(const Transform3d& other) const;
142
143 /**
144 * Returns the current pose relative to the given pose.
145 *
146 * This function can often be used for trajectory tracking or pose
147 * stabilization algorithms to get the error between the reference and the
148 * current pose.
149 *
150 * @param other The pose that is the origin of the new coordinate frame that
151 * the current pose will be converted into.
152 *
153 * @return The current pose relative to the new origin pose.
154 */
155 Pose3d RelativeTo(const Pose3d& other) const;
156
157 /**
158 * Obtain a new Pose3d from a (constant curvature) velocity.
159 *
160 * The twist is a change in pose in the robot's coordinate frame since the
161 * previous pose update. When the user runs exp() on the previous known
162 * field-relative pose with the argument being the twist, the user will
163 * receive the new field-relative pose.
164 *
165 * "Exp" represents the pose exponential, which is solving a differential
166 * equation moving the pose forward in time.
167 *
168 * @param twist The change in pose in the robot's coordinate frame since the
169 * previous pose update. For example, if a non-holonomic robot moves forward
170 * 0.01 meters and changes angle by 0.5 degrees since the previous pose
171 * update, the twist would be Twist3d{0.01_m, 0_m, 0_m, Rotation3d{0.0, 0.0,
172 * 0.5_deg}}.
173 *
174 * @return The new pose of the robot.
175 */
176 Pose3d Exp(const Twist3d& twist) const;
177
178 /**
179 * Returns a Twist3d that maps this pose to the end pose. If c is the output
180 * of a.Log(b), then a.Exp(c) would yield b.
181 *
182 * @param end The end pose for the transformation.
183 *
184 * @return The twist that maps this to end.
185 */
186 Twist3d Log(const Pose3d& end) const;
187
188 /**
189 * Returns a Pose2d representing this Pose3d projected into the X-Y plane.
190 */
192
193 private:
194 Translation3d m_translation;
195 Rotation3d m_rotation;
196};
197
199void to_json(wpi::json& json, const Pose3d& pose);
200
202void from_json(const wpi::json& json, Pose3d& pose);
203
204} // namespace frc
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:25
Represents a 3D pose containing translational and rotational elements.
Definition: Pose3d.h:23
Pose3d RelativeTo(const Pose3d &other) const
Returns the current pose relative to the given pose.
Pose2d ToPose2d() const
Returns a Pose2d representing this Pose3d projected into the X-Y plane.
Pose3d TransformBy(const Transform3d &other) const
Transforms the pose by the given transformation and returns the new pose.
units::meter_t Y() const
Returns the Y component of the pose's translation.
Definition: Pose3d.h:99
const Rotation3d & Rotation() const
Returns the underlying rotation.
Definition: Pose3d.h:113
Twist3d Log(const Pose3d &end) const
Returns a Twist3d that maps this pose to the end pose.
Pose3d(Translation3d translation, Rotation3d rotation)
Constructs a pose with the specified translation and rotation.
Pose3d Exp(const Twist3d &twist) const
Obtain a new Pose3d from a (constant curvature) velocity.
units::meter_t X() const
Returns the X component of the pose's translation.
Definition: Pose3d.h:92
const Translation3d & Translation() const
Returns the underlying translation.
Definition: Pose3d.h:85
Pose3d operator+(const Transform3d &other) const
Transforms the pose by the given transformation and returns the new transformed pose.
Pose3d operator*(double scalar) const
Multiplies the current pose by a scalar.
bool operator==(const Pose3d &) const =default
Checks equality between this Pose3d and another object.
Pose3d(const Pose2d &pose)
Constructs a 3D pose from a 2D pose in the X-Y plane.
Pose3d operator/(double scalar) const
Divides the current pose by a scalar.
units::meter_t Z() const
Returns the Z component of the pose's translation.
Definition: Pose3d.h:106
Transform3d operator-(const Pose3d &other) const
Returns the Transform3d that maps the one pose to another.
Pose3d(units::meter_t x, units::meter_t y, units::meter_t z, Rotation3d rotation)
Constructs a pose with x, y, and z translations instead of a separate Translation3d.
constexpr Pose3d()=default
Constructs a pose at the origin facing toward the positive X axis.
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
Represents a translation in 3D space.
Definition: Translation3d.h:27
a class to store JSON values
Definition: json.h:2655
const Scalar & y
Definition: MathFunctions.h:821
static EIGEN_DEPRECATED const end_t end
Definition: IndexedViewHelper.h:181
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
/file This file defines the SmallVector class.
Definition: AprilTagFieldLayout.h:18
A change in distance along a 3D arc since the last pose update.
Definition: Twist3d.h:22