Trajectory
- class wpimath.trajectory.Trajectory(*args, **kwargs)
Bases:
pybind11_object
Represents a time-parameterized trajectory. The trajectory contains of various States that represent the pose, curvature, time elapsed, velocity, and acceleration at that point.
Overloaded function.
__init__(self: wpimath._controls._controls.trajectory.Trajectory) -> None
__init__(self: wpimath._controls._controls.trajectory.Trajectory, states: List[wpimath._controls._controls.trajectory.Trajectory.State]) -> None
Constructs a trajectory from a vector of states.
- class State(t: seconds = 0.0, velocity: meters_per_second = 0.0, acceleration: meters_per_second_squared = 0.0, pose: wpimath.geometry._geometry.Pose2d = Pose2d(Translation2d(x=0.000000, y=0.000000), Rotation2d(0.000000)), curvature: radians_per_meter = 0.0)
Bases:
pybind11_object
Represents one point on the trajectory.
- property acceleration
- property acceleration_fps
- property curvature
- interpolate(endValue: wpimath._controls._controls.trajectory.Trajectory.State, i: float) wpimath._controls._controls.trajectory.Trajectory.State
Interpolates between two States.
- Parameters:
endValue – The end value for the interpolation.
i – The interpolant (fraction).
- Returns:
The interpolated state.
- property pose
- property t
- property velocity
- property velocity_fps
- initialPose() wpimath.geometry._geometry.Pose2d
Returns the initial pose of the trajectory.
- Returns:
The initial pose of the trajectory.
- relativeTo(pose: wpimath.geometry._geometry.Pose2d) wpimath._controls._controls.trajectory.Trajectory
Transforms all poses in the trajectory so that they are relative to the given pose. This is useful for converting a field-relative trajectory into a robot-relative trajectory.
- Parameters:
pose – The pose that is the origin of the coordinate frame that the current trajectory will be transformed into.
- Returns:
The transformed trajectory.
- sample(t: seconds) wpimath._controls._controls.trajectory.Trajectory.State
Sample the trajectory at a point in time.
- Parameters:
t – The point in time since the beginning of the trajectory to sample.
- Returns:
The state at that point in time.
- states() List[wpimath._controls._controls.trajectory.Trajectory.State]
Return the states of the trajectory.
- Returns:
The states of the trajectory.
- totalTime() seconds
Returns the overall duration of the trajectory.
- Returns:
The duration of the trajectory.
- transformBy(transform: wpimath.geometry._geometry.Transform2d) wpimath._controls._controls.trajectory.Trajectory
Transforms all poses in the trajectory by the given transform. This is useful for converting a robot-relative trajectory into a field-relative trajectory. This works with respect to the first pose in the trajectory.
- Parameters:
transform – The transform to transform the trajectory by.
- Returns:
The transformed trajectory.