La cinématique de l’entraînement de type « à embardée » (Swerve)

N.D.T. (le mot « Swerve » sera utilisé tout le long de cette page, afin d’alléger le texte). La classe SwerveDriveKinematics est un outil utile qui convertit entre un objet ChassisSpeeds et plusieurs objets SwerveModuleState, qui contient les vitesses et les angles pour chaque module Swerve d’un robot avec entraînement de ce type.

La classe d’état du module swerve

La classe SwerveModuleState contient des informations sur la vitesse et l’angle d’un seul module Swerve. Le constructeur d’un SwerveModuleState prend deux arguments, la vitesse de la roue sur le module et l’angle du module.

Note

En Java, la vitesse de la roue doit être en mètres par seconde. En C ++, la librairie d’unités peut être utilisée pour fournir la vitesse en utilisant n’importe quelle unité de vitesse linéaire.

Note

Un angle de 0 correspond aux modules tournés vers l’avant.

Construction de l’objet cinématique

La classe SwerveDriveKinematics accepte un nombre variable d’arguments constructeur, chaque argument étant l’emplacement d’un module swerve par rapport au centre du robot (sous la forme d’un Translation2d. Le nombre d’arguments constructeur correspond au nombre de modules Swerve.

Note

Un robot doit avoir au moins 2 modules Swerve.

Note

En C ++, la classe est basée sur le nombre de modules. Par conséquent, lors de la construction d’un objet SwerveDriveKinematics en tant que variable membre d’une classe, le nombre de modules doit être transmis en tant qu’argument. Par exemple, pour un entraînement Swerve typique avec quatre modules, l’objet cinématique doit être construit comme suit: frc::SwerveDriveKinematics<4> m_kinematics{...}.

Les emplacements des modules doivent être relatifs au centre du robot. Les valeurs x positives représentent le déplacement vers l’avant du robot tandis que les valeurs y positives représentent le déplacement vers la gauche du robot.

// 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
);

Conversion des vitesses de châssis en états de module

La méthode toSwerveModuleStates(ChassisSpeeds speeds) (Java) / ToSwerveModuleStates(ChassisSpeeds speeds) (C++) doit être utilisée pour convertir un objet ChassisSpeeds en un tableau d’objets SwerveModuleState . Ceci est utile dans les situations où vous devez convertir une vitesse avant, une vitesse latérale et une vitesse angulaire en états de module individuels.

Les éléments du tableau renvoyé par cette méthode sont du même ordre dans lequel l’objet cinématique a été construit. Par exemple, si l’objet cinématique a été construit avec l’emplacement du module avant-gauche, l’emplacement du module avant-droit, l’emplacement du module arrière-gauche et l’emplacement du module arrière-droit dans cet ordre, les éléments du tableau seront: état du module avant-gauche, état du module avant-droit, état du module arrière-gauche et état du module arrière-droit (en respectant cet ordre).

// 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];

Module d’optimisation de l’angle

La classe SwerveModuleState contient une méthode statique optimize() (Java) / Optimize() (C++) qui est utilisée pour « optimiser » les points de consigne de vitesse et d’angle pour un SwerveModuleState donné afin de minimiser le changement d’orientation angulaire. Par exemple, si le point de consigne angulaire d’un certain module de cinématique inverse est de 90 degrés, mais que votre angle actuel est de -89 degrés, cette méthode annulera automatiquement la vitesse du point de consigne du module et fournira le point de consigne angulaire -90 degrés pour réduire la distance parcourue par le module.

Cette méthode prend deux paramètres : l’état désiré (généralement par l’intermédiaire de la méthode toSwerveModuleStates) et l’angle actuel. Il retournera le nouvel état optimisé que vous pouvez utiliser comme point de consigne dans votre boucle de contrôle de rétroaction.

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

Entraînement orienté terrain

Recall peut être créé à partir d’un ensemble de vitesses orientées en fonction du terrain de jeu. Cette fonction peut être utilisée également pour obtenir les vitesses de roue à partir du même ensemble (de vitesses orientées en fonction du terrain de jeu).

// 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);

Utilisation de centres de rotation personnalisés

Parfois, la rotation autour d’un point spécifique peut être souhaitable pour certaines manœuvres d’évitement. Ce type de comportement est également pris en charge par les classes WPILib. La même méthode ToSwerveModuleStates() accepte un deuxième paramètre pour le centre de rotation (comme un Translation2d). Tout comme les emplacements des roues, le Translation2d représentant le centre de rotation doit être relatif au centre du robot.

Note

Étant donné que tous les robots ont un châssis rigide, les vitesses vx et vy fournies par l’objet ChassisSpeeds s’appliqueront toujours à l’intégralité du robot. Cependant, omega de l’objet ChassisSpeeds sera mesuré à partir du centre de rotation.

Par exemple, on peut définir le centre de rotation sur un certain module et si l’objet `ChassisSpeeds fourni a un vx et un vy de zéro et un omega différent de zéro, le robot tournerar autour de ce module Swerve spécifique.

Conversion des états des modules en vitesses de châssis

On peut également utiliser l’objet cinématique pour convertir un tableau d’objets SwerveModuleState en un objet ChassisSpeeds unique. La méthode toChassisSpeeds(SwerveModuleState... states) (Java) / ToChassisSpeeds(SwerveModuleState... states) (C++) peut être utilisée pour y parvenir.

// 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;