麦克纳姆驱动运动学
``MecanumDriveKinematics``类是一个有用的工具,它可以在``ChassisSpeeds``对象和``MecanumDriveWheelSpeeds``对象之间进行转换,后者包含了麦克纳姆轮驱动器上四个车轮的速度。
构造运动学对象
MecanumDriveKinematics``类接受四个构造函数参数,每个参数是相对于机器人中心的轮子的位置(作为``Translation2d
)。参数的顺序是前左,前右,后左,后右。轮子的位置必须相对于机器人的中心。正的x值代表向机器人前面移动,正的y值代表向机器人左边移动。
// 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};
将底盘速度转换为车轮速度
``toWheelSpeeds(ChassisSpeeds speeds)``(Java)/``ToWheelSpeeds(ChassisSpeeds speeds)``(C++)方法应该用于将``ChassisSpeeds``对象转换为``MecanumDriveWheelSpeeds``对象。当你需要将前进速度、侧向速度和角速度转换为单个车轮速度时,这个方法很有用。
// 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);
定向驱动
:ref:`Recall <docs/software/kinematics-and-odometry/intro-and-chassis-speeds:Creating a ChassisSpeeds object from field-relative speeds>```ChassisSpeeds``对象可以从一组所需的场向速度中创建。这个功能可以用来从一组期望的场向速度中获得轮速。
// 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);
使用自定义旋转中心
有时,对于某些规避操作,可能需要绕一个特定的角旋转。 WPILib也支持这种类型的行为。相同的ToWheelSpeeds()方法接受旋转中心的第二个参数(作为Translation2d)。就像轮子的位置一样,代表旋转中心的``Translation2d’’应该相对于机器人中心。
备注
由于所有机器人都是一个刚性框架,因此,从 “底盘速度 “对象中提供的 “vx “和 “vy “速度仍然适用于整个机器人。然而,来自``底盘速度``对象的``omega``将从旋转中心测量。
例如,可以将旋转中心设置在某个轮子上,如果提供的``ChassisSpeeds``对象的``vx``和``vy``为零,而``omega``非零,机器人就会出现围绕该轮子旋转。
将车轮速度转换为底盘速度
人们还可以使用运动学对象将``MecanumDriveWheelSpeeds``对象转换为单一的``ChassisSpeeds``对象。使用``toChassisSpeeds(MecanumDriveWheelSpeeds speeds)``(Java)/``ToChassisSpeeds(MecanumDriveWheelSpeeds speeds)``(C++)方法可以实现这个目的。
// 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);