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