plan_node.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2008, 2013, Willow Garage, Inc.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of Willow Garage, Inc. nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  * Author: Bhaskara Marthi
00036  *         David V. Lu!!
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 } // namespace
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 


global_planner
Author(s): David Lu!!
autogenerated on Wed Aug 2 2017 03:13:12