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