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>
43 
44 namespace cm = costmap_2d;
45 namespace rm = geometry_msgs;
46 
47 using std::vector;
48 using rm::PoseStamped;
49 using std::string;
50 using cm::Costmap2D;
51 using cm::Costmap2DROS;
52 
53 namespace global_planner {
54 
56  public:
57  PlannerWithCostmap(string name, Costmap2DROS* cmap);
58  bool makePlanService(navfn::MakeNavPlan::Request& req, navfn::MakeNavPlan::Response& resp);
59 
60  private:
61  void poseCallback(const rm::PoseStamped::ConstPtr& goal);
65 };
66 
67 bool PlannerWithCostmap::makePlanService(navfn::MakeNavPlan::Request& req, navfn::MakeNavPlan::Response& resp) {
68  vector<PoseStamped> path;
69 
70  req.start.header.frame_id = "map";
71  req.goal.header.frame_id = "map";
72  bool success = makePlan(req.start, req.goal, path);
73  resp.plan_found = success;
74  if (success) {
75  resp.path = path;
76  }
77 
78  return true;
79 }
80 
81 void PlannerWithCostmap::poseCallback(const rm::PoseStamped::ConstPtr& goal) {
82  geometry_msgs::PoseStamped global_pose;
83  cmap_->getRobotPose(global_pose);
84  vector<PoseStamped> path;
85  makePlan(global_pose, *goal, path);
86 }
87 
89  GlobalPlanner(name, cmap->getCostmap(), cmap->getGlobalFrameID()) {
90  ros::NodeHandle private_nh("~");
91  cmap_ = cmap;
93  pose_sub_ = private_nh.subscribe<rm::PoseStamped>("goal", 1, &PlannerWithCostmap::poseCallback, this);
94 }
95 
96 } // namespace
97 
98 int main(int argc, char** argv) {
99  ros::init(argc, argv, "global_planner");
100 
101  tf2_ros::Buffer buffer(ros::Duration(10));
103 
104  costmap_2d::Costmap2DROS lcr("costmap", buffer);
105 
106  global_planner::PlannerWithCostmap pppp("planner", &lcr);
107 
108  ros::spin();
109  return 0;
110 }
111 
global_planner::PlannerWithCostmap::PlannerWithCostmap
PlannerWithCostmap(string name, Costmap2DROS *cmap)
Definition: plan_node.cpp:88
global_planner
Definition: astar.h:46
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
global_planner::PlannerWithCostmap
Definition: plan_node.cpp:55
geometry_msgs
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
costmap_2d::Costmap2D
costmap_2d_ros.h
ros::ServiceServer
global_planner::GlobalPlanner
Definition: planner_core.h:66
tf2_ros::TransformListener
planner_core.h
global_planner::PlannerWithCostmap::makePlanService
bool makePlanService(navfn::MakeNavPlan::Request &req, navfn::MakeNavPlan::Response &resp)
Definition: plan_node.cpp:67
global_planner::PlannerWithCostmap::poseCallback
void poseCallback(const rm::PoseStamped::ConstPtr &goal)
Definition: plan_node.cpp:81
tf2_ros::Buffer
global_planner::PlannerWithCostmap::cmap_
Costmap2DROS * cmap_
Definition: plan_node.cpp:62
goal
int goal[2]
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
global_planner::GlobalPlanner::makePlan
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.
Definition: planner_core.cpp:249
transform_listener.h
main
int main(int argc, char **argv)
Definition: plan_node.cpp:98
costmap_2d::Costmap2DROS::getRobotPose
bool getRobotPose(geometry_msgs::PoseStamped &global_pose) const
ros::spin
ROSCPP_DECL void spin()
tf
costmap_2d
ros::Duration
costmap_2d::Costmap2DROS
ros::NodeHandle
ros::Subscriber
global_planner::PlannerWithCostmap::pose_sub_
ros::Subscriber pose_sub_
Definition: plan_node.cpp:64
global_planner::PlannerWithCostmap::make_plan_service_
ros::ServiceServer make_plan_service_
Definition: plan_node.cpp:63


global_planner
Author(s): David Lu!!
autogenerated on Mon Mar 6 2023 03:50:40