Class RamseteController
public class RamseteController extends Object
Instead of using wheel path arc lengths (which are in the robot's local coordinate frame), nonlinear controllers like pure pursuit and Ramsete use global pose. The controller uses this extra information to guide a linear reference tracker like the PID controllers back in by adjusting the references of the PID controllers.
The paper "Control of Wheeled Mobile Robots: An Experimental Overview" describes a nonlinear controller for a wheeled vehicle with unicycle-like kinematics; a global pose consisting of x, y, and theta; and a desired pose consisting of x_d, y_d, and theta_d. We call it Ramsete because that's the acronym for the title of the book it came from in Italian ("Robotica Articolata e Mobile per i SErvizi e le TEcnologie").
See Controls Engineering in the FIRST Robotics Competition section on Ramsete unicycle controller for a derivation and analysis.
-
Constructor Summary
Constructors Constructor Description RamseteController()
Construct a Ramsete unicycle controller.RamseteController(double b, double zeta)
Construct a Ramsete unicycle controller. -
Method Summary
Modifier and Type Method Description boolean
atReference()
Returns true if the pose error is within tolerance of the reference.ChassisSpeeds
calculate(Pose2d currentPose, Pose2d poseRef, double linearVelocityRefMeters, double angularVelocityRefRadiansPerSecond)
Returns the next output of the Ramsete controller.ChassisSpeeds
calculate(Pose2d currentPose, Trajectory.State desiredState)
Returns the next output of the Ramsete controller.void
setEnabled(boolean enabled)
Enables and disables the controller for troubleshooting purposes.void
setTolerance(Pose2d poseTolerance)
Sets the pose error which is considered tolerable for use with atReference().
-
Constructor Details
-
RamseteController
Construct a Ramsete unicycle controller.- Parameters:
b
- Tuning parameter (b > 0 rad²/m²) for which larger values make convergence more aggressive like a proportional term.zeta
- Tuning parameter (0 rad⁻¹ < zeta < 1 rad⁻¹) for which larger values provide more damping in response.
-
RamseteController
public RamseteController()Construct a Ramsete unicycle controller. The default arguments for b and zeta of 2.0 rad²/m² and 0.7 rad⁻¹ have been well-tested to produce desirable results.
-
-
Method Details
-
atReference
Returns true if the pose error is within tolerance of the reference.- Returns:
- True if the pose error is within tolerance of the reference.
-
setTolerance
Sets the pose error which is considered tolerable for use with atReference().- Parameters:
poseTolerance
- Pose error which is tolerable.
-
calculate
public ChassisSpeeds calculate(Pose2d currentPose, Pose2d poseRef, double linearVelocityRefMeters, double angularVelocityRefRadiansPerSecond)Returns the next output of the Ramsete controller.The reference pose, linear velocity, and angular velocity should come from a drivetrain trajectory.
- Parameters:
currentPose
- The current pose.poseRef
- The desired pose.linearVelocityRefMeters
- The desired linear velocity in meters per second.angularVelocityRefRadiansPerSecond
- The desired angular velocity in radians per second.- Returns:
- The next controller output.
-
calculate
Returns the next output of the Ramsete controller.The reference pose, linear velocity, and angular velocity should come from a drivetrain trajectory.
- Parameters:
currentPose
- The current pose.desiredState
- The desired pose, linear velocity, and angular velocity from a trajectory.- Returns:
- The next controller output.
-
setEnabled
Enables and disables the controller for troubleshooting purposes.- Parameters:
enabled
- If the controller is enabled or not.
-