![]() |
WPILibC++ 2027.0.0-alpha-4
|
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. | |
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.
|
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}
| scalar | The scalar to multiply by. |
|
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}
| other | The ChassisAccelerations to add. |
|
inlineconstexpr |
Returns the inverse of the current ChassisAccelerations.
This is equivalent to negating all components of the ChassisAccelerations.
|
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}
| other | The ChassisAccelerations to subtract. |
|
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}
| scalar | The scalar to divide by. |
|
constexprdefault |
Compares the ChassisAccelerations with another ChassisAccelerations.
| other | The other ChassisAccelerations. |
|
inlineconstexpr |
Converts this robot-relative set of accelerations into a field-relative ChassisAccelerations object.
| 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 |
Converts this field-relative set of accelerations into a robot-relative ChassisAccelerations object.
| 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. |
| units::radians_per_second_squared_t wpi::math::ChassisAccelerations::alpha = 0_rad_per_s_sq |
Angular acceleration of the robot frame.
(CCW is +)
| units::meters_per_second_squared_t wpi::math::ChassisAccelerations::ax = 0_mps_sq |
Acceleration along the x-axis.
(Fwd is +)
| units::meters_per_second_squared_t wpi::math::ChassisAccelerations::ay = 0_mps_sq |
Acceleration along the y-axis.
(Left is +)