WPILibC++ 2023.4.3-108-ge5452e3
Rotation2d.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 "units/angle.h"
10
11namespace wpi {
12class json;
13} // namespace wpi
14
15namespace frc {
16
17/**
18 * A rotation in a 2D coordinate frame represented by a point on the unit circle
19 * (cosine and sine).
20 *
21 * The angle is continuous, that is if a Rotation2d is constructed with 361
22 * degrees, it will return 361 degrees. This allows algorithms that wouldn't
23 * want to see a discontinuity in the rotations as it sweeps past from 360 to 0
24 * on the second time around.
25 */
27 public:
28 /**
29 * Constructs a Rotation2d with a default angle of 0 degrees.
30 */
31 constexpr Rotation2d() = default;
32
33 /**
34 * Constructs a Rotation2d with the given radian value.
35 *
36 * @param value The value of the angle in radians.
37 */
38 constexpr Rotation2d(units::radian_t value); // NOLINT
39
40 /**
41 * Constructs a Rotation2d with the given degree value.
42 *
43 * @param value The value of the angle in degrees.
44 */
45 constexpr Rotation2d(units::degree_t value); // NOLINT
46
47 /**
48 * Constructs a Rotation2d with the given x and y (cosine and sine)
49 * components. The x and y don't have to be normalized.
50 *
51 * @param x The x component or cosine of the rotation.
52 * @param y The y component or sine of the rotation.
53 */
54 constexpr Rotation2d(double x, double y);
55
56 /**
57 * Adds two rotations together, with the result being bounded between -pi and
58 * pi.
59 *
60 * For example, <code>Rotation2d{30_deg} + Rotation2d{60_deg}</code> equals
61 * <code>Rotation2d{units::radian_t{std::numbers::pi/2.0}}</code>
62 *
63 * @param other The rotation to add.
64 *
65 * @return The sum of the two rotations.
66 */
67 constexpr Rotation2d operator+(const Rotation2d& other) const;
68
69 /**
70 * Subtracts the new rotation from the current rotation and returns the new
71 * rotation.
72 *
73 * For example, <code>Rotation2d{10_deg} - Rotation2d{100_deg}</code> equals
74 * <code>Rotation2d{units::radian_t{-std::numbers::pi/2.0}}</code>
75 *
76 * @param other The rotation to subtract.
77 *
78 * @return The difference between the two rotations.
79 */
80 constexpr Rotation2d operator-(const Rotation2d& other) const;
81
82 /**
83 * Takes the inverse of the current rotation. This is simply the negative of
84 * the current angular value.
85 *
86 * @return The inverse of the current rotation.
87 */
88 constexpr Rotation2d operator-() const;
89
90 /**
91 * Multiplies the current rotation by a scalar.
92 *
93 * @param scalar The scalar.
94 *
95 * @return The new scaled Rotation2d.
96 */
97 constexpr Rotation2d operator*(double scalar) const;
98
99 /**
100 * Divides the current rotation by a scalar.
101 *
102 * @param scalar The scalar.
103 *
104 * @return The new scaled Rotation2d.
105 */
106 constexpr Rotation2d operator/(double scalar) const;
107
108 /**
109 * Checks equality between this Rotation2d and another object.
110 *
111 * @param other The other object.
112 * @return Whether the two objects are equal.
113 */
114 constexpr bool operator==(const Rotation2d& other) const;
115
116 /**
117 * Adds the new rotation to the current rotation using a rotation matrix.
118 *
119 * <pre>
120 * [cos_new] [other.cos, -other.sin][cos]
121 * [sin_new] = [other.sin, other.cos][sin]
122 * value_new = std::atan2(sin_new, cos_new)
123 * </pre>
124 *
125 * @param other The rotation to rotate by.
126 *
127 * @return The new rotated Rotation2d.
128 */
129 constexpr Rotation2d RotateBy(const Rotation2d& other) const;
130
131 /**
132 * Returns the radian value of the rotation.
133 *
134 * @return The radian value of the rotation.
135 * @see AngleModulus to constrain the angle within (-pi, pi]
136 */
137 constexpr units::radian_t Radians() const { return m_value; }
138
139 /**
140 * Returns the degree value of the rotation.
141 *
142 * @return The degree value of the rotation.
143 * @see InputModulus to constrain the angle within (-180, 180]
144 */
145 constexpr units::degree_t Degrees() const { return m_value; }
146
147 /**
148 * Returns the cosine of the rotation.
149 *
150 * @return The cosine of the rotation.
151 */
152 constexpr double Cos() const { return m_cos; }
153
154 /**
155 * Returns the sine of the rotation.
156 *
157 * @return The sine of the rotation.
158 */
159 constexpr double Sin() const { return m_sin; }
160
161 /**
162 * Returns the tangent of the rotation.
163 *
164 * @return The tangent of the rotation.
165 */
166 constexpr double Tan() const { return Sin() / Cos(); }
167
168 private:
169 units::radian_t m_value = 0_rad;
170 double m_cos = 1;
171 double m_sin = 0;
172};
173
175void to_json(wpi::json& json, const Rotation2d& rotation);
176
178void from_json(const wpi::json& json, Rotation2d& rotation);
179
180} // namespace frc
181
182#include "Rotation2d.inc"
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const CwiseBinaryOp< internal::scalar_quotient_op< Scalar, typename OtherDerived::Scalar >, const Derived, const OtherDerived > operator/(const EIGEN_CURRENT_STORAGE_BASE_CLASS< OtherDerived > &other) const
Definition: ArrayCwiseBinaryOps.h:21
EIGEN_DEVICE_FUNC const NegativeReturnType operator-() const
Definition: CommonCwiseUnaryOps.h:45
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
Definition: Rotation2d.h:26
constexpr double Tan() const
Returns the tangent of the rotation.
Definition: Rotation2d.h:166
constexpr units::degree_t Degrees() const
Returns the degree value of the rotation.
Definition: Rotation2d.h:145
constexpr double Cos() const
Returns the cosine of the rotation.
Definition: Rotation2d.h:152
constexpr Rotation2d()=default
Constructs a Rotation2d with a default angle of 0 degrees.
constexpr double Sin() const
Returns the sine of the rotation.
Definition: Rotation2d.h:159
constexpr units::radian_t Radians() const
Returns the radian value of the rotation.
Definition: Rotation2d.h:137
Definition: core.h:1240
a class to store JSON values
Definition: json.h:2655
FMT_CONSTEXPR fp operator*(fp x, fp y)
Definition: format.h:1482
const Scalar & y
Definition: MathFunctions.h:821
Definition: AprilTagPoseEstimator.h:15
WPILIB_DLLEXPORT void from_json(const wpi::json &json, AprilTagFieldLayout &layout)
WPILIB_DLLEXPORT void to_json(wpi::json &json, const AprilTagFieldLayout &layout)
bool operator==(const Value &lhs, const Value &rhs)
unit< std::ratio< 1 >, units::category::scalar_unit > scalar
Definition: base.h:2521
constexpr unit_t< Units, T, NonLinearScale > operator+(const unit_t< Units, T, NonLinearScale > &u) noexcept
Definition: base.h:2339
Definition: AprilTagFieldLayout.h:18