WPILibC++ 2024.3.2
frc::Kinematics< WheelSpeeds, WheelPositions > Class Template Referenceabstract

Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel speeds. More...

#include <frc/kinematics/Kinematics.h>

Public Member Functions

virtual ChassisSpeeds ToChassisSpeeds (const WheelSpeeds &wheelSpeeds) const =0
 Performs forward kinematics to return the resulting chassis speed from the wheel speeds. More...
 
virtual WheelSpeeds ToWheelSpeeds (const ChassisSpeeds &chassisSpeeds) const =0
 Performs inverse kinematics to return the wheel speeds from a desired chassis velocity. More...
 
virtual Twist2d ToTwist2d (const WheelPositions &start, const WheelPositions &end) const =0
 Performs forward kinematics to return the resulting Twist2d from the given change in wheel positions. More...
 

Detailed Description

template<typename WheelSpeeds, typename WheelPositions>
class frc::Kinematics< WheelSpeeds, WheelPositions >

Helper class that converts a chassis velocity (dx, dy, and dtheta components) into individual wheel speeds.

Robot code should not use this directly- Instead, use the particular type for your drivetrain (e.g., DifferentialDriveKinematics).

Inverse kinematics converts a desired chassis speed into wheel speeds whereas forward kinematics converts wheel speeds into chassis speed.

Member Function Documentation

◆ ToChassisSpeeds()

template<typename WheelSpeeds , typename WheelPositions >
virtual ChassisSpeeds frc::Kinematics< WheelSpeeds, WheelPositions >::ToChassisSpeeds ( const WheelSpeeds &  wheelSpeeds) const
pure virtual

Performs forward kinematics to return the resulting chassis speed from the wheel speeds.

This method is often used for odometry – determining the robot's position on the field using data from the real-world speed of each wheel on the robot.

Parameters
wheelSpeedsThe speeds of the wheels.
Returns
The chassis speed.

Implemented in frc::DifferentialDriveKinematics, and frc::MecanumDriveKinematics.

◆ ToTwist2d()

template<typename WheelSpeeds , typename WheelPositions >
virtual Twist2d frc::Kinematics< WheelSpeeds, WheelPositions >::ToTwist2d ( const WheelPositions &  start,
const WheelPositions &  end 
) const
pure virtual

Performs forward kinematics to return the resulting Twist2d from the given change in wheel positions.

This method is often used for odometry – determining the robot's position on the field using changes in the distance driven by each wheel on the robot.

Parameters
startThe starting distances driven by the wheels.
endThe ending distances driven by the wheels.
Returns
The resulting Twist2d in the robot's movement.

Implemented in frc::DifferentialDriveKinematics, frc::MecanumDriveKinematics, and frc::SwerveDriveKinematics< NumModules >.

◆ ToWheelSpeeds()

template<typename WheelSpeeds , typename WheelPositions >
virtual WheelSpeeds frc::Kinematics< WheelSpeeds, WheelPositions >::ToWheelSpeeds ( const ChassisSpeeds chassisSpeeds) const
pure virtual

Performs inverse kinematics to return the wheel speeds from a desired chassis velocity.

This method is often used to convert joystick values into wheel speeds.

Parameters
chassisSpeedsThe desired chassis speed.
Returns
The wheel speeds.

Implemented in frc::DifferentialDriveKinematics, frc::MecanumDriveKinematics, and frc::SwerveDriveKinematics< NumModules >.


The documentation for this class was generated from the following file: