#include <path.h>

Public Member Functions | |
| virtual bool | collides (const Shape *body, std::vector< Point > obstacles) | 
| Returns true iff the path collides with any static obstacles.   | |
| virtual Path * | copy ()=0 | 
| Returns a pointer that is a new instance of this object.  | |
| virtual PathPoint | getPathPoint (double d) const =0 | 
| Returns the waypoint at distance d.   | |
| virtual std::vector< PathPoint > | getPathPoints () const | 
| Returns a series of waypoints that describe the path.  | |
| PathPoint | getInitPathPoint () const | 
| Returns the waypoint where the path begins.  | |
| PathPoint | getFinalPathPoint () const | 
| Returns the waypoint where the path ends.  | |
| virtual double | getLength () const =0 | 
| Returns the total path length.  | |
| virtual bool | isReverse (double d) const | 
| Returns true if the path is moving in reverse and true otherwise.  | |
| virtual void | read (istream &is) | 
| Reads the path from an input stream using polymorphic >> operator.  | |
| virtual void | write (ostream &os) const | 
| Prints the path to an output stream using polymorphic << operator.  | |
Protected Attributes | |
| PathPoint | _wp0 | 
| initial waypoint  | |
Returns true iff the path collides with any static obstacles.
| body | vehicle shape | |
| obstacles | point cloud of obstacles | 
Reimplemented in navlib::PathChain, and navlib::DubinsC.
References _wp0, navlib::Shape::contains(), getPathPoints(), navlib::Shape::getPoints(), navlib::Pose::localize(), navlib::Pose::x, and navlib::Pose::y.
Referenced by navlib::NDPlanner::getPath().
| virtual PathPoint navlib::Path::getPathPoint | ( | double | d | ) |  const [pure virtual] | 
        
Returns the waypoint at distance d.
Returns the initial waypoint if d is less than zero and the final waypoint if d greater than the path length.
| length | along the path | 
Implemented in navlib::PathChain, navlib::ReversePath, navlib::DubinsC, navlib::DubinsS, and navlib::HKPath.
Referenced by navlib::FrenetSerretController::getAction(), getFinalPathPoint(), navlib::ReversePath::getPathPoint(), navlib::PathChain::getPathPoint(), and getPathPoints().
 1.5.5