Cinemática de accionamiento Mecanum

La clase MecanumDriveKinematics es una herramienta útil que convierte entre un objeto ChassisSpeeds y un objeto MecanumDriveWheelSpeeds, que contiene las velocidades de cada una de las cuatro ruedas de un mecanismo mecanum.

Construyendo el objeto cinemático

La clase MecanumDriveKinematics acepta cuatro argumentos de constructor, y cada argumento es la ubicación de una rueda en relación con el centro del robot (como un Translation2d). El orden de los argumentos es frontal izquierdo, frontal derecho, posterior izquierdo y posterior derecho. Las ubicaciones de las ruedas deben ser relativas al centro del robot. Los valores x positivos representan un movimiento hacia la parte delantera del robot, mientras que los valores y positivos representan un movimiento hacia la izquierda del robot.

// Locations of the wheels 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 wheel locations.
MecanumDriveKinematics m_kinematics = new MecanumDriveKinematics(
  m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation, m_backRightLocation
);

Conversión de velocidades del chasis a velocidades de las ruedas

El método toWheelSpeeds(ChassisSpeeds speeds) (Java) / ToWheelSpeeds(ChassisSpeeds speeds) (C++) debe usarse para convertir un objeto ChassisSpeeds en un objeto MecanumDriveWheelSpeeds. Esto es útil en situaciones en las que tiene que convertir una velocidad de avance, una velocidad lateral y una velocidad angular en velocidades de rueda individuales.

// 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 wheel speeds
MecanumDriveWheelSpeeds wheelSpeeds = kinematics.toWheelSpeeds(speeds);

// Get the individual wheel speeds
double frontLeft = wheelSpeeds.frontLeftMetersPerSecond
double frontRight = wheelSpeeds.frontRightMetersPerSecond
double backLeft = wheelSpeeds.rearLeftMetersPerSecond
double backRight = wheelSpeeds.rearRightMetersPerSecond

Accionamiento orientado al campo

Recall que un objeto ChassisSpeeds se puede crear a partir de un conjunto de velocidades deseadas orientadas al campo. Esta función se puede utilizar para obtener velocidades de rueda 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
MecanumDriveWheelSpeeds wheelSpeeds = kinematics.toWheelSpeeds(speeds);

Usar centros de rotación personalizados

A veces, girar alrededor de una esquina específica puede ser deseable para ciertas maniobras evasivas. Este tipo de comportamiento también es compatible con las clases WPILib. El mismo método ToWheelSpeeds() acepta un segundo parámetro para el centro de rotación (como un Translation2d). Al igual que las ubicaciones de las ruedas, la Translation2d que representa el centro de rotación debe ser relativa al centro del robot.

Nota

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

Por ejemplo, se puede establecer el centro de rotación en una determinada rueda y si el objeto ChassisSpeeds proporcionado tiene un vx y un vy de cero y un omega distinto de cero, el robot parecerá girar alrededor de esa rueda en particular.

Conversión de velocidades de rueda a velocidades de chasis

También se puede usar el objeto cinemático para convertir un objeto MecanumDriveWheelSpeeds en un objeto singular ChassisSpeeds. El método toChassisSpeeds(MecanumDriveWheelSpeeds speeds) (Java) / ToChassisSpeeds(MecanumDriveWheelSpeeds speeds) (C++) se puede utilizar para lograr esto.

// Example wheel speeds
var wheelSpeeds = new MecanumDriveWheelSpeeds(-17.67, 20.51, -13.44, 16.26);

// Convert to chassis speeds
ChassisSpeeds chassisSpeeds = kinematics.toChassisSpeeds(wheelSpeeds);

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