class
AdaptivePurePursuitControllerThe AdaptivePurePurePursuitController is a controller that drives the robot along a path using the pure pursuit algorithn.
In each iteration, the controller computes the lookahead point on the path that is one lookahead distance away from the robot. The robot then drives towards the point at constant curvature given the target velocity. This process is repeated until the end of the path is reached.
Public types
Constructors, destructors, conversion operators
- AdaptivePurePursuitController(const std::shared_ptr<OdomChassisController>& chassis, const Gains& gains, const TimeUtil& timeUtil, std::unique_ptr<FeedforwardController<QLength>> leftController = nullptr, std::unique_ptr<FeedforwardController<QLength>> rightController = nullptr)
- Constructs a new AdaptivePurePursuitController.
Public functions
- void followPath(const DiscretePath& path, QTime timeout = 2_min, bool isReversed = false)
- Follows the given path.
- void stop()
- Stops the chassis and any running movements.
- void waitUntilSettled()
- Blocks the current movement until the movement is complete.
Function documentation
rz:: AdaptivePurePursuitController:: AdaptivePurePursuitController(const std::shared_ptr<OdomChassisController>& chassis,
const Gains& gains,
const TimeUtil& timeUtil,
std::unique_ptr<FeedforwardController<QLength>> leftController = nullptr,
std::unique_ptr<FeedforwardController<QLength>> rightController = nullptr)
Constructs a new AdaptivePurePursuitController.
Parameters | |
---|---|
chassis | The chassis to control |
gains | The gains to use |
timeUtil | The time utility to use |
leftController | The left side feedforward velocity controller. If this is null, the controller will use vex's internal velocity control |
rightController | The right side feedforward velocity controller. If this is null, the controller will use vex's internal velocity control |
void rz:: AdaptivePurePursuitController:: followPath(const DiscretePath& path,
QTime timeout = 2_min,
bool isReversed = false)
Follows the given path.
Parameters | |
---|---|
path | The path to follow |
timeout | The maximum time allowed to follow the path. This is to prevent the robot from getting stuck |
isReversed | Whether or not to follow the path in reverse |
The path is followed until the end is reached or the timeout is exceeded.