WPILibC++ 2027.0.0-alpha-2
Loading...
Searching...
No Matches
frc::ChassisSpeeds Struct Reference

Represents the speed of a robot chassis. More...

#include <frc/kinematics/ChassisSpeeds.h>

Public Member Functions

constexpr Twist2d ToTwist2d (units::second_t dt) const
 Creates a Twist2d from ChassisSpeeds.
 
constexpr ChassisSpeeds Discretize (units::second_t dt) const
 Discretizes a continuous-time chassis speed.
 
constexpr ChassisSpeeds ToRobotRelative (const Rotation2d &robotAngle) const
 Converts this field-relative set of speeds into a robot-relative ChassisSpeeds object.
 
constexpr ChassisSpeeds ToFieldRelative (const Rotation2d &robotAngle) const
 Converts this robot-relative set of speeds into a field-relative ChassisSpeeds object.
 
constexpr ChassisSpeeds operator+ (const ChassisSpeeds &other) const
 Adds two ChassisSpeeds and returns the sum.
 
constexpr ChassisSpeeds operator- (const ChassisSpeeds &other) const
 Subtracts the other ChassisSpeeds from the current ChassisSpeeds and returns the difference.
 
constexpr ChassisSpeeds operator- () const
 Returns the inverse of the current ChassisSpeeds.
 
constexpr ChassisSpeeds operator* (double scalar) const
 Multiplies the ChassisSpeeds by a scalar and returns the new ChassisSpeeds.
 
constexpr ChassisSpeeds operator/ (double scalar) const
 Divides the ChassisSpeeds by a scalar and returns the new ChassisSpeeds.
 
constexpr bool operator== (const ChassisSpeeds &other) const =default
 Compares the ChassisSpeeds with another ChassisSpeed.
 

Public Attributes

units::meters_per_second_t vx = 0_mps
 Velocity along the x-axis.
 
units::meters_per_second_t vy = 0_mps
 Velocity along the y-axis.
 
units::radians_per_second_t omega = 0_rad_per_s
 Represents the angular velocity of the robot frame.
 

Detailed Description

Represents the speed of a robot chassis.

Although this struct contains similar members compared to a Twist2d, they do NOT represent the same thing. Whereas a Twist2d represents a change in pose w.r.t to the robot frame of reference, a ChassisSpeeds struct represents a robot's velocity.

A strictly non-holonomic drivetrain, such as a differential drive, should never have a dy component because it can never move sideways. Holonomic drivetrains such as swerve and mecanum will often have all three components.

Member Function Documentation

◆ Discretize()

ChassisSpeeds frc::ChassisSpeeds::Discretize ( units::second_t dt) const
inlineconstexpr

Discretizes a continuous-time chassis speed.

This function converts a continuous-time chassis speed into a discrete-time one such that when the discrete-time chassis speed is applied for one timestep, the robot moves as if the velocity components are independent (i.e., the robot moves v_x * dt along the x-axis, v_y * dt along the y-axis, and omega * dt around the z-axis).

This is useful for compensating for translational skew when translating and rotating a holonomic (swerve or mecanum) drivetrain. However, scaling down the ChassisSpeeds after discretizing (e.g., when desaturating swerve module speeds) rotates the direction of net motion in the opposite direction of rotational velocity, introducing a different translational skew which is not accounted for by discretization.

Parameters
dtThe duration of the timestep the speeds should be applied for.
Returns
Discretized ChassisSpeeds.

◆ operator*()

ChassisSpeeds frc::ChassisSpeeds::operator* ( double scalar) const
inlineconstexpr

Multiplies the ChassisSpeeds by a scalar and returns the new ChassisSpeeds.

For example, ChassisSpeeds{2.0, 2.5, 1.0} * 2 = ChassisSpeeds{4.0, 5.0, 1.0}

Parameters
scalarThe scalar to multiply by.
Returns
The scaled ChassisSpeeds.

◆ operator+()

ChassisSpeeds frc::ChassisSpeeds::operator+ ( const ChassisSpeeds & other) const
inlineconstexpr

Adds two ChassisSpeeds and returns the sum.

For example, ChassisSpeeds{1.0, 0.5, 1.5} + ChassisSpeeds{2.0, 1.5, 0.5} = ChassisSpeeds{3.0, 2.0, 2.0}

Parameters
otherThe ChassisSpeeds to add.
Returns
The sum of the ChassisSpeeds.

◆ operator-() [1/2]

ChassisSpeeds frc::ChassisSpeeds::operator- ( ) const
inlineconstexpr

Returns the inverse of the current ChassisSpeeds.

This is equivalent to negating all components of the ChassisSpeeds.

Returns
The inverse of the current ChassisSpeeds.

◆ operator-() [2/2]

ChassisSpeeds frc::ChassisSpeeds::operator- ( const ChassisSpeeds & other) const
inlineconstexpr

Subtracts the other ChassisSpeeds from the current ChassisSpeeds and returns the difference.

For example, ChassisSpeeds{5.0, 4.0, 2.0} - ChassisSpeeds{1.0, 2.0, 1.0} = ChassisSpeeds{4.0, 2.0, 1.0}

Parameters
otherThe ChassisSpeeds to subtract.
Returns
The difference between the two ChassisSpeeds.

◆ operator/()

ChassisSpeeds frc::ChassisSpeeds::operator/ ( double scalar) const
inlineconstexpr

Divides the ChassisSpeeds by a scalar and returns the new ChassisSpeeds.

For example, ChassisSpeeds{2.0, 2.5, 1.0} / 2 = ChassisSpeeds{1.0, 1.25, 0.5}

Parameters
scalarThe scalar to divide by.
Returns
The scaled ChassisSpeeds.

◆ operator==()

bool frc::ChassisSpeeds::operator== ( const ChassisSpeeds & other) const
constexprdefault

Compares the ChassisSpeeds with another ChassisSpeed.

Parameters
otherThe other ChassisSpeeds.
Returns
The result of the comparison. Is true if they are the same.

◆ ToFieldRelative()

ChassisSpeeds frc::ChassisSpeeds::ToFieldRelative ( const Rotation2d & robotAngle) const
inlineconstexpr

Converts this robot-relative set of speeds into a field-relative ChassisSpeeds object.

Parameters
robotAngleThe angle of the robot as measured by a gyroscope. The robot's angle is considered to be zero when it is facing directly away from your alliance station wall. Remember that this should be CCW positive.
Returns
ChassisSpeeds object representing the speeds in the field's frame of reference.

◆ ToRobotRelative()

ChassisSpeeds frc::ChassisSpeeds::ToRobotRelative ( const Rotation2d & robotAngle) const
inlineconstexpr

Converts this field-relative set of speeds into a robot-relative ChassisSpeeds object.

Parameters
robotAngleThe angle of the robot as measured by a gyroscope. The robot's angle is considered to be zero when it is facing directly away from your alliance station wall. Remember that this should be CCW positive.
Returns
ChassisSpeeds object representing the speeds in the robot's frame of reference.

◆ ToTwist2d()

Twist2d frc::ChassisSpeeds::ToTwist2d ( units::second_t dt) const
inlineconstexpr

Creates a Twist2d from ChassisSpeeds.

Parameters
dtThe duration of the timestep.
Returns
Twist2d.

Member Data Documentation

◆ omega

units::radians_per_second_t frc::ChassisSpeeds::omega = 0_rad_per_s

Represents the angular velocity of the robot frame.

(CCW is +)

◆ vx

units::meters_per_second_t frc::ChassisSpeeds::vx = 0_mps

Velocity along the x-axis.

(Fwd is +)

◆ vy

units::meters_per_second_t frc::ChassisSpeeds::vy = 0_mps

Velocity along the y-axis.

(Left is +)


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