Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef NAVFN_NAVFN_ROS_H_
00038 #define NAVFN_NAVFN_ROS_H_
00039
00040 #include <ros/ros.h>
00041 #include <navfn/navfn.h>
00042 #include <costmap_2d/costmap_2d_ros.h>
00043 #include <geometry_msgs/PoseStamped.h>
00044 #include <geometry_msgs/Point.h>
00045 #include <nav_msgs/Path.h>
00046 #include <tf/transform_datatypes.h>
00047 #include <vector>
00048 #include <nav_core/base_global_planner.h>
00049 #include <nav_msgs/GetPlan.h>
00050 #include <navfn/potarr_point.h>
00051 #include <pcl_ros/publisher.h>
00052
00053 namespace navfn {
00058 class NavfnROS : public nav_core::BaseGlobalPlanner {
00059 public:
00063 NavfnROS();
00064
00070 NavfnROS(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
00071
00077 void initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros);
00078
00086 bool makePlan(const geometry_msgs::PoseStamped& start,
00087 const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan);
00088
00097 bool makePlan(const geometry_msgs::PoseStamped& start,
00098 const geometry_msgs::PoseStamped& goal, double tolerance, std::vector<geometry_msgs::PoseStamped>& plan);
00099
00105 bool computePotential(const geometry_msgs::Point& world_point);
00106
00113 bool getPlanFromPotential(const geometry_msgs::PoseStamped& goal, std::vector<geometry_msgs::PoseStamped>& plan);
00114
00120 double getPointPotential(const geometry_msgs::Point& world_point);
00121
00127 bool validPointPotential(const geometry_msgs::Point& world_point);
00128
00135 bool validPointPotential(const geometry_msgs::Point& world_point, double tolerance);
00136
00140 void publishPlan(const std::vector<geometry_msgs::PoseStamped>& path, double r, double g, double b, double a);
00141
00142 ~NavfnROS(){delete costmap_publisher_;}
00143
00144 bool makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp);
00145
00146 protected:
00147
00151 virtual void getCostmap(costmap_2d::Costmap2D& costmap);
00152 costmap_2d::Costmap2DROS* costmap_ros_;
00153 boost::shared_ptr<NavFn> planner_;
00154 double inscribed_radius_, circumscribed_radius_, inflation_radius_;
00155 ros::Publisher plan_pub_;
00156 pcl_ros::Publisher<PotarrPoint> potarr_pub_;
00157 bool initialized_, allow_unknown_, visualize_potential_;
00158
00159
00160 private:
00161 inline double sq_distance(const geometry_msgs::PoseStamped& p1, const geometry_msgs::PoseStamped& p2){
00162 double dx = p1.pose.position.x - p2.pose.position.x;
00163 double dy = p1.pose.position.y - p2.pose.position.y;
00164 return dx*dx +dy*dy;
00165 }
00166
00167 void mapToWorld(double mx, double my, double& wx, double& wy);
00168 void clearRobotCell(const tf::Stamped<tf::Pose>& global_pose, unsigned int mx, unsigned int my);
00169 costmap_2d::Costmap2D costmap_;
00170 double planner_window_x_, planner_window_y_, default_tolerance_;
00171 costmap_2d::Costmap2DPublisher* costmap_publisher_;
00172 std::string tf_prefix_;
00173 boost::mutex mutex_;
00174 ros::ServiceServer make_plan_srv_;
00175 };
00176 };
00177
00178 #endif