La cinématique de l’entraînement Mécanum
La classe MecanumDriveKinematics
est un outil utile qui convertit entre un objet ChassisSpeeds
et un objet MecanumDriveWheelSpeeds
, qui contient les vitesses pour chacune des quatre roues sur un entraînement mécanique.
Note
Mecanum kinematics uses a common coordinate system. You may wish to reference the Coordinate System section for details.
Construction de l’objet cinématique
La classe MecanumDriveKinematics
accepte quatre arguments de constructeur, chaque argument étant l’emplacement d’une roue par rapport au centre du robot (en tant que Translation2d
). L’ordre des arguments est avant gauche, avant droit, arrière gauche et arrière droit. L’emplacement des roues doit être relatif 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 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
);
// Locations of the wheels relative to the robot center.
frc::Translation2d m_frontLeftLocation{0.381_m, 0.381_m};
frc::Translation2d m_frontRightLocation{0.381_m, -0.381_m};
frc::Translation2d m_backLeftLocation{-0.381_m, 0.381_m};
frc::Translation2d m_backRightLocation{-0.381_m, -0.381_m};
// Creating my kinematics object using the wheel locations.
frc::MecanumDriveKinematics m_kinematics{
m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation,
m_backRightLocation};
from wpimath.geometry import Translation2d
from wpimath.kinematics import MecanumDriveKinematics
# Locations of the wheels relative to the robot center.
frontLeftLocation = Translation2d(0.381, 0.381)
frontRightLocation = Translation2d(0.381, -0.381)
backLeftLocation = Translation2d(-0.381, 0.381)
backRightLocation = Translation2d(-0.381, -0.381)
# Creating my kinematics object using the wheel locations.
self.kinematics = MecanumDriveKinematics(
frontLeftLocation, frontRightLocation, backLeftLocation, backRightLocation
)
Conversion des vitesses du châssis en vitesses de roue
The toWheelSpeeds(ChassisSpeeds speeds)
(Java / Python) / ToWheelSpeeds(ChassisSpeeds speeds)
(C++) method should be used to convert a ChassisSpeeds
object to a MecanumDriveWheelSpeeds
object. This is useful in situations where you have to convert a forward velocity, sideways velocity, and an angular velocity into individual wheel speeds.
// 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
// Example chassis speeds: 1 meter per second forward, 3 meters
// per second to the left, and rotation at 1.5 radians per second
// counterclockwise.
frc::ChassisSpeeds speeds{1_mps, 3_mps, 1.5_rad_per_s};
// Convert to wheel speeds. Here, we can use C++17's structured
// bindings feature to automatically split up the MecanumDriveWheelSpeeds
// struct into it's individual components
auto [fl, fr, bl, br] = kinematics.ToWheelSpeeds(speeds);
from wpimath.kinematics import ChassisSpeeds
# Example chassis speeds: 1 meter per second forward, 3 meters
# per second to the left, and rotation at 1.5 radians per second
# counterclockwise.
speeds = ChassisSpeeds(1.0, 3.0, 1.5)
# Convert to wheel speeds
frontLeft, frontRight, backLeft, backRight = self.kinematics.toWheelSpeeds(speeds)
Entraînement orienté terrain
Recall qu’un objet ChassisSpeeds
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
MecanumDriveWheelSpeeds wheelSpeeds = kinematics.toWheelSpeeds(speeds);
// 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.
frc::ChassisSpeeds speeds = frc::ChassisSpeeds::FromFieldRelativeSpeeds(
2_mps, 2_mps, units::radians_per_second_t(std::numbers::pi / 2.0), Rotation2d(45_deg));
// Now use this in our kinematics
auto [fl, fr, bl, br] = kinematics.ToWheelSpeeds(speeds);
from wpimath.kinematics import ChassisSpeeds
import math
from wpimath.geometry import Rotation2d
# 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.
speeds = ChassisSpeeds.fromFieldRelativeSpeeds(
2.0, 2.0, math.pi / 2.0, Rotation2d.fromDegrees(45.0))
# Now use this in our kinematics
wheelSpeeds = self.kinematics.toWheelSpeeds(speeds)
Utilisation de centres de rotation personnalisés
Parfois, la rotation autour d’un point spécifique peut être souhaitable pour que le robot puisse éviter un obstacle. Cette manoeuvre est également prise en charge par les classes WPILib. La même méthode ToWheelSpeeds()
accepte un deuxième paramètre pour le centre de rotation (comme un Translation2d
). Tout comme les emplacements des roues, le Translation2d
qui correspond au centre de rotation doit être défini par rapport 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 une certaine roue 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 tournera autour de cette roue spécifique.
Conversion des vitesses de roue en vitesses de châssis
One can also use the kinematics object to convert a MecanumDriveWheelSpeeds
object to a singular ChassisSpeeds
object. The toChassisSpeeds(MecanumDriveWheelSpeeds speeds)
(Java / Python) / ToChassisSpeeds(MecanumDriveWheelSpeeds speeds)
(C++) method can be used to achieve this.
// 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;
// Example wheel speeds
frc::MecanumDriveWheelSpeeds wheelSpeeds{-17.67_mps, 20.51_mps, -13.44_mps, 16.26_mps};
// Convert to chassis speeds. Here, we can use C++17's structured bindings
// feature to automatically break up the ChassisSpeeds struct into its
// three components.
auto [forward, sideways, angular] = kinematics.ToChassisSpeeds(wheelSpeeds);
from wpimath.kinematics import MecanumDriveWheelSpeeds
# Example wheel speeds
wheelSpeeds = MecanumDriveWheelSpeeds(-17.67, 20.51, -13.44, 16.26)
# Convert to chassis speeds
chassisSpeeds = self.kinematics.toChassisSpeeds(wheelSpeeds)
# Getting individual speeds
forward = chassisSpeeds.vx
sideways = chassisSpeeds.vy
angular = chassisSpeeds.omega