|
bool | makePlanService (navfn::MakeNavPlan::Request &req, navfn::MakeNavPlan::Response &resp) |
|
| PlannerWithCostmap (string name, Costmap2DROS *cmap) |
|
bool | computePotential (const geometry_msgs::Point &world_point) |
| Computes the full navigation function for the map given a point in the world to start from. More...
|
|
bool | getPlanFromPotential (double start_x, double start_y, double end_x, double end_y, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan) |
| Compute a plan to a goal after the potential for a start point has already been computed (Note: You should call computePotential first) More...
|
|
double | getPointPotential (const geometry_msgs::Point &world_point) |
| Get the potential, or naviagation cost, at a given point in the world (Note: You should call computePotential first) More...
|
|
| GlobalPlanner () |
| Default constructor for the PlannerCore object. More...
|
|
| GlobalPlanner (std::string name, costmap_2d::Costmap2D *costmap, std::string frame_id) |
| Constructor for the PlannerCore object. More...
|
|
void | initialize (std::string name, costmap_2d::Costmap2DROS *costmap_ros) |
| Initialization function for the PlannerCore object. More...
|
|
void | initialize (std::string name, costmap_2d::Costmap2D *costmap, std::string frame_id) |
|
bool | makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan) |
| Given a goal pose in the world, compute a plan. More...
|
|
bool | makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, double tolerance, std::vector< geometry_msgs::PoseStamped > &plan) |
| Given a goal pose in the world, compute a plan. More...
|
|
bool | makePlanService (nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp) |
|
void | publishPlan (const std::vector< geometry_msgs::PoseStamped > &path) |
| Publish a path for visualization purposes. More...
|
|
bool | validPointPotential (const geometry_msgs::Point &world_point) |
| Check for a valid potential value at a given point in the world (Note: You should call computePotential first) More...
|
|
bool | validPointPotential (const geometry_msgs::Point &world_point, double tolerance) |
| Check for a valid potential value at a given point in the world (Note: You should call computePotential first) More...
|
|
| ~GlobalPlanner () |
| Default deconstructor for the PlannerCore object. More...
|
|
virtual bool | makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan, double &cost) |
|
virtual | ~BaseGlobalPlanner () |
|
Definition at line 54 of file plan_node.cpp.