![]() |
WPILibC++ 2025.3.1
|
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 | 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. | |
Static Public Member Functions | |
static constexpr ChassisSpeeds | Discretize (units::meters_per_second_t vx, units::meters_per_second_t vy, units::radians_per_second_t omega, units::second_t dt) |
Discretizes a continuous-time chassis speed. | |
static constexpr ChassisSpeeds | Discretize (const ChassisSpeeds &continuousSpeeds, units::second_t dt) |
Discretizes a continuous-time chassis speed. | |
static constexpr 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. | |
static constexpr ChassisSpeeds | FromFieldRelativeSpeeds (const ChassisSpeeds &fieldRelativeSpeeds, const Rotation2d &robotAngle) |
Converts a user provided field-relative ChassisSpeeds object into a robot-relative ChassisSpeeds object. | |
static constexpr 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. | |
static constexpr ChassisSpeeds | FromRobotRelativeSpeeds (const ChassisSpeeds &robotRelativeSpeeds, const Rotation2d &robotAngle) |
Converts a user provided robot-relative ChassisSpeeds object into a field-relative ChassisSpeeds object. | |
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. | |
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.
|
inlinestaticconstexpr |
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.
continuousSpeeds | The continuous speeds. |
dt | The duration of the timestep the speeds should be applied for. |
|
inlinestaticconstexpr |
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.
vx | Forward velocity. |
vy | Sideways velocity. |
omega | Angular velocity. |
dt | The duration of the timestep the speeds should be applied for. |
|
inlinestaticconstexpr |
Converts a user provided field-relative ChassisSpeeds object into a robot-relative ChassisSpeeds object.
fieldRelativeSpeeds | The 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. |
robotAngle | The 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. |
|
inlinestaticconstexpr |
Converts a user provided field-relative set of speeds into a robot-relative ChassisSpeeds object.
vx | The component of speed in the x direction relative to the field. Positive x is away from your alliance wall. |
vy | The component of speed in the y direction relative to the field. Positive y is to your left when standing behind the alliance wall. |
omega | The angular rate of the robot. |
robotAngle | The 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. |
|
inlinestaticconstexpr |
Converts a user provided robot-relative ChassisSpeeds object into a field-relative ChassisSpeeds object.
robotRelativeSpeeds | The 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. |
robotAngle | The 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. |
|
inlinestaticconstexpr |
Converts a user provided robot-relative set of speeds into a field-relative ChassisSpeeds object.
vx | The component of speed in the x direction relative to the robot. Positive x is towards the robot's front. |
vy | The component of speed in the y direction relative to the robot. Positive y is towards the robot's left. |
omega | The angular rate of the robot. |
robotAngle | The 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. |
|
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}
scalar | The scalar to multiply by. |
|
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}
other | The ChassisSpeeds to add. |
|
inlineconstexpr |
Returns the inverse of the current ChassisSpeeds.
This is equivalent to negating all components of the ChassisSpeeds.
|
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}
other | The ChassisSpeeds to subtract. |
|
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}
scalar | The scalar to divide by. |
|
constexprdefault |
Compares the ChassisSpeeds with another ChassisSpeed.
other | The other ChassisSpeeds. |
|
inlineconstexpr |
units::radians_per_second_t frc::ChassisSpeeds::omega = 0_rad_per_s |
Represents the angular velocity of the robot frame.
(CCW is +)
units::meters_per_second_t frc::ChassisSpeeds::vx = 0_mps |
Velocity along the x-axis.
(Fwd is +)
units::meters_per_second_t frc::ChassisSpeeds::vy = 0_mps |
Velocity along the y-axis.
(Left is +)