#include <choreo/trajectory/SwerveSample.h>
|
constexpr | SwerveSample ()=default |
|
constexpr | SwerveSample (units::second_t timestamp, units::meter_t x, units::meter_t y, units::radian_t heading, units::meters_per_second_t vx, units::meters_per_second_t vy, units::radians_per_second_t omega, units::meters_per_second_squared_t ax, units::meters_per_second_squared_t ay, units::radians_per_second_squared_t alpha, std::array< units::newton_t, 4 > moduleForcesX, std::array< units::newton_t, 4 > moduleForcesY) |
|
constexpr units::second_t | GetTimestamp () const |
|
constexpr frc::Pose2d | GetPose () const |
|
constexpr frc::ChassisSpeeds | GetChassisSpeeds () const |
|
template<int Year = util::kDefaultYear> |
constexpr SwerveSample | Flipped () const |
|
constexpr SwerveSample | OffsetBy (units::second_t timeStampOffset) const |
|
constexpr SwerveSample | Interpolate (const SwerveSample &endValue, units::second_t t) const |
|
constexpr bool | operator== (const SwerveSample &other) const |
|
|
units::second_t | timestamp = 0_s |
| The timestamp of this sample relative to the beginning of the trajectory.
|
|
units::meter_t | x = 0_m |
| The X position of the sample relative to the blue alliance wall origin.
|
|
units::meter_t | y = 0_m |
| The Y position of the sample relative to the blue alliance wall origin.
|
|
units::radian_t | heading = 0_rad |
| The heading of the sample, with 0 being in the +X direction.
|
|
units::meters_per_second_t | vx = 0_mps |
| The velocity of the sample in the X direction.
|
|
units::meters_per_second_t | vy = 0_mps |
| The velocity of the sample in the Y direction.
|
|
units::radians_per_second_t | omega = 0_rad_per_s |
| The angular velocity of the sample.
|
|
units::meters_per_second_squared_t | ax = 0_mps_sq |
| The acceleration of the in the X direction.
|
|
units::meters_per_second_squared_t | ay = 0_mps_sq |
| The acceleration of the in the Y direction.
|
|
units::radians_per_second_squared_t | alpha = 0_rad_per_s_sq |
| The angular acceleration of the sample.
|
|
std::array< units::newton_t, 4 > | moduleForcesX {0_N, 0_N, 0_N, 0_N} |
|
std::array< units::newton_t, 4 > | moduleForcesY {0_N, 0_N, 0_N, 0_N} |
|
A single swerve robot sample in a Trajectory.
◆ SwerveSample() [1/2]
constexpr choreo::SwerveSample::SwerveSample |
( |
| ) |
|
|
constexprdefault |
◆ SwerveSample() [2/2]
constexpr choreo::SwerveSample::SwerveSample |
( |
units::second_t |
timestamp, |
|
|
units::meter_t |
x, |
|
|
units::meter_t |
y, |
|
|
units::radian_t |
heading, |
|
|
units::meters_per_second_t |
vx, |
|
|
units::meters_per_second_t |
vy, |
|
|
units::radians_per_second_t |
omega, |
|
|
units::meters_per_second_squared_t |
ax, |
|
|
units::meters_per_second_squared_t |
ay, |
|
|
units::radians_per_second_squared_t |
alpha, |
|
|
std::array< units::newton_t, 4 > |
moduleForcesX, |
|
|
std::array< units::newton_t, 4 > |
moduleForcesY |
|
) |
| |
|
inlineconstexpr |
Constructs a SwerveSample with the specified parameters.
- Parameters
-
timestamp | The timestamp of this sample, relative to the beginning of the trajectory. |
x | The X position of the sample |
y | The Y position of the sample |
heading | The heading of the sample, with 0 being in the +X direction. |
vx | The velocity of the sample in the X direction. |
vy | The velocity of the sample in the Y direction. |
omega | The angular velocity of the sample. |
ax | The acceleration of the sample in the X direction. |
ay | The acceleration of the sample in the Y direction. |
alpha | The angular acceleration of the sample. |
moduleForcesX | The force on each swerve module in the X direction. Module forces appear in the following order: [FL, FR, BL, BR]. |
moduleForcesY | The force on each swerve module in the Y direction. Module forces appear in the following order: [FL, FR, BL, BR]. |
◆ Flipped()
template<int Year = util::kDefaultYear>
constexpr SwerveSample choreo::SwerveSample::Flipped |
( |
| ) |
const |
|
inlineconstexpr |
Returns the current sample flipped based on the field year.
- Template Parameters
-
- Returns
- SwerveSample that is flipped based on the field layout.
◆ GetChassisSpeeds()
constexpr frc::ChassisSpeeds choreo::SwerveSample::GetChassisSpeeds |
( |
| ) |
const |
|
inlineconstexpr |
Gets the field-relative chassis speeds of the SwerveSample.
- Returns
- The field-relative chassis speeds.
◆ GetPose()
constexpr frc::Pose2d choreo::SwerveSample::GetPose |
( |
| ) |
const |
|
inlineconstexpr |
◆ GetTimestamp()
constexpr units::second_t choreo::SwerveSample::GetTimestamp |
( |
| ) |
const |
|
inlineconstexpr |
Gets the timestamp of the SwerveSample.
- Returns
- The timestamp.
◆ Interpolate()
Interpolates between endValue and this by t
- Parameters
-
endValue | the end interpolated value |
t | time to move sample by |
- Returns
- the interpolated sample
◆ OffsetBy()
constexpr SwerveSample choreo::SwerveSample::OffsetBy |
( |
units::second_t |
timeStampOffset | ) |
const |
|
inlineconstexpr |
Returns the current sample offset by a the time offset passed in.
- Parameters
-
timeStampOffset | time to move sample by |
- Returns
- SwerveSample that is moved forward by the offset
◆ operator==()
constexpr bool choreo::SwerveSample::operator== |
( |
const SwerveSample & |
other | ) |
const |
|
inlineconstexpr |
SwerveSample equality operator.
- Parameters
-
- Returns
- True for equality.
◆ moduleForcesX
std::array<units::newton_t, 4> choreo::SwerveSample::moduleForcesX {0_N, 0_N, 0_N, 0_N} |
The force on each swerve module in the X direction. Module forces appear in the following order: [FL, FR, BL, BR].
◆ moduleForcesY
std::array<units::newton_t, 4> choreo::SwerveSample::moduleForcesY {0_N, 0_N, 0_N, 0_N} |
The force on each swerve module in the Y direction. Module forces appear in the following order: [FL, FR, BL, BR].
The documentation for this class was generated from the following file: