WPILibC++ 2024.3.2
frc::ChassisSpeeds Struct Reference

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

#include <frc/kinematics/ChassisSpeeds.h>

Public Member Functions

constexpr ChassisSpeeds operator+ (const ChassisSpeeds &other) const
 Adds two ChassisSpeeds and returns the sum. More...
 
constexpr ChassisSpeeds operator- (const ChassisSpeeds &other) const
 Subtracts the other ChassisSpeeds from the current ChassisSpeeds and returns the difference. More...
 
constexpr ChassisSpeeds operator- () const
 Returns the inverse of the current ChassisSpeeds. More...
 
constexpr ChassisSpeeds operator* (double scalar) const
 Multiplies the ChassisSpeeds by a scalar and returns the new ChassisSpeeds. More...
 
constexpr ChassisSpeeds operator/ (double scalar) const
 Divides the ChassisSpeeds by a scalar and returns the new ChassisSpeeds. More...
 

Static Public Member Functions

static ChassisSpeeds Discretize (units::meters_per_second_t vx, units::meters_per_second_t vy, units::radians_per_second_t omega, units::second_t dt)
 Disretizes a continuous-time chassis speed. More...
 
static ChassisSpeeds Discretize (const ChassisSpeeds &continuousSpeeds, units::second_t dt)
 Disretizes a continuous-time chassis speed. More...
 
static ChassisSpeeds FromFieldRelativeSpeeds (units::meters_per_second_t vx, units::meters_per_second_t vy, units::radians_per_second_t omega, const Rotation2d &robotAngle)
 Converts a user provided field-relative set of speeds into a robot-relative ChassisSpeeds object. More...
 
static ChassisSpeeds FromFieldRelativeSpeeds (const ChassisSpeeds &fieldRelativeSpeeds, const Rotation2d &robotAngle)
 Converts a user provided field-relative ChassisSpeeds object into a robot-relative ChassisSpeeds object. More...
 
static ChassisSpeeds FromRobotRelativeSpeeds (units::meters_per_second_t vx, units::meters_per_second_t vy, units::radians_per_second_t omega, const Rotation2d &robotAngle)
 Converts a user provided robot-relative set of speeds into a field-relative ChassisSpeeds object. More...
 
static ChassisSpeeds FromRobotRelativeSpeeds (const ChassisSpeeds &robotRelativeSpeeds, const Rotation2d &robotAngle)
 Converts a user provided robot-relative ChassisSpeeds object into a field-relative ChassisSpeeds object. More...
 

Public Attributes

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

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() [1/2]

static ChassisSpeeds frc::ChassisSpeeds::Discretize ( const ChassisSpeeds continuousSpeeds,
units::second_t  dt 
)
inlinestatic

Disretizes 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 swerve drivetrain.

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

◆ Discretize() [2/2]

static ChassisSpeeds frc::ChassisSpeeds::Discretize ( units::meters_per_second_t  vx,
units::meters_per_second_t  vy,
units::radians_per_second_t  omega,
units::second_t  dt 
)
inlinestatic

Disretizes 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 swerve drivetrain.

Parameters
vxForward velocity.
vySideways velocity.
omegaAngular velocity.
dtThe duration of the timestep the speeds should be applied for.
Returns
Discretized ChassisSpeeds.

◆ FromFieldRelativeSpeeds() [1/2]

static ChassisSpeeds frc::ChassisSpeeds::FromFieldRelativeSpeeds ( const ChassisSpeeds fieldRelativeSpeeds,
const Rotation2d robotAngle 
)
inlinestatic

Converts a user provided field-relative ChassisSpeeds object into a robot-relative ChassisSpeeds object.

Parameters
fieldRelativeSpeedsThe ChassisSpeeds object representing the speeds in the field frame of reference. Positive x is away from your alliance wall. Positive y is to your left when standing behind the alliance wall.
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.

◆ FromFieldRelativeSpeeds() [2/2]

static ChassisSpeeds frc::ChassisSpeeds::FromFieldRelativeSpeeds ( units::meters_per_second_t  vx,
units::meters_per_second_t  vy,
units::radians_per_second_t  omega,
const Rotation2d robotAngle 
)
inlinestatic

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

Parameters
vxThe component of speed in the x direction relative to the field. Positive x is away from your alliance wall.
vyThe component of speed in the y direction relative to the field. Positive y is to your left when standing behind the alliance wall.
omegaThe angular rate of the robot.
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.

◆ FromRobotRelativeSpeeds() [1/2]

static ChassisSpeeds frc::ChassisSpeeds::FromRobotRelativeSpeeds ( const ChassisSpeeds robotRelativeSpeeds,
const Rotation2d robotAngle 
)
inlinestatic

Converts a user provided robot-relative ChassisSpeeds object into a field-relative ChassisSpeeds object.

Parameters
robotRelativeSpeedsThe ChassisSpeeds object representing the speeds in the robot frame of reference. Positive x is the towards robot's front. Positive y is towards the robot's left.
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.

◆ FromRobotRelativeSpeeds() [2/2]

static ChassisSpeeds frc::ChassisSpeeds::FromRobotRelativeSpeeds ( units::meters_per_second_t  vx,
units::meters_per_second_t  vy,
units::radians_per_second_t  omega,
const Rotation2d robotAngle 
)
inlinestatic

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

Parameters
vxThe component of speed in the x direction relative to the robot. Positive x is towards the robot's front.
vyThe component of speed in the y direction relative to the robot. Positive y is towards the robot's left.
omegaThe angular rate of the robot.
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.

◆ operator*()

constexpr 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+()

constexpr 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]

constexpr 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]

constexpr 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/()

constexpr 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.

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: