|
units::second_t | time = 0_s |
|
frc::ChassisSpeeds | fieldSpeeds |
|
frc::Pose2d | pose |
|
units::meters_per_second_t | linearVelocity = 0_mps |
|
DriveFeedforwards | feedforwards |
|
frc::Rotation2d | heading |
|
units::meter_t | deltaPos = 0_m |
|
frc::Rotation2d | deltaRot |
|
std::vector< SwerveModuleTrajectoryState > | moduleStates |
|
PathConstraints | constraints |
|
double | waypointRelativePos = 0.0 |
|
◆ copyWithTime()
Copy this state and change the timestamp
- Parameters
-
- Returns
- Copied state with the given time
◆ flip()
Flip this trajectory state for the other side of the field, maintaining a blue alliance origin
- Returns
- This trajectory state flipped to the other side of the field
◆ interpolate()
Interpolate between this state and the given state
- Parameters
-
endVal | State to interpolate with |
t | Interpolation factor (0.0-1.0) |
- Returns
- Interpolated state
◆ reverse()
Get the state reversed, used for following a trajectory reversed with a differential drivetrain
- Returns
- The reversed state
The documentation for this class was generated from the following files:
- src/main/native/include/pathplanner/lib/trajectory/PathPlannerTrajectoryState.h
- src/main/native/cpp/pathplanner/lib/trajectory/PathPlannerTrajectoryState.cpp