WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
wpi::math::ChassisVelocities Struct Reference

Represents robot chassis velocities. More...

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

Public Member Functions

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

Public Attributes

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

Detailed Description

Represents robot chassis velocities.

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 ChassisVelocities struct represents a robot's velocities.

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

ChassisVelocities wpi::math::ChassisVelocities::Discretize ( wpi::units::second_t dt) const
inlineconstexpr

Discretizes continuous-time chassis velocities.

This function converts continuous-time chassis velocities into discrete-time ones such that when the discrete-time chassis velocities are 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 ChassisVelocities after discretizing (e.g., when desaturating swerve module velocities) 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 velocities should be applied for.
Returns
Discretized ChassisVelocities.

◆ operator*()

ChassisVelocities wpi::math::ChassisVelocities::operator* ( double scalar) const
inlineconstexpr

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

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

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

◆ operator+()

ChassisVelocities wpi::math::ChassisVelocities::operator+ ( const ChassisVelocities & other) const
inlineconstexpr

Adds two ChassisVelocities and returns the sum.

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

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

◆ operator-() [1/2]

ChassisVelocities wpi::math::ChassisVelocities::operator- ( ) const
inlineconstexpr

Returns the inverse of the current ChassisVelocities.

This is equivalent to negating all components of the ChassisVelocities.

Returns
The inverse of the current ChassisVelocities.

◆ operator-() [2/2]

ChassisVelocities wpi::math::ChassisVelocities::operator- ( const ChassisVelocities & other) const
inlineconstexpr

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

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

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

◆ operator/()

ChassisVelocities wpi::math::ChassisVelocities::operator/ ( double scalar) const
inlineconstexpr

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

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

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

◆ operator==()

bool wpi::math::ChassisVelocities::operator== ( const ChassisVelocities & other) const
constexprdefault

Compares the ChassisVelocities with another ChassisVelocity.

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

◆ ToFieldRelative()

ChassisVelocities wpi::math::ChassisVelocities::ToFieldRelative ( const Rotation2d & robotAngle) const
inlineconstexpr

Converts this robot-relative set of velocities into a field-relative ChassisVelocities 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
ChassisVelocities object representing the velocities in the field's frame of reference.

◆ ToRobotRelative()

ChassisVelocities wpi::math::ChassisVelocities::ToRobotRelative ( const Rotation2d & robotAngle) const
inlineconstexpr

Converts this field-relative set of velocities into a robot-relative ChassisVelocities 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
ChassisVelocities object representing the velocities in the robot's frame of reference.

◆ ToTwist2d()

Twist2d wpi::math::ChassisVelocities::ToTwist2d ( wpi::units::second_t dt) const
inlineconstexpr

Creates a Twist2d from ChassisVelocities.

Parameters
dtThe duration of the timestep.
Returns
Twist2d.

Member Data Documentation

◆ omega

wpi::units::radians_per_second_t wpi::math::ChassisVelocities::omega = 0_rad_per_s

Represents the angular velocity of the robot frame.

(CCW is +)

◆ vx

wpi::units::meters_per_second_t wpi::math::ChassisVelocities::vx = 0_mps

Velocity along the x-axis.

(Fwd is +)

◆ vy

wpi::units::meters_per_second_t wpi::math::ChassisVelocities::vy = 0_mps

Velocity along the y-axis.

(Left is +)


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