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

Represents robot chassis accelerations. More...

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

Public Member Functions

constexpr ChassisAccelerations ToRobotRelative (const Rotation2d &robotAngle) const
 Converts this field-relative set of accelerations into a robot-relative ChassisAccelerations object.
constexpr ChassisAccelerations ToFieldRelative (const Rotation2d &robotAngle) const
 Converts this robot-relative set of accelerations into a field-relative ChassisAccelerations object.
constexpr ChassisAccelerations operator+ (const ChassisAccelerations &other) const
 Adds two ChassisAccelerations and returns the sum.
constexpr ChassisAccelerations operator- (const ChassisAccelerations &other) const
 Subtracts the other ChassisAccelerations from the current ChassisAccelerations and returns the difference.
constexpr ChassisAccelerations operator- () const
 Returns the inverse of the current ChassisAccelerations.
constexpr ChassisAccelerations operator* (double scalar) const
 Multiplies the ChassisAccelerations by a scalar and returns the new ChassisAccelerations.
constexpr ChassisAccelerations operator/ (double scalar) const
 Divides the ChassisAccelerations by a scalar and returns the new ChassisAccelerations.
constexpr bool operator== (const ChassisAccelerations &other) const =default
 Compares the ChassisAccelerations with another ChassisAccelerations.

Public Attributes

units::meters_per_second_squared_t ax = 0_mps_sq
 Acceleration along the x-axis.
units::meters_per_second_squared_t ay = 0_mps_sq
 Acceleration along the y-axis.
units::radians_per_second_squared_t alpha = 0_rad_per_s_sq
 Angular acceleration of the robot frame.

Detailed Description

Represents robot chassis accelerations.

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

Member Function Documentation

◆ operator*()

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

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

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

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

◆ operator+()

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

Adds two ChassisAccelerations and returns the sum.

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

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

◆ operator-() [1/2]

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

Returns the inverse of the current ChassisAccelerations.

This is equivalent to negating all components of the ChassisAccelerations.

Returns
The inverse of the current ChassisAccelerations.

◆ operator-() [2/2]

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

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

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

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

◆ operator/()

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

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

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

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

◆ operator==()

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

Compares the ChassisAccelerations with another ChassisAccelerations.

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

◆ ToFieldRelative()

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

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

◆ ToRobotRelative()

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

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

Member Data Documentation

◆ alpha

units::radians_per_second_squared_t wpi::math::ChassisAccelerations::alpha = 0_rad_per_s_sq

Angular acceleration of the robot frame.

(CCW is +)

◆ ax

units::meters_per_second_squared_t wpi::math::ChassisAccelerations::ax = 0_mps_sq

Acceleration along the x-axis.

(Fwd is +)

◆ ay

units::meters_per_second_squared_t wpi::math::ChassisAccelerations::ay = 0_mps_sq

Acceleration along the y-axis.

(Left is +)


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