| 
| bool  | makePlanService (MakeNavPlan::Request &req, MakeNavPlan::Response &resp) | 
|   | 
|   | NavfnWithCostmap (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 (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...
  | 
|   | 
| void  | initialize (std::string name, costmap_2d::Costmap2D *costmap, std::string global_frame) | 
|   | Initialization function for the NavFnROS object.  More...
  | 
|   | 
| void  | initialize (std::string name, costmap_2d::Costmap2DROS *costmap_ros) | 
|   | Initialization function for the NavFnROS object.  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  | 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  | makePlanService (nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp) | 
|   | 
|   | NavfnROS () | 
|   | Default constructor for the NavFnROS object.  More...
  | 
|   | 
|   | NavfnROS (std::string name, costmap_2d::Costmap2D *costmap, std::string global_frame) | 
|   | Constructor for the NavFnROS object.  More...
  | 
|   | 
|   | NavfnROS (std::string name, costmap_2d::Costmap2DROS *costmap_ros) | 
|   | Constructor for the NavFnROS object.  More...
  | 
|   | 
| void  | publishPlan (const std::vector< geometry_msgs::PoseStamped > &path, double r, double g, double b, double a) | 
|   | 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...
  | 
|   | 
|   | ~NavfnROS () | 
|   | 
| 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 navfn_node.cpp.