WPILibC++ 2023.4.3-108-ge5452e3
frc::ChassisSpeeds Struct Reference

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

#include <frc/kinematics/ChassisSpeeds.h>

Static Public Member Functions

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

Public Attributes

units::meters_per_second_t vx = 0_mps
 Represents forward velocity w.r.t the robot frame of reference. More...
 
units::meters_per_second_t vy = 0_mps
 Represents strafe velocity w.r.t the robot frame of reference. 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, this ChassisSpeeds struct represents a velocity w.r.t to the robot frame of reference.

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

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

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

Represents forward velocity w.r.t the robot frame of reference.

(Fwd is +)

◆ vy

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

Represents strafe velocity w.r.t the robot frame of reference.

(Left is +)


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