|
enum | FieldSymmetry { kRotational
, kMirrored
} |
|
|
static frc::Translation2d | flipFieldPosition (const frc::Translation2d &pos) |
|
static frc::Rotation2d | flipFieldRotation (const frc::Rotation2d &rotation) |
|
static frc::Pose2d | flipFieldPose (const frc::Pose2d &pose) |
|
static frc::ChassisSpeeds | flipFieldSpeeds (const frc::ChassisSpeeds &fieldSpeeds) |
|
template<class UnitType , class = std::enable_if_t< units::traits::is_unit_t<UnitType>::value>> |
static std::vector< UnitType > | flipFeedforwards (const std::vector< UnitType > &feedforwards) |
|
template<class UnitType , class = std::enable_if_t< units::traits::is_unit_t<UnitType>::value>> |
static std::vector< UnitType > | flipFeedforwardXs (const std::vector< UnitType > &feedforwardXs) |
|
template<class UnitType , class = std::enable_if_t< units::traits::is_unit_t<UnitType>::value>> |
static std::vector< UnitType > | flipFeedforwardYs (const std::vector< UnitType > &feedforwardYs) |
|
|
static FieldSymmetry | symmetryType |
|
static units::meter_t | fieldSizeX = 57.573_ft |
|
static units::meter_t | fieldSizeY = 26.417_ft |
|
◆ flipFeedforwards()
template<class UnitType , class = std::enable_if_t< units::traits::is_unit_t<UnitType>::value>>
static std::vector< UnitType > pathplanner::FlippingUtil::flipFeedforwards |
( |
const std::vector< UnitType > & |
feedforwards | ) |
|
|
inlinestatic |
Flip an array of drive feedforwards for the other side of the field. Only does anything if mirrored symmetry is used
- Parameters
-
feedforwards | Array of drive feedforwards |
- Returns
- The flipped feedforwards
◆ flipFeedforwardXs()
template<class UnitType , class = std::enable_if_t< units::traits::is_unit_t<UnitType>::value>>
static std::vector< UnitType > pathplanner::FlippingUtil::flipFeedforwardXs |
( |
const std::vector< UnitType > & |
feedforwardXs | ) |
|
|
inlinestatic |
Flip an array of drive feedforward X components for the other side of the field. Only does anything if mirrored symmetry is used
- Parameters
-
feedforwardXs | Array of drive feedforward X components |
- Returns
- The flipped feedforward X components
◆ flipFeedforwardYs()
template<class UnitType , class = std::enable_if_t< units::traits::is_unit_t<UnitType>::value>>
static std::vector< UnitType > pathplanner::FlippingUtil::flipFeedforwardYs |
( |
const std::vector< UnitType > & |
feedforwardYs | ) |
|
|
inlinestatic |
Flip an array of drive feedforward Y components for the other side of the field. Only does anything if mirrored symmetry is used
- Parameters
-
feedforwardYs | Array of drive feedforward Y components |
- Returns
- The flipped feedforward Y components
◆ flipFieldPose()
static frc::Pose2d pathplanner::FlippingUtil::flipFieldPose |
( |
const frc::Pose2d & |
pose | ) |
|
|
inlinestatic |
Flip a field pose to the other side of the field, maintaining a blue alliance origin
- Parameters
-
- Returns
- The flipped pose
◆ flipFieldPosition()
static frc::Translation2d pathplanner::FlippingUtil::flipFieldPosition |
( |
const frc::Translation2d & |
pos | ) |
|
|
inlinestatic |
Flip a field position to the other side of the field, maintaining a blue alliance origin
- Parameters
-
- Returns
- The flipped position
◆ flipFieldRotation()
static frc::Rotation2d pathplanner::FlippingUtil::flipFieldRotation |
( |
const frc::Rotation2d & |
rotation | ) |
|
|
inlinestatic |
Flip a field rotation to the other side of the field, maintaining a blue alliance origin
- Parameters
-
rotation | The rotation to flip |
- Returns
- The flipped rotation
◆ flipFieldSpeeds()
static frc::ChassisSpeeds pathplanner::FlippingUtil::flipFieldSpeeds |
( |
const frc::ChassisSpeeds & |
fieldSpeeds | ) |
|
|
inlinestatic |
Flip field relative chassis speeds for the other side of the field, maintaining a blue alliance origin
- Parameters
-
fieldSpeeds | Field relative chassis speeds |
- Returns
- Flipped speeds
◆ symmetryType
FlippingUtil::FieldSymmetry FlippingUtil::symmetryType |
|
static |
Initial value:=
FlippingUtil::FieldSymmetry::kRotational
The documentation for this class was generated from the following files:
- src/main/native/include/pathplanner/lib/util/FlippingUtil.h
- src/main/native/cpp/pathplanner/lib/util/FlippingUtil.cpp