Class RamseteController


  • public class RamseteController
    extends Object
    Ramsete is a nonlinear time-varying feedback controller for unicycle models that drives the model to a desired pose along a two-dimensional trajectory. Why would we need a nonlinear control law in addition to the linear ones we have used so far like PID? If we use the original approach with PID controllers for left and right position and velocity states, the controllers only deal with the local pose. If the robot deviates from the path, there is no way for the controllers to correct and the robot may not reach the desired global pose. This is due to multiple endpoints existing for the robot which have the same encoder path arc lengths.

    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 Detail

      • RamseteController

        public RamseteController​(double b,
                                 double zeta)
        Construct a Ramsete unicycle controller.
        Parameters:
        b - Tuning parameter (b > 0) for which larger values make convergence more aggressive like a proportional term.
        zeta - Tuning parameter (0 < zeta < 1) 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 and 0.7 have been well-tested to produce desireable results.
    • Method Detail

      • atReference

        public boolean atReference()
        Returns true if the pose error is within tolerance of the reference.
      • setTolerance

        public void setTolerance​(Pose2d poseTolerance)
        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.
        angularVelocityRefRadiansPerSecond - The desired angular velocity in meters.
      • calculate

        public ChassisSpeeds calculate​(Pose2d currentPose,
                                       Trajectory.State desiredState)
        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.
      • setEnabled

        public void setEnabled​(boolean enabled)
        Enables and disables the controller for troubleshooting purposes.
        Parameters:
        enabled - If the controller is enabled or not.