Controlador ramsete

El controlador Ramsete es un rastreador de trayectoria integrado en WPILib. Este rastreador se puede utilizar para rastrear trayectorias con precisión con corrección de perturbaciones menores.

Construcción del objeto controlador Ramsete

El controlador Ramsete debe inicializarse con dos ganancias, a saber, b y zeta. Los valores más altos de b hacen que la convergencia sea más agresiva como un término proporcional, mientras que los valores más altos de zeta proporcionan más amortiguación en la respuesta. Estas ganancias del controlador solo dictan cómo el controlador generará velocidades ajustadas. NO afecta el seguimiento de la velocidad real del robot. Esto significa que estas ganancias del controlador son generalmente independientes del robot.

Nota

Las ganancias de 2.0 y 0.7``para ``b y zeta se han probado repetidamente para producir resultados deseables cuando todas las unidades estaban en metros. Como tal, existe un constructor de argumento cero para RamseteController con ganancias predeterminadas a estos valores.

// Using the default constructor of RamseteController. Here
// the gains are initialized to 2.0 and 0.7.
RamseteController controller1 = new RamseteController();

// Using the secondary constructor of RamseteController where
// the user can choose any other gains.
RamseteController controller2 = new RamseteController(2.1, 0.8);
// Using the default constructor of RamseteController. Here
// the gains are initialized to 2.0 and 0.7.
frc::RamseteController controller1;

// Using the secondary constructor of RamseteController where
// the user can choose any other gains.
frc::RamseteController controller2{2.1, 0.8};
from wpimath.controller import RamseteController

# Using the default constructor of RamseteController. Here
# the gains are initialized to 2.0 and 0.7.
controller1 = RamseteController()

# Using the secondary constructor of RamseteController where
# the user can choose any other gains.
controller2 = RamseteController(2.1, 0.8)

Obtener velocidades ajustadas

El controlador Ramsete devuelve «velocidades ajustadas» de modo que cuando el robot rastrea estas velocidades, alcanza con precisión el punto objetivo. El controlador debe actualizarse periódicamente con el nuevo objetivo. El objetivo comprende una pose deseada, una velocidad lineal deseada y una velocidad angular deseada. Además, la posición actual del robot también debe actualizarse periódicamente. El controlador usa estos cuatro argumentos para devolver la velocidad lineal y angular ajustada. Los usuarios deben ordenar a su robot estas velocidades lineales y angulares para lograr un seguimiento de trayectoria óptimo.

Nota

The «goal pose» represents the position that the robot should be at a particular timestep when tracking the trajectory. It does NOT represent the final endpoint of the trajectory.

The controller can be updated using the Calculate (C++) / calculate (Java/Python) method. There are two overloads for this method. Both of these overloads accept the current robot position as the first parameter. For the other parameters, one of these overloads takes in the goal as three separate parameters (pose, linear velocity, and angular velocity) whereas the other overload accepts a Trajectory.State object, which contains information about the goal pose. For its ease, users should use the latter method when tracking trajectories.

Trajectory.State goal = trajectory.sample(3.4); // sample the trajectory at 3.4 seconds from the beginning
ChassisSpeeds adjustedSpeeds = controller.calculate(currentRobotPose, goal);
const Trajectory::State goal = trajectory.Sample(3.4_s); // sample the trajectory at 3.4 seconds from the beginning
ChassisSpeeds adjustedSpeeds = controller.Calculate(currentRobotPose, goal);
goal = trajectory.sample(3.4)  # sample the trajectory at 3.4 seconds from the beginning
adjustedSpeeds = controller.calculate(currentRobotPose, goal)

Estos cálculos deben realizarse en cada iteración de bucle, con una posición y un objetivo actualizados del robot.

Usando las velocidades ajustadas

Las velocidades ajustadas son del tipo ChassisSpeeds, que contiene un vx (velocidad lineal en la dirección de avance), una vy (velocidad lineal en la dirección lateral) y un omega (velocidad angular alrededor del centro del marco del robot). Debido a que el controlador Ramsete es un controlador para robots no holonómicos (robots que no pueden moverse hacia los lados), el objeto de velocidades ajustadas tiene una vy de cero.

Las velocidades ajustadas de regreso pueden ser convertidas a velocidades para usar utilizando las clases cinemáticas para el tipo de chasis. Por ejemplo, las velocidades ajustadas pueden convertirse en velocidades de derecha e izquierda para un manejo diferencial usando el objeto DifferentialDriveKinematics.

ChassisSpeeds adjustedSpeeds = controller.calculate(currentRobotPose, goal);
DifferentialDriveWheelSpeeds wheelSpeeds = kinematics.toWheelSpeeds(adjustedSpeeds);
double left = wheelSpeeds.leftMetersPerSecond;
double right = wheelSpeeds.rightMetersPerSecond;
ChassisSpeeds adjustedSpeeds = controller.Calculate(currentRobotPose, goal);
DifferentialDriveWheelSpeeds wheelSpeeds = kinematics.ToWheelSpeeds(adjustedSpeeds);
auto [left, right] = kinematics.ToWheelSpeeds(adjustedSpeeds);
adjustedSpeeds = controller.calculate(currentRobotPose, goal)
wheelSpeeds = kinematics.toWheelSpeeds(adjustedSpeeds)
left = wheelSpeeds.left
right = wheelSpeeds.right

Because these new left and right velocities are still speeds and not voltages, two PID Controllers, one for each side may be used to track these velocities. Either the WPILib PIDController (C++, Java, Python) can be used, or the Velocity PID feature on smart motor controllers such as the TalonSRX and the SPARK MAX can be used.

Ramsete en el Framework con base comando

Con motivos de facilitar a los usuarios, la clase RamseteCommand está contruida en WPILib. Para un tutorial completo en la implementación de un autónomo que siga un camino usando RamseteCommand, vea Trajectory Tutorial.