plan_node.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Bhaskara Marthi
36  * David V. Lu!!
37  *********************************************************************/
39 #include <navfn/MakeNavPlan.h>
40 #include <boost/shared_ptr.hpp>
42 
43 namespace cm = costmap_2d;
44 namespace rm = geometry_msgs;
45 
46 using std::vector;
47 using rm::PoseStamped;
48 using std::string;
49 using cm::Costmap2D;
50 using cm::Costmap2DROS;
51 
52 namespace global_planner {
53 
55  public:
56  PlannerWithCostmap(string name, Costmap2DROS* cmap);
57  bool makePlanService(navfn::MakeNavPlan::Request& req, navfn::MakeNavPlan::Response& resp);
58 
59  private:
60  void poseCallback(const rm::PoseStamped::ConstPtr& goal);
61  Costmap2DROS* cmap_;
64 };
65 
66 bool PlannerWithCostmap::makePlanService(navfn::MakeNavPlan::Request& req, navfn::MakeNavPlan::Response& resp) {
67  vector<PoseStamped> path;
68 
69  req.start.header.frame_id = "/map";
70  req.goal.header.frame_id = "/map";
71  bool success = makePlan(req.start, req.goal, path);
72  resp.plan_found = success;
73  if (success) {
74  resp.path = path;
75  }
76 
77  return true;
78 }
79 
80 void PlannerWithCostmap::poseCallback(const rm::PoseStamped::ConstPtr& goal) {
81  tf::Stamped<tf::Pose> global_pose;
82  cmap_->getRobotPose(global_pose);
83  vector<PoseStamped> path;
84  rm::PoseStamped start;
85  start.header.stamp = global_pose.stamp_;
86  start.header.frame_id = global_pose.frame_id_;
87  start.pose.position.x = global_pose.getOrigin().x();
88  start.pose.position.y = global_pose.getOrigin().y();
89  start.pose.position.z = global_pose.getOrigin().z();
90  start.pose.orientation.x = global_pose.getRotation().x();
91  start.pose.orientation.y = global_pose.getRotation().y();
92  start.pose.orientation.z = global_pose.getRotation().z();
93  start.pose.orientation.w = global_pose.getRotation().w();
94  makePlan(start, *goal, path);
95 }
96 
97 PlannerWithCostmap::PlannerWithCostmap(string name, Costmap2DROS* cmap) :
98  GlobalPlanner(name, cmap->getCostmap(), cmap->getGlobalFrameID()) {
99  ros::NodeHandle private_nh("~");
100  cmap_ = cmap;
102  pose_sub_ = private_nh.subscribe<rm::PoseStamped>("goal", 1, &PlannerWithCostmap::poseCallback, this);
103 }
104 
105 } // namespace
106 
107 int main(int argc, char** argv) {
108  ros::init(argc, argv, "global_planner");
109 
111 
112  costmap_2d::Costmap2DROS lcr("costmap", tf);
113 
114  global_planner::PlannerWithCostmap pppp("planner", &lcr);
115 
116  ros::spin();
117  return 0;
118 }
119 
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.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int main(int argc, char **argv)
Definition: plan_node.cpp:107
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void poseCallback(const rm::PoseStamped::ConstPtr &goal)
Definition: plan_node.cpp:80
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
PlannerWithCostmap(string name, Costmap2DROS *cmap)
Definition: plan_node.cpp:97
ROSCPP_DECL void spin(Spinner &spinner)
ros::Time stamp_
std::string frame_id_
ros::ServiceServer make_plan_service_
Definition: plan_node.cpp:62
bool makePlanService(navfn::MakeNavPlan::Request &req, navfn::MakeNavPlan::Response &resp)
Definition: plan_node.cpp:66


global_planner
Author(s): David Lu!!
autogenerated on Sun Mar 3 2019 03:44:42