Swerve Drive Kinematics

La clase SwerveDriveKinematics es una herramienta útil que convierte entre un objeto ChassisSpeeds a varios objetos SwerveModuleState , los cuales contienen velocidades y ángulos para cada módulo swerve de un robot.

Clase swerve module state

La clase SwerveModuleState contiene información de la velocidad y ángulo de un modo singular de swerve drive. El constructor para una SwerveModuleState toma dos argumentos, la velocidad de la llanta en el módulo, y el ángulo del módulo.

Nota

En Java, la velocidad de la llanta tiene que estar en metros por segundo. En C++, la librería de las unidades puede ser usada para proporcionar la velocidad usando cualquier unidad de velocidad lineal.

Nota

Un ángulo de 0 corresponde a los módulos orientados hacía adelante.

Construyendo los objetos cinemáticos.

La clase SwerveDriveKinematics acepta un número variable de argumentos del constructor, con cada argumento siendo la ubicación de un módulo swerve relativo al centro del robot (así como Translation2d. El número de argumentos del constructor corresponde al número de módulos swerve.

Nota

Un swerve drive tiene que tener 2 módulos o más.

Nota

En C++, la clase se planifica en función del número de módulos. Por lo tanto, al construir un objeto SwerveDriveKinematics como un miembro variable de una clase, el número de módulos debe ser pasado como un argumento de plantilla. Por ejemplo, para un swerve drive común con cuatro módulos, el objeto cinemático debe ser construido como: frc::SwerveDriveKinematics<4>m_kinematics{...}.

Las ubicaciones de los módulos deben ser relativas con el centro del robot. Los valores positivos x representan el movimiento hacía la parte delantera del robot, mientras que los calores positivos representan el movimiento del robot hacía la izquierda.

// Locations for the swerve drive modules relative to the robot center.
Translation2d m_frontLeftLocation = new Translation2d(0.381, 0.381);
Translation2d m_frontRightLocation = new Translation2d(0.381, -0.381);
Translation2d m_backLeftLocation = new Translation2d(-0.381, 0.381);
Translation2d m_backRightLocation = new Translation2d(-0.381, -0.381);

// Creating my kinematics object using the module locations
SwerveDriveKinematics m_kinematics = new SwerveDriveKinematics(
  m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation, m_backRightLocation
);

Convertir las velocidades del chasis a estados de los módulos

El método toSwerveModuleStates(ChassisSpeeds speeds) (Java) / ToSwerveModuleStates(ChassisSpeeds speeds) (C++) debe ser usado para convertir un objeto ChassisSpeeds a una matriz de objetos SwerveModuleState . Esto es útil en situaciones donde se tenga que convertir una velocidad hacía adelante, hacía los lados y una velocidad angular en estados de módulo individuales.

Los elementos en la matriz que se devuelven por este método son el mismo orden en el cual se construyó el objeto cinemático. Por ejemplo, si el objeto cinemático se construyó con la ubicación del módulo frontal izquierdo, la ubicación del módulo frontal derecho, la ubicación del módulo posterior izquierdo y la ubicación del módulo posterior derecho en ese orden, los elementos de la matriz serían el estado del módulo frontal izquierdo, el estado del módulo frontal derecho, el estado del módulo posterior izquierdo y el estado del módulo posterior derecho en ese orden.

// Example chassis speeds: 1 meter per second forward, 3 meters
// per second to the left, and rotation at 1.5 radians per second
// counterclockwise.
ChassisSpeeds speeds = new ChassisSpeeds(1.0, 3.0, 1.5);

// Convert to module states
SwerveModuleState[] moduleStates = kinematics.toSwerveModuleStates(speeds);

// Front left module state
SwerveModuleState frontLeft = moduleStates[0];

// Front right module state
SwerveModuleState frontRight = moduleStates[1];

// Back left module state
SwerveModuleState backLeft = moduleStates[2];

// Back right module state
SwerveModuleState backRight = moduleStates[3];

Optimización del ángulo del módulo

La clase SwerveModuleState contiene un método estático optimize() (Java) / Optimize() (C++) que se utiliza para «optimizar» la velocidad y el punto de ajuste del ángulo de un determinado SwerveModuleState para minimizar el cambio de rumbo. Por ejemplo, si el punto de ajuste angular de un cierto módulo de cinemática inversa es de 90 grados, pero su ángulo actual es de -89 grados, este método negará automáticamente la velocidad del punto de ajuste del módulo y hará que el punto de ajuste angular sea de -90 grados para reducir la distancia. el módulo tiene que viajar.

Este método toma dos parámetros: el estado deseado (generalmente del método toSwerveModuleStates) y el ángulo actual. Devolverá el nuevo estado optimizado que puede usar como punto de ajuste en su circuito de control de retroalimentación.

var frontLeftOptimized = SwerveModuleState.optimize(frontLeft,
   new Rotation2d(m_turningEncoder.getDistance()));

Field-oriented drive

Recuerde que un objeto ChassisSpeeds puede crearse a partir de un conjunto de velocidades deseadas orientadas al campo. Esta característica puede ser utilizada para obtener estados de módulo a partir de un conjunto de velocidades deseadas orientadas al campo.

// The desired field relative speed here is 2 meters per second
// toward the opponent's alliance station wall, and 2 meters per
// second toward the left field boundary. The desired rotation
// is a quarter of a rotation per second counterclockwise. The current
// robot angle is 45 degrees.
ChassisSpeeds speeds = ChassisSpeeds.fromFieldRelativeSpeeds(
  2.0, 2.0, Math.PI / 2.0, Rotation2d.fromDegrees(45.0));

// Now use this in our kinematics
SwerveModuleState[] moduleStates = kinematics.toSwerveModuleStates(speeds);

Usando centros de rotación personalizados

En ocasiones, girar alrededor de una esquina específica puede ser deseable para ciertas maniobras evasivas. Este tipo de comportamiento también es apoyado por las clases de WPILib. El mismo método ToSwerveModuleStates() acepta un segundo parámetro para el centro de rotación (así como``Translation2d``). Justo como la ubicación de las llantas, la Translation2d representa que el centro de rotación debe ser relativo al centro del robot.

Nota

Debido a que todos los robots son un marco rígido, las velocidades vx y vy del objeto ChassisSpeeds aplican a la totalidad del robot. Sin embargo, el omega  del objeto ChassisSpeeds se medirá desde el centro de rotación.

Por ejemplo, uno puede establecer el centro de rotación en un cierto módulo y si el objeto ChassisSpeeds tiene vx y vy de cero y un omega que no sea cero, el robot parecerá rotar alrededor de ese particular módulo swerve.

Convirtiendo estados de módulo a velocidades del chasis

También se puede usar el objeto cinemático para convertir un conjunto de objetos SwerveModuleState a un objeto ChassisSpeeds . El método toChassisSpeeds(SwerveModuleState... states) (Java) / ToChassisSpeeds(SwerveModuleState... states) (C++) puede usarse para lograr esto.

// Example module states
var frontLeftState = new SwerveModuleState(23.43, Rotation2d.fromDegrees(-140.19));
var frontRightState = new SwerveModuleState(23.43, Rotation2d.fromDegrees(-39.81));
var backLeftState = new SwerveModuleState(54.08, Rotation2d.fromDegrees(-109.44));
var backRightState = new SwerveModuleState(54.08, Rotation2d.fromDegrees(-70.56));

// Convert to chassis speeds
ChassisSpeeds chassisSpeeds = kinematics.toChassisSpeeds(
  frontLeftState, frontRightState, backLeftState, backRightState);

// Getting individual speeds
double forward = chassisSpeeds.vxMetersPerSecond;
double sideways = chassisSpeeds.vyMetersPerSecond;
double angular = chassisSpeeds.omegaRadiansPerSecond;