Creación de perfiles de movimiento a través de los subsistemas TrapezoidProfile y los comandos TrapezoidProfile

Nota

Para obtener una descripción de las funciones de creación de perfiles de movimiento de WPILib utilizadas por estos contenedores basados en comandos, consulte Perfil de movimiento trapezoidal en WPILib.

Nota

Los contenedores de comando TrapezoidProfile generalmente están destinados a la composición con controladores personalizados o externos. Para combinar la creación de perfiles de movimiento trapezoidal con el PIDController de WPILib, consulte Combinando Motion Profiling y PID Basado en Comandos.

Cuando se controla un mecanismo, a menudo es deseable moverlo suavemente entre dos posiciones, en lugar de cambiar bruscamente su punto de ajuste. Esto se llama «perfil de movimiento», y es soportado en WPILib a través de la clase TrapezoidProfile (Java, C++).

Para ayudar aún más a los equipos a integrar la creación de perfiles de movimiento en sus proyectos de robots basados en comandos, WPILib incluye dos envoltorios de conveniencia para la clase TrapezoidProfile: TrapezoidProfileSubsystem, que genera y ejecuta automáticamente perfiles de movimiento en su método periodic() , y el``TrapezoidProfileCommand``, que ejecuta un único TrapezoidProfile proporcionado por el usuario.

TrapezoideProfileSubsystem

Nota

En C ++, la clase TrapezoidProfileSubsystem se basa en el tipo de unidad utilizada para las mediciones de distancia, que puede ser angular o lineal. Los valores pasados deben tener unidades consistentes con las unidades de distancia, o se lanzará un error en tiempo de compilación. Para obtener más información sobre las unidades C ++, consulte Biblioteca de unidades de C++.

La clase TrapezoidProfileSubsystem (Java, C++) creará y ejecutará automáticamente perfiles de movimiento trapezoidales para alcanzar el estado que se quiera, proporcionado por el usuario. Para utilizar la clase TrapezoidProfileSubsystem, los usuarios deben crear una subclase de la misma.

Creación de un subsistema de perfil trapezoidal

Al subclasificar TrapezoidProfileSubsystem, los usuarios deben anular un único método abstracto para proporcionar la funcionalidad que la clase usará en su operación ordinaria:

useState()

protected abstract void useState(TrapezoidProfile.State state);

El método useState() consume el estado actual del perfil de movimiento. El TrapezoidProfileSubsystem llamará automáticamente a este método desde su bloque periodic() y le pasará el estado del perfil de movimiento correspondiente al progreso actual del subsistema a través del perfil de movimiento.

Los usuarios pueden hacer lo que quieran con este estado; un caso de uso típico (como se muestra en el Full TrapezoidProfileSubsystem Example) es usar el estado para obtener un punto de ajuste y un avance para un controlador de motor «inteligente» externo.

Parámetros de constructor

Los usuarios deben pasar un conjunto de TrapezoidProfile.Constraints a la clase base TrapezoidProfileSubsystem a través de la llamada al constructor de superclase de su subclase. Esto sirve para restringir los perfiles generados automáticamente a una velocidad y aceleración máximas determinadas.

Los usuarios también deben pasar en una posición inicial para el mecanismo.

Los usuarios avanzados pueden pasar un valor alternativo para el período de bucle, si se está utilizando un período de bucle principal no estándar.

Uso de un TrapezoidProfileSubsystem

Una vez que se ha creado una instancia de una subclase TrapezoidProfileSubsystem, los comandos pueden usarla a través de los siguientes métodos:

setGoal()

Nota

Si desea establecer el objetivo en una distancia simple con una velocidad objetivo implícita de cero, existe una sobrecarga de setGoal() que toma un valor de distancia único, en lugar de un estado de perfil de movimiento completo.

El método setGoal() se puede utilizar para establecer el estado objetivo del TrapezoidProfileSubsystem. El subsistema ejecutará automáticamente un perfil para el objetivo, pasando el estado actual en cada iteración al método useState() proporcionado.

// The subsystem will execute a profile to a position of 5 and a velocity of 3.
examplePIDSubsystem.setGoal(new TrapezoidProfile.Goal(5, 3);

Ejemplo completo de TrapezoidProfileSubsystem

¿Qué aspecto tiene un TrapezoidProfileSubsystem cuando se utiliza en la práctica? Los siguientes ejemplos están tomados del proyecto de ejemplo ArmbotOffobard (Java, C++):

 8
 9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
package edu.wpi.first.wpilibj.examples.armbotoffboard.subsystems;

import edu.wpi.first.wpilibj.controller.ArmFeedforward;
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
import edu.wpi.first.wpilibj2.command.TrapezoidProfileSubsystem;

import edu.wpi.first.wpilibj.examples.armbotoffboard.Constants.ArmConstants;
import edu.wpi.first.wpilibj.examples.armbotoffboard.ExampleSmartMotorController;

/**
 * A robot arm subsystem that moves with a motion profile.
 */
public class ArmSubsystem extends TrapezoidProfileSubsystem {
  private final ExampleSmartMotorController m_motor =
      new ExampleSmartMotorController(ArmConstants.kMotorPort);
  private final ArmFeedforward m_feedforward =
      new ArmFeedforward(ArmConstants.kSVolts, ArmConstants.kCosVolts,
                         ArmConstants.kVVoltSecondPerRad, ArmConstants.kAVoltSecondSquaredPerRad);

  /**
   * Create a new ArmSubsystem.
   */
  public ArmSubsystem() {
    super(new TrapezoidProfile.Constraints(ArmConstants.kMaxVelocityRadPerSecond,
                                           ArmConstants.kMaxAccelerationRadPerSecSquared),
          ArmConstants.kArmOffsetRads);
    m_motor.setPID(ArmConstants.kP, 0, 0);
  }

  @Override
  public void useState(TrapezoidProfile.State setpoint) {
    // Calculate the feedforward from the sepoint
    double feedforward = m_feedforward.calculate(setpoint.position, setpoint.velocity);
    // Add the feedforward to the PID output to get the motor output
    m_motor.setSetpoint(ExampleSmartMotorController.PIDMode.kPosition, setpoint.position,
                        feedforward / 12.0);
  }
}

Usar un TrapezoidProfileSubsystem con comandos puede ser bastante simple:

63
64
65
66
67
68
69
    // Move the arm to 2 radians above horizontal when the 'A' button is pressed.
    new JoystickButton(m_driverController, Button.kA.value)
        .whenPressed(() -> m_robotArm.setGoal(2), m_robotArm);

    // Move the arm to neutral position when the 'B' button is pressed.
    new JoystickButton(m_driverController, Button.kB.value)
        .whenPressed(() -> m_robotArm.setGoal(Constants.ArmConstants.kArmOffsetRads), m_robotArm);

Comando TrapezoideProfile

Nota

En C++, la clase TrapezoidProfileCommand se basa en el tipo de unidad utilizada para las mediciones de distancia, que puede ser angular o lineal. Los valores pasados deben tener unidades consistentes con las unidades de distancia, o se lanzará un error en tiempo de compilación. Para obtener más información sobre las unidades C++, consulte Biblioteca de unidades de C++.

La clase TrapezoidProfileCommand (Java, C++) permite a los usuarios crear un comando que ejecutará un único TrapezoidProfile, pasando su estado actual en cada iteración a una función definida por el usuario.

Al igual que con TrapezoidProfileSubsystem, los usuarios pueden crear un TrapezoidProfileCommand subclasificando la clase TrapezoidProfileCommand. Sin embargo, como ocurre con muchas de las otras clases de comandos de la biblioteca basada en comandos, los usuarios pueden querer guardar el código definiendo un TrapezoidProfileCommand inline.

Creando un TrapezoidProfileCommand

Se puede crear un TrapezoidProfileCommand de dos maneras: subclasificando la clase TrapezoidProfileCommand o definiendo el comando inline. En ambos métodos son extremadamente similares y por último la elección de cuál usar se reduce al lugar donde el usuario desea que se ubique el código relevante.

En cualquier caso, se crea un TrapezoidProfileCommand pasando los parámetros necesarios a su constructor (si se define una subclase, esto se puede hacer con una llamada super ()):

28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
  /**
   * Creates a new TrapezoidProfileCommand that will execute the given {@link TrapezoidProfile}.
   * Output will be piped to the provided consumer function.
   *
   * @param profile      The motion profile to execute.
   * @param output       The consumer for the profile output.
   * @param requirements The subsystems required by this command.
   */
  public TrapezoidProfileCommand(TrapezoidProfile profile,
                                 Consumer<State> output,
                                 Subsystem... requirements) {
    m_profile = requireNonNullParam(profile, "profile", "TrapezoidProfileCommand");
    m_output = requireNonNullParam(output, "output", "TrapezoidProfileCommand");
    addRequirements(requirements);
  }

profile

El parámetro profile es el objeto TrapezoidProfile que será ejecutado por el comando. Al pasar esto, los usuarios especifican el estado inicial, el estado final y las restricciones de movimiento del perfil que usará el comando.

output

El parámetro output es una función (normalmente pasada como lambda) que consume la salida y el punto de ajuste del lazo de control. Pasar la función useOutput en PIDCommand es funcionalmente análogo a anular la función useState() en PIDSubsystem.

requisitos

Como todos los comandos en línea, TrapezoidProfileCommand permite al usuario especificar los requisitos de su subsistema como un parámetro de constructor.

Ejemplo completo de TrapezoidProfileCommand

¿Qué aspecto tiene un TrapezoidProfileSubsystem cuando se utiliza en la práctica? Los siguientes ejemplos están tomados del proyecto de ejemplo DriveDistanceOffboard (Java, C++):

 8
 9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
package edu.wpi.first.wpilibj.examples.drivedistanceoffboard.commands;

import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
import edu.wpi.first.wpilibj2.command.TrapezoidProfileCommand;

import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.Constants.DriveConstants;
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.subsystems.DriveSubsystem;

/**
 * Drives a set distance using a motion profile.
 */
public class DriveDistanceProfiled extends TrapezoidProfileCommand {
  /**
   * Creates a new DriveDistanceProfiled command.
   *
   * @param meters The distance to drive.
   * @param drive The drive subsystem to use.
   */
  public DriveDistanceProfiled(double meters, DriveSubsystem drive) {
    super(
        new TrapezoidProfile(
            // Limit the max acceleration and velocity
            new TrapezoidProfile.Constraints(DriveConstants.kMaxSpeedMetersPerSecond,
                                             DriveConstants.kMaxAccelerationMetersPerSecondSquared),
            // End at desired position in meters; implicitly starts at 0
            new TrapezoidProfile.State(meters, 0)),
        // Pipe the profile state to the drive
        setpointState -> drive.setDriveStates(setpointState, setpointState),
        // Require the drive
        drive);
    // Reset drive encoders since we're starting at 0
    drive.resetEncoders();
  }
}

Y, para un ejemplo inlined

68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
    // Do the same thing as above when the 'B' button is pressed, but defined inline
    new JoystickButton(m_driverController, Button.kB.value)
        .whenPressed(
            new TrapezoidProfileCommand(
                new TrapezoidProfile(
                    // Limit the max acceleration and velocity
                    new TrapezoidProfile.Constraints(
                        DriveConstants.kMaxSpeedMetersPerSecond,
                        DriveConstants.kMaxAccelerationMetersPerSecondSquared),
                    // End at desired position in meters; implicitly starts at 0
                    new TrapezoidProfile.State(3, 0)),
                // Pipe the profile state to the drive
                setpointState -> m_robotDrive.setDriveStates(
                    setpointState,
                    setpointState),
                // Require the drive
                m_robotDrive)
                .beforeStarting(m_robotDrive::resetEncoders)
                .withTimeout(10));