WPILibC++ 2024.3.2
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
13#include "units/length.h"
14#include "units/velocity.h"
15
16namespace frc {
17
18/**
19 * Ramsete is a nonlinear time-varying feedback controller for unicycle models
20 * that drives the model to a desired pose along a two-dimensional trajectory.
21 * Why would we need a nonlinear control law in addition to the linear ones we
22 * have used so far like PID? If we use the original approach with PID
23 * controllers for left and right position and velocity states, the controllers
24 * only deal with the local pose. If the robot deviates from the path, there is
25 * no way for the controllers to correct and the robot may not reach the desired
26 * global pose. This is due to multiple endpoints existing for the robot which
27 * have the same encoder path arc lengths.
28 *
29 * Instead of using wheel path arc lengths (which are in the robot's local
30 * coordinate frame), nonlinear controllers like pure pursuit and Ramsete use
31 * global pose. The controller uses this extra information to guide a linear
32 * reference tracker like the PID controllers back in by adjusting the
33 * references of the PID controllers.
34 *
35 * The paper "Control of Wheeled Mobile Robots: An Experimental Overview"
36 * describes a nonlinear controller for a wheeled vehicle with unicycle-like
37 * kinematics; a global pose consisting of x, y, and theta; and a desired pose
38 * consisting of x_d, y_d, and theta_d. We call it Ramsete because that's the
39 * acronym for the title of the book it came from in Italian ("Robotica
40 * Articolata e Mobile per i SErvizi e le TEcnologie").
41 *
42 * See <https://file.tavsys.net/control/controls-engineering-in-frc.pdf> section
43 * on Ramsete unicycle controller for a derivation and analysis.
44 */
46 public:
47 using b_unit =
51
52 /**
53 * Construct a Ramsete unicycle controller.
54 *
55 * @param b Tuning parameter (b > 0 rad²/m²) for which larger values make
56 * convergence more aggressive like a proportional term.
57 * @param zeta Tuning parameter (0 rad⁻¹ < zeta < 1 rad⁻¹) for which larger
58 * values provide more damping in response.
59 */
61
62 /**
63 * Construct a Ramsete unicycle controller. The default arguments for
64 * b and zeta of 2.0 rad²/m² and 0.7 rad⁻¹ have been well-tested to produce
65 * desirable results.
66 */
68
69 /**
70 * Returns true if the pose error is within tolerance of the reference.
71 */
72 bool AtReference() const;
73
74 /**
75 * Sets the pose error which is considered tolerable for use with
76 * AtReference().
77 *
78 * @param poseTolerance Pose error which is tolerable.
79 */
80 void SetTolerance(const Pose2d& poseTolerance);
81
82 /**
83 * Returns the next output of the Ramsete controller.
84 *
85 * The reference pose, linear velocity, and angular velocity should come from
86 * a drivetrain trajectory.
87 *
88 * @param currentPose The current pose.
89 * @param poseRef The desired pose.
90 * @param linearVelocityRef The desired linear velocity.
91 * @param angularVelocityRef The desired angular velocity.
92 */
93 ChassisSpeeds Calculate(const Pose2d& currentPose, const Pose2d& poseRef,
94 units::meters_per_second_t linearVelocityRef,
95 units::radians_per_second_t angularVelocityRef);
96
97 /**
98 * Returns the next output of the Ramsete controller.
99 *
100 * The reference pose, linear velocity, and angular velocity should come from
101 * a drivetrain trajectory.
102 *
103 * @param currentPose The current pose.
104 * @param desiredState The desired pose, linear velocity, and angular velocity
105 * from a trajectory.
106 */
107 ChassisSpeeds Calculate(const Pose2d& currentPose,
108 const Trajectory::State& desiredState);
109
110 /**
111 * Enables and disables the controller for troubleshooting purposes.
112 *
113 * @param enabled If the controller is enabled or not.
114 */
115 void SetEnabled(bool enabled);
116
117 private:
120
121 Pose2d m_poseError;
122 Pose2d m_poseTolerance;
123 bool m_enabled = true;
124};
125
126} // namespace frc
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Represents a 2D pose containing translational and rotational elements.
Definition: Pose2d.h:23
Ramsete is a nonlinear time-varying feedback controller for unicycle models that drives the model to ...
Definition: RamseteController.h:45
RamseteController(units::unit_t< b_unit > b, units::unit_t< zeta_unit > zeta)
Construct a Ramsete unicycle controller.
ChassisSpeeds Calculate(const Pose2d &currentPose, const Trajectory::State &desiredState)
Returns the next output of the Ramsete controller.
void SetEnabled(bool enabled)
Enables and disables the controller for troubleshooting purposes.
void SetTolerance(const Pose2d &poseTolerance)
Sets the pose error which is considered tolerable for use with AtReference().
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.
units::inverse< units::radians > zeta_unit
Definition: RamseteController.h:50
units::compound_unit< units::squared< units::radians >, units::inverse< units::squared< units::meters > > > b_unit
Definition: RamseteController.h:49
RamseteController()
Construct a Ramsete unicycle controller.
bool AtReference() const
Returns true if the pose error is within tolerance of the reference.
typename units::detail::inverse_impl< U >::type inverse
represents the inverse unit type of class U.
Definition: base.h:1134
typename units::detail::compound_impl< U, Us... >::type compound_unit
Represents a unit type made up from other units.
Definition: base.h:1434
Definition: AprilTagPoseEstimator.h:15
b
Definition: data.h:44
Represents the speed of a robot chassis.
Definition: ChassisSpeeds.h:25
Represents one point on the trajectory.
Definition: Trajectory.h:30