Provides a ROS wrapper for the navfn planner which runs a fast, interpolated navigation function on a costmap. More...
#include <navfn_ros.h>

| Public Member Functions | |
| 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 () | |
|  Public Member Functions inherited from nav_core::BaseGlobalPlanner | |
| virtual bool | makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan, double &cost) | 
| virtual | ~BaseGlobalPlanner () | 
| Protected Attributes | |
| bool | allow_unknown_ | 
| costmap_2d::Costmap2D * | costmap_ | 
| Store a copy of the current costmap in costmap. Called by makePlan.  More... | |
| bool | initialized_ | 
| ros::Publisher | plan_pub_ | 
| boost::shared_ptr< NavFn > | planner_ | 
| ros::Publisher | potarr_pub_ | 
| bool | visualize_potential_ | 
| Private Member Functions | |
| void | clearRobotCell (const geometry_msgs::PoseStamped &global_pose, unsigned int mx, unsigned int my) | 
| void | mapToWorld (double mx, double my, double &wx, double &wy) | 
| double | sq_distance (const geometry_msgs::PoseStamped &p1, const geometry_msgs::PoseStamped &p2) | 
| Private Attributes | |
| double | default_tolerance_ | 
| std::string | global_frame_ | 
| ros::ServiceServer | make_plan_srv_ | 
| boost::mutex | mutex_ | 
| double | planner_window_x_ | 
| double | planner_window_y_ | 
| Additional Inherited Members | |
|  Protected Member Functions inherited from nav_core::BaseGlobalPlanner | |
| BaseGlobalPlanner () | |
Provides a ROS wrapper for the navfn planner which runs a fast, interpolated navigation function on a costmap.
Definition at line 91 of file navfn_ros.h.
| navfn::NavfnROS::NavfnROS | ( | ) | 
Default constructor for the NavFnROS object.
Definition at line 83 of file navfn_ros.cpp.
| navfn::NavfnROS::NavfnROS | ( | std::string | name, | 
| costmap_2d::Costmap2DROS * | costmap_ros | ||
| ) | 
Constructor for the NavFnROS object.
| name | The name of this planner | 
| costmap | A pointer to the ROS wrapper of the costmap to use | 
Definition at line 86 of file navfn_ros.cpp.
| navfn::NavfnROS::NavfnROS | ( | std::string | name, | 
| costmap_2d::Costmap2D * | costmap, | ||
| std::string | global_frame | ||
| ) | 
Constructor for the NavFnROS object.
| name | The name of this planner | 
| costmap | A pointer to the costmap to use | 
| global_frame | The global frame of the costmap | 
Definition at line 92 of file navfn_ros.cpp.
| 
 | inline | 
Definition at line 191 of file navfn_ros.h.
| 
 | private | 
Definition at line 204 of file navfn_ros.cpp.
| bool navfn::NavfnROS::computePotential | ( | const geometry_msgs::Point & | world_point | ) | 
Computes the full navigation function for the map given a point in the world to start from.
| world_point | The point to use for seeding the navigation function | 
Definition at line 176 of file navfn_ros.cpp.
| bool navfn::NavfnROS::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)
| goal | The goal pose to create a plan to | 
| plan | The plan... filled by the planner | 
Definition at line 405 of file navfn_ros.cpp.
| double navfn::NavfnROS::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)
| world_point | The point to get the potential for | 
Definition at line 162 of file navfn_ros.cpp.
| void navfn::NavfnROS::initialize | ( | std::string | name, | 
| costmap_2d::Costmap2D * | costmap, | ||
| std::string | global_frame | ||
| ) | 
Initialization function for the NavFnROS object.
| name | The name of this planner | 
| costmap | A pointer to the costmap to use for planning | 
| global_frame | The global frame of the costmap | 
Definition at line 98 of file navfn_ros.cpp.
| 
 | virtual | 
Initialization function for the NavFnROS object.
| name | The name of this planner | 
| costmap | A pointer to the ROS wrapper of the costmap to use for planning | 
Implements nav_core::BaseGlobalPlanner.
Definition at line 127 of file navfn_ros.cpp.
| bool navfn::NavfnROS::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.
| start | The start pose | 
| goal | The goal pose | 
| tolerance | The tolerance on the goal point for the planner | 
| plan | The plan... filled by the planner | 
Definition at line 233 of file navfn_ros.cpp.
| 
 | virtual | 
Given a goal pose in the world, compute a plan.
| start | The start pose | 
| goal | The goal pose | 
| plan | The plan... filled by the planner | 
Implements nav_core::BaseGlobalPlanner.
Definition at line 228 of file navfn_ros.cpp.
| bool navfn::NavfnROS::makePlanService | ( | nav_msgs::GetPlan::Request & | req, | 
| nav_msgs::GetPlan::Response & | resp | ||
| ) | 
Definition at line 214 of file navfn_ros.cpp.
| 
 | private | 
Definition at line 223 of file navfn_ros.cpp.
| void navfn::NavfnROS::publishPlan | ( | const std::vector< geometry_msgs::PoseStamped > & | path, | 
| double | r, | ||
| double | g, | ||
| double | b, | ||
| double | a | ||
| ) | 
Publish a path for visualization purposes.
Definition at line 378 of file navfn_ros.cpp.
| 
 | inlineprivate | 
Definition at line 208 of file navfn_ros.h.
| bool navfn::NavfnROS::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)
| world_point | The point to get the potential for | 
Definition at line 131 of file navfn_ros.cpp.
| bool navfn::NavfnROS::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)
| world_point | The point to get the potential for | 
| tolerance | The tolerance on searching around the world_point specified | 
Definition at line 135 of file navfn_ros.cpp.
| 
 | protected | 
Definition at line 204 of file navfn_ros.h.
| 
 | protected | 
Store a copy of the current costmap in costmap. Called by makePlan.
Definition at line 200 of file navfn_ros.h.
| 
 | private | 
Definition at line 216 of file navfn_ros.h.
| 
 | private | 
Definition at line 219 of file navfn_ros.h.
| 
 | protected | 
Definition at line 204 of file navfn_ros.h.
| 
 | private | 
Definition at line 218 of file navfn_ros.h.
| 
 | private | 
Definition at line 217 of file navfn_ros.h.
| 
 | protected | 
Definition at line 202 of file navfn_ros.h.
| 
 | protected | 
Definition at line 201 of file navfn_ros.h.
| 
 | private | 
Definition at line 216 of file navfn_ros.h.
| 
 | private | 
Definition at line 216 of file navfn_ros.h.
| 
 | protected | 
Definition at line 203 of file navfn_ros.h.
| 
 | protected | 
Definition at line 204 of file navfn_ros.h.