13#include "units/angle.h"
14#include "units/angular_velocity.h"
15#include "units/length.h"
16#include "units/math.h"
17#include "units/velocity.h"
51 units::compound_unit<units::squared<units::radians>,
52 units::inverse<units::squared<units::meters>>>;
64 [[deprecated(
"Use LTVUnicycleController instead.")]]
66 units::unit_t<zeta_unit> zeta)
67 : m_b{b}, m_zeta{zeta} {}
78 [[deprecated(
"Use LTVUnicycleController instead.")]]
81 units::unit_t<zeta_unit>{0.7}} {}
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();
105 m_poseTolerance = poseTolerance;
121 units::meters_per_second_t linearVelocityRef,
122 units::radians_per_second_t angularVelocityRef) {
124 return ChassisSpeeds{linearVelocityRef, 0_mps, angularVelocityRef};
127 m_poseError = poseRef.
RelativeTo(currentPose);
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;
137 auto k = 2.0 * m_zeta *
138 units::math::sqrt(units::math::pow<2>(omegaRef) +
139 m_b * units::math::pow<2>(vRef));
144 vRef * m_poseError.Rotation().Cos() + k * eX, 0_mps,
145 omegaRef + k * eTheta + m_b * vRef * Sinc(eTheta) * eY};
160 return Calculate(currentPose, desiredState.
pose, desiredState.
velocity,
169 constexpr void SetEnabled(
bool enabled) { m_enabled = enabled; }
172 units::unit_t<b_unit> m_b;
173 units::unit_t<zeta_unit> m_zeta;
177 bool m_enabled =
true;
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()};
188 return units::math::sin(x) / x;
#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:326
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 ¤tPose, 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 ¤tPose, 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
#define WPI_IGNORE_DEPRECATED
Definition deprecated.h:16
#define WPI_UNIGNORE_DEPRECATED
Definition deprecated.h:27
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