abstract class TrajectoryFollower
Generic Trajectory follower for time-based pose reference tracking.
TrajectoryFollower(clock: NanoClock = NanoClock.system())
Generic Trajectory follower for time-based pose reference tracking. |
val clock: NanoClock
clock |
|
abstract var lastError: Pose2d
Robot pose error computed in the last update call. |
|
var trajectory: Trajectory |
fun elapsedTime(): Double
Returns the elapsed time since the last followTrajectory calls. |
|
fun followTrajectory(trajectory: Trajectory): Unit
Follow the given trajectory. |
|
fun isFollowing(): Boolean
Returns true if the current trajectory has finished executing. |
|
abstract fun update(currentPose: Pose2d): Unit
Run a single iteration of the trajectory follower. |
abstract class HolonomicPIDVAFollower : TrajectoryFollower
Traditional PID controller with feedforward velocity and acceleration components to follow a trajectory. More specifically, the feedback is applied to the components of the robot's pose (x position, y position, and heading) to determine the velocity correction. The feedforward components are instead applied at the wheel level. |
|
class RamseteFollower : TrajectoryFollower
Time-varying, non-linear feedback controller for nonholonomic drives. See equation 5.12 of Ramsete01.pdf. |
|
class TankPIDVAFollower : TrajectoryFollower
Traditional PID controller with feedforward velocity and acceleration components to follow a trajectory. More specifically, one feedback loop controls the path displacement (that is, x in the robot reference frame), and another feedback loop to minimize cross track (lateral) error via heading correction (overall, very similar to MecanumPIDVAFollower except adjusted for the nonholonomic constraint). Feedforward is applied at the wheel level. |