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 #include <navfn/navfn_ros.h>
00038 #include <navfn/MakeNavPlan.h>
00039 #include <boost/shared_ptr.hpp>
00040 #include <costmap_2d/costmap_2d_ros.h>
00041
00042 namespace cm=costmap_2d;
00043 namespace rm=geometry_msgs;
00044
00045 using std::vector;
00046 using rm::PoseStamped;
00047 using std::string;
00048 using cm::Costmap2D;
00049 using cm::Costmap2DROS;
00050
00051 namespace navfn {
00052
00053 class NavfnWithCostmap : public NavfnROS
00054 {
00055 public:
00056 NavfnWithCostmap(string name, Costmap2DROS* cmap);
00057 bool makePlanService(MakeNavPlan::Request& req, MakeNavPlan::Response& resp);
00058
00059 private:
00060 void poseCallback(const rm::PoseStamped::ConstPtr& goal);
00061 Costmap2DROS* cmap_;
00062 ros::ServiceServer make_plan_service_;
00063 ros::Subscriber pose_sub_;
00064 };
00065
00066
00067 bool NavfnWithCostmap::makePlanService(MakeNavPlan::Request& req, MakeNavPlan::Response& resp)
00068 {
00069 vector<PoseStamped> path;
00070
00071 req.start.header.frame_id = "/map";
00072 req.goal.header.frame_id = "/map";
00073 bool success = makePlan(req.start, req.goal, path);
00074 resp.plan_found = success;
00075 if (success) {
00076 resp.path = path;
00077 }
00078
00079 return true;
00080 }
00081
00082 void NavfnWithCostmap::poseCallback(const rm::PoseStamped::ConstPtr& goal) {
00083 tf::Stamped<tf::Pose> global_pose;
00084 cmap_->getRobotPose(global_pose);
00085 vector<PoseStamped> path;
00086 rm::PoseStamped start;
00087 start.header.stamp = global_pose.stamp_;
00088 start.header.frame_id = global_pose.frame_id_;
00089 start.pose.position.x = global_pose.getOrigin().x();
00090 start.pose.position.y = global_pose.getOrigin().y();
00091 start.pose.position.z = global_pose.getOrigin().z();
00092 start.pose.orientation.x = global_pose.getRotation().x();
00093 start.pose.orientation.y = global_pose.getRotation().y();
00094 start.pose.orientation.z = global_pose.getRotation().z();
00095 start.pose.orientation.w = global_pose.getRotation().w();
00096 makePlan(start, *goal, path);
00097 }
00098
00099
00100 NavfnWithCostmap::NavfnWithCostmap(string name, Costmap2DROS* cmap) :
00101 NavfnROS(name, cmap)
00102 {
00103 ros::NodeHandle private_nh("~");
00104 cmap_ = cmap;
00105 make_plan_service_ = private_nh.advertiseService("make_plan", &NavfnWithCostmap::makePlanService, this);
00106 pose_sub_ = private_nh.subscribe<rm::PoseStamped>("goal", 1, &NavfnWithCostmap::poseCallback, this);
00107 }
00108
00109 }
00110
00111 int main (int argc, char** argv)
00112 {
00113 ros::init(argc, argv, "global_planner");
00114
00115 tf::TransformListener tf(ros::Duration(10));
00116
00117 costmap_2d::Costmap2DROS lcr("costmap", tf);
00118
00119 navfn::NavfnWithCostmap navfn("navfn_planner", &lcr);
00120
00121 ros::spin();
00122 return 0;
00123 }
00124
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134
00135
00136
00137
00138
00139