WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
wpi::math::Kinematics< WheelPositions, WheelVelocities, WheelAccelerations > Class Template Referenceabstract

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

#include <wpi/math/kinematics/Kinematics.hpp>

Public Member Functions

virtual ~Kinematics () noexcept=default
virtual ChassisVelocities ToChassisVelocities (const WheelVelocities &wheelVelocities) const =0
 Performs forward kinematics to return the resulting chassis velocity from the wheel velocities.
virtual WheelVelocities ToWheelVelocities (const ChassisVelocities &chassisVelocities) const =0
 Performs inverse kinematics to return the wheel velocities from a desired chassis velocity.
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.
virtual WheelPositions Interpolate (const WheelPositions &start, const WheelPositions &end, double t) const =0
 Performs interpolation between two values.
virtual ChassisAccelerations ToChassisAccelerations (const WheelAccelerations &wheelAccelerations) const =0
 Performs forward kinematics to return the resulting chassis accelerations from the wheel accelerations.
virtual WheelAccelerations ToWheelAccelerations (const ChassisAccelerations &chassisAccelerations) const =0
 Performs inverse kinematics to return the wheel accelerations from a desired chassis acceleration.

Detailed Description

template<typename WheelPositions, typename WheelVelocities, typename WheelAccelerations>
requires std::copy_constructible<WheelPositions> && std::assignable_from<WheelPositions&, const WheelPositions&>
class wpi::math::Kinematics< WheelPositions, WheelVelocities, WheelAccelerations >

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

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

Inverse kinematics converts a desired chassis velocity into wheel velocities whereas forward kinematics converts wheel velocities into chassis velocity.

Constructor & Destructor Documentation

◆ ~Kinematics()

template<typename WheelPositions, typename WheelVelocities, typename WheelAccelerations>
virtual wpi::math::Kinematics< WheelPositions, WheelVelocities, WheelAccelerations >::~Kinematics ( )
virtualdefaultnoexcept

Member Function Documentation

◆ Interpolate()

template<typename WheelPositions, typename WheelVelocities, typename WheelAccelerations>
virtual WheelPositions wpi::math::Kinematics< WheelPositions, WheelVelocities, WheelAccelerations >::Interpolate ( const WheelPositions & start,
const WheelPositions & end,
double t ) const
pure virtual

Performs interpolation between two values.

Parameters
startThe value to start at.
endThe value to end at.
tHow far between the two values to interpolate. This should be bounded to [0, 1].
Returns
The interpolated value.

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

◆ ToChassisAccelerations()

template<typename WheelPositions, typename WheelVelocities, typename WheelAccelerations>
virtual ChassisAccelerations wpi::math::Kinematics< WheelPositions, WheelVelocities, WheelAccelerations >::ToChassisAccelerations ( const WheelAccelerations & wheelAccelerations) const
pure virtual

Performs forward kinematics to return the resulting chassis accelerations from the wheel accelerations.

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

Parameters
wheelAccelerationsThe accelerations of the wheels.
Returns
The chassis accelerations.

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

◆ ToChassisVelocities()

template<typename WheelPositions, typename WheelVelocities, typename WheelAccelerations>
virtual ChassisVelocities wpi::math::Kinematics< WheelPositions, WheelVelocities, WheelAccelerations >::ToChassisVelocities ( const WheelVelocities & wheelVelocities) const
pure virtual

Performs forward kinematics to return the resulting chassis velocity from the wheel velocities.

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

Parameters
wheelVelocitiesThe velocities of the wheels.
Returns
The chassis velocity.

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

◆ ToTwist2d()

template<typename WheelPositions, typename WheelVelocities, typename WheelAccelerations>
virtual Twist2d wpi::math::Kinematics< WheelPositions, WheelVelocities, WheelAccelerations >::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 wpi::math::DifferentialDriveKinematics, wpi::math::MecanumDriveKinematics, and wpi::math::SwerveDriveKinematics< NumModules >.

◆ ToWheelAccelerations()

template<typename WheelPositions, typename WheelVelocities, typename WheelAccelerations>
virtual WheelAccelerations wpi::math::Kinematics< WheelPositions, WheelVelocities, WheelAccelerations >::ToWheelAccelerations ( const ChassisAccelerations & chassisAccelerations) const
pure virtual

Performs inverse kinematics to return the wheel accelerations from a desired chassis acceleration.

This method is often used for dynamics calculations – converting desired robot accelerations into individual wheel accelerations.

Parameters
chassisAccelerationsThe desired chassis accelerations.
Returns
The wheel accelerations.

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

◆ ToWheelVelocities()

template<typename WheelPositions, typename WheelVelocities, typename WheelAccelerations>
virtual WheelVelocities wpi::math::Kinematics< WheelPositions, WheelVelocities, WheelAccelerations >::ToWheelVelocities ( const ChassisVelocities & chassisVelocities) const
pure virtual

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

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

Parameters
chassisVelocitiesThe desired chassis velocity.
Returns
The wheel velocities.

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


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