WPILibC++ 2025.3.1
Loading...
Searching...
No Matches
RamseteController.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/deprecated.h>
9
10#include "frc/geometry/Pose2d.h"
13#include "units/angle.h"
15#include "units/length.h"
16#include "units/math.h"
17#include "units/velocity.h"
18
19namespace frc {
20
21/**
22 * Ramsete is a nonlinear time-varying feedback controller for unicycle models
23 * that drives the model to a desired pose along a two-dimensional trajectory.
24 * Why would we need a nonlinear control law in addition to the linear ones we
25 * have used so far like PID? If we use the original approach with PID
26 * controllers for left and right position and velocity states, the controllers
27 * only deal with the local pose. If the robot deviates from the path, there is
28 * no way for the controllers to correct and the robot may not reach the desired
29 * global pose. This is due to multiple endpoints existing for the robot which
30 * have the same encoder path arc lengths.
31 *
32 * Instead of using wheel path arc lengths (which are in the robot's local
33 * coordinate frame), nonlinear controllers like pure pursuit and Ramsete use
34 * global pose. The controller uses this extra information to guide a linear
35 * reference tracker like the PID controllers back in by adjusting the
36 * references of the PID controllers.
37 *
38 * The paper "Control of Wheeled Mobile Robots: An Experimental Overview"
39 * describes a nonlinear controller for a wheeled vehicle with unicycle-like
40 * kinematics; a global pose consisting of x, y, and theta; and a desired pose
41 * consisting of x_d, y_d, and theta_d. We call it Ramsete because that's the
42 * acronym for the title of the book it came from in Italian ("Robotica
43 * Articolata e Mobile per i SErvizi e le TEcnologie").
44 *
45 * See <https://file.tavsys.net/control/controls-engineering-in-frc.pdf> section
46 * on Ramsete unicycle controller for a derivation and analysis.
47 */
49 public:
50 using b_unit =
54
55 /**
56 * Construct a Ramsete unicycle controller.
57 *
58 * @param b Tuning parameter (b > 0 rad²/m²) for which larger values make
59 * convergence more aggressive like a proportional term.
60 * @param zeta Tuning parameter (0 rad⁻¹ < zeta < 1 rad⁻¹) for which larger
61 * values provide more damping in response.
62 * @deprecated Use LTVUnicycleController instead.
63 */
64 [[deprecated("Use LTVUnicycleController instead.")]]
67 : m_b{b}, m_zeta{zeta} {}
68
70
71 /**
72 * Construct a Ramsete unicycle controller. The default arguments for
73 * b and zeta of 2.0 rad²/m² and 0.7 rad⁻¹ have been well-tested to produce
74 * desirable results.
75 *
76 * @deprecated Use LTVUnicycleController instead.
77 */
78 [[deprecated("Use LTVUnicycleController instead.")]]
82
84
85 /**
86 * Returns true if the pose error is within tolerance of the reference.
87 */
88 constexpr bool AtReference() const {
89 const auto& eTranslate = m_poseError.Translation();
90 const auto& eRotate = m_poseError.Rotation();
91 const auto& tolTranslate = m_poseTolerance.Translation();
92 const auto& tolRotate = m_poseTolerance.Rotation();
93 return units::math::abs(eTranslate.X()) < tolTranslate.X() &&
94 units::math::abs(eTranslate.Y()) < tolTranslate.Y() &&
95 units::math::abs(eRotate.Radians()) < tolRotate.Radians();
96 }
97
98 /**
99 * Sets the pose error which is considered tolerable for use with
100 * AtReference().
101 *
102 * @param poseTolerance Pose error which is tolerable.
103 */
104 constexpr void SetTolerance(const Pose2d& poseTolerance) {
105 m_poseTolerance = poseTolerance;
106 }
107
108 /**
109 * Returns the next output of the Ramsete controller.
110 *
111 * The reference pose, linear velocity, and angular velocity should come from
112 * a drivetrain trajectory.
113 *
114 * @param currentPose The current pose.
115 * @param poseRef The desired pose.
116 * @param linearVelocityRef The desired linear velocity.
117 * @param angularVelocityRef The desired angular velocity.
118 */
120 const Pose2d& currentPose, const Pose2d& poseRef,
121 units::meters_per_second_t linearVelocityRef,
122 units::radians_per_second_t angularVelocityRef) {
123 if (!m_enabled) {
124 return ChassisSpeeds{linearVelocityRef, 0_mps, angularVelocityRef};
125 }
126
127 m_poseError = poseRef.RelativeTo(currentPose);
128
129 // Aliases for equation readability
130 const auto& eX = m_poseError.X();
131 const auto& eY = m_poseError.Y();
132 const auto& eTheta = m_poseError.Rotation().Radians();
133 const auto& vRef = linearVelocityRef;
134 const auto& omegaRef = angularVelocityRef;
135
136 // k = 2ζ√(ω_ref² + b v_ref²)
137 auto k = 2.0 * m_zeta *
139 m_b * units::math::pow<2>(vRef));
140
141 // v_cmd = v_ref cos(e_θ) + k e_x
142 // ω_cmd = ω_ref + k e_θ + b v_ref sinc(e_θ) e_y
143 return ChassisSpeeds{
144 vRef * m_poseError.Rotation().Cos() + k * eX, 0_mps,
145 omegaRef + k * eTheta + m_b * vRef * Sinc(eTheta) * eY};
146 }
147
148 /**
149 * Returns the next output of the Ramsete controller.
150 *
151 * The reference pose, linear velocity, and angular velocity should come from
152 * a drivetrain trajectory.
153 *
154 * @param currentPose The current pose.
155 * @param desiredState The desired pose, linear velocity, and angular velocity
156 * from a trajectory.
157 */
158 constexpr ChassisSpeeds Calculate(const Pose2d& currentPose,
159 const Trajectory::State& desiredState) {
160 return Calculate(currentPose, desiredState.pose, desiredState.velocity,
161 desiredState.velocity * desiredState.curvature);
162 }
163
164 /**
165 * Enables and disables the controller for troubleshooting purposes.
166 *
167 * @param enabled If the controller is enabled or not.
168 */
169 constexpr void SetEnabled(bool enabled) { m_enabled = enabled; }
170
171 private:
174
175 Pose2d m_poseError;
176 Pose2d m_poseTolerance;
177 bool m_enabled = true;
178
179 /**
180 * Returns sin(x) / x.
181 *
182 * @param x Value of which to take sinc(x).
183 */
184 static constexpr decltype(1 / 1_rad) Sinc(units::radian_t x) {
185 if (units::math::abs(x) < 1e-9_rad) {
186 return decltype(1 / 1_rad){1.0 - 1.0 / 6.0 * x.value() * x.value()};
187 } else {
188 return units::math::sin(x) / x;
189 }
190 }
191};
192
193} // namespace frc
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
Represents a 2D pose containing translational and rotational elements.
Definition Pose2d.h:28
constexpr units::meter_t X() const
Returns the X component of the pose's translation.
Definition Pose2d.h:114
constexpr Pose2d RelativeTo(const Pose2d &other) const
Returns the current pose relative to the given pose.
Definition Pose2d.h:318
Ramsete is a nonlinear time-varying feedback controller for unicycle models that drives the model to ...
Definition RamseteController.h:48
constexpr void SetEnabled(bool enabled)
Enables and disables the controller for troubleshooting purposes.
Definition RamseteController.h:169
constexpr RamseteController(units::unit_t< b_unit > b, units::unit_t< zeta_unit > zeta)
Construct a Ramsete unicycle controller.
Definition RamseteController.h:65
constexpr ChassisSpeeds Calculate(const Pose2d &currentPose, const Pose2d &poseRef, units::meters_per_second_t linearVelocityRef, units::radians_per_second_t angularVelocityRef)
Returns the next output of the Ramsete controller.
Definition RamseteController.h:119
units::inverse< units::radians > zeta_unit
Definition RamseteController.h:53
units::compound_unit< units::squared< units::radians >, units::inverse< units::squared< units::meters > > > b_unit
Definition RamseteController.h:50
WPI_UNIGNORE_DEPRECATED constexpr bool AtReference() const
Returns true if the pose error is within tolerance of the reference.
Definition RamseteController.h:88
constexpr ChassisSpeeds Calculate(const Pose2d &currentPose, const Trajectory::State &desiredState)
Returns the next output of the Ramsete controller.
Definition RamseteController.h:158
constexpr void SetTolerance(const Pose2d &poseTolerance)
Sets the pose error which is considered tolerable for use with AtReference().
Definition RamseteController.h:104
WPI_IGNORE_DEPRECATED constexpr RamseteController()
Construct a Ramsete unicycle controller.
Definition RamseteController.h:79
Container for values which represent quantities of a given unit.
Definition base.h:1930
#define WPI_IGNORE_DEPRECATED
Definition deprecated.h:16
#define WPI_UNIGNORE_DEPRECATED
Definition deprecated.h:27
typename units::detail::inverse_impl< U >::type inverse
represents the inverse unit type of class U.
Definition base.h:1138
constexpr UnitType abs(const UnitType x) noexcept
Compute absolute value.
Definition math.h:726
constexpr auto sqrt(const UnitType &value) noexcept -> unit_t< square_root< typename units::traits::unit_t_traits< UnitType >::unit_type >, typename units::traits::unit_t_traits< UnitType >::underlying_type, linear_scale >
computes the square root of value
Definition math.h:485
constexpr dimensionless::scalar_t sin(const AngleUnit angle) noexcept
Compute sine.
Definition math.h:83
typename units::detail::compound_impl< U, Us... >::type compound_unit
Represents a unit type made up from other units.
Definition base.h:1438
Definition CAN.h:11
constexpr auto pow(const UnitType &value) noexcept -> unit_t< typename units::detail::power_of_unit< power, typename units::traits::unit_t_traits< UnitType >::unit_type >::type, typename units::traits::unit_t_traits< UnitType >::underlying_type, linear_scale >
computes the value of value raised to the power
Definition base.h:2810
Unit Conversion Library namespace.
Definition acceleration.h:33
Represents the speed of a robot chassis.
Definition ChassisSpeeds.h:25
Represents one point on the trajectory.
Definition Trajectory.h:34
Pose2d pose
The pose at that point of the trajectory.
Definition Trajectory.h:45
units::meters_per_second_t velocity
The speed at that point of the trajectory.
Definition Trajectory.h:39
units::curvature_t curvature
The curvature at that point of the trajectory.
Definition Trajectory.h:48