planner_node.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #include <ros/ros.h>
37 #include <nav_core2/exceptions.h>
39 #include <geometry_msgs/PoseStamped.h>
40 #include <geometry_msgs/PoseWithCovarianceStamped.h>
41 #include <visualization_msgs/Marker.h>
42 #include <string>
43 
44 namespace dlux_global_planner
45 {
61 {
62 public:
63  PlannerNode() : costmap_loader_("nav_core2", "nav_core2::Costmap"), has_start_(false), has_goal_(false)
64  {
65  ros::NodeHandle nh("~");
66  marker_pub_ = nh.advertise<visualization_msgs::Marker>("/visualization_marker", 10);
67 
68  tf_ = std::make_shared<tf::TransformListener>(ros::Duration(10));
69  std::string costmap_class;
70  nh.param("global_costmap_class", costmap_class, std::string("nav_core_adapter::CostmapAdapter"));
71  costmap_ = costmap_loader_.createUniqueInstance(costmap_class);
72  costmap_->initialize(nh, std::string("global_costmap"), tf_);
73 
74  gp_.initialize(nh, "planner", tf_, costmap_);
75  goal_sub_ = nh.subscribe<geometry_msgs::PoseStamped>("/move_base_simple/goal", 1,
76  boost::bind(&PlannerNode::goalCB, this, _1));
77  pose_sub_ = nh.subscribe<geometry_msgs::PoseWithCovarianceStamped>("/initialpose", 1,
78  boost::bind(&PlannerNode::poseCB, this, _1));
79  nh.param("red", red_, 1.0);
80  nh.param("green", green_, 1.0);
81  nh.param("blue", blue_, 1.0);
82  nh.param("marker_ns", marker_ns_, std::string(""));
83  }
84 
86  {
87  costmap_.reset();
88  }
89 private:
90  void goalCB(const geometry_msgs::PoseStamped::ConstPtr& goal)
91  {
92  has_goal_ = true;
94  publishPointMarker(goal_, false);
95  plan();
96  }
97 
98  void poseCB(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& goal)
99  {
100  has_start_ = true;
101  start_.header = goal->header;
102  start_.pose.x = goal->pose.pose.position.x;
103  start_.pose.y = goal->pose.pose.position.y;
104  publishPointMarker(start_, true);
105  plan();
106  }
107 
108  void plan()
109  {
110  if (!has_goal_ || !has_start_) return;
111  nav_2d_msgs::Path2D plan;
112  try
113  {
114  plan = gp_.makePlan(start_, goal_);
115  }
116  catch (nav_core2::PlannerException& e)
117  {
118  ROS_ERROR("%s", e.what());
119  }
120 
121  // publish plan as markers
122  nav_msgs::Path path = nav_2d_utils::pathToPath(plan);
123  double resolution = costmap_->getResolution();
124 
125  visualization_msgs::Marker m;
126  m.header.stamp = ros::Time::now();
127  m.header.frame_id = plan.header.frame_id;
128  m.ns = marker_ns_ + "path";
129  m.type = visualization_msgs::Marker::LINE_STRIP;
130  m.scale.x = resolution / 4;
131  m.color.r = red_;
132  m.color.g = green_;
133  m.color.b = blue_;
134  m.color.a = 0.7;
135  for (unsigned int i = 0; i < plan.poses.size(); i++)
136  {
137  m.points.push_back(path.poses[i].pose.position);
138  }
139  marker_pub_.publish(m);
140 
141  m.type = visualization_msgs::Marker::SPHERE_LIST;
142  m.id += 1;
143  m.color.r = red_ / 2;
144  m.color.g = green_ / 2;
145  m.color.b = blue_ / 2;
146  m.scale.x = resolution / 2;
147  m.scale.y = resolution / 2;
148  m.scale.z = resolution / 2;
149  marker_pub_.publish(m);
150  }
151 
152  void publishPointMarker(nav_2d_msgs::Pose2DStamped pose, bool start)
153  {
154  visualization_msgs::Marker m;
155  m.header = pose.header;
156  m.header.stamp = ros::Time::now();
157  m.ns = (start ? "start" : "goal");
158  m.type = visualization_msgs::Marker::CYLINDER;
159  m.pose.position.x = pose.pose.x;
160  m.pose.position.y = pose.pose.y;
161 
162  double resolution = costmap_->getResolution();
163  m.scale.x = 4 * resolution;
164  m.scale.y = 4 * resolution;
165  m.scale.z = 0.1;
166  m.color.r = start ? 0.0 : 1.0;
167  m.color.g = start ? 1.0 : 0.0;
168  m.color.a = 0.5;
169  marker_pub_.publish(m);
170  }
171 
174 
179 
180  nav_2d_msgs::Pose2DStamped start_, goal_;
182 
183  double red_, green_, blue_;
184  std::string marker_ns_;
185 };
186 } // namespace dlux_global_planner
187 
188 int main(int argc, char** argv)
189 {
190  ros::init(argc, argv, "global_planner");
192  ros::spin();
193  return 0;
194 }
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Demonstration/debug tool that creates paths between arbitrary points.
nav_2d_msgs::Path2D pathToPath(const nav_msgs::Path &path)
void poseCB(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &goal)
nav_2d_msgs::Pose2DStamped goal_
ROSCPP_DECL void spin(Spinner &spinner)
nav_2d_msgs::Pose2DStamped poseStampedToPose2D(const geometry_msgs::PoseStamped &pose)
pluginlib::ClassLoader< nav_core2::Costmap > costmap_loader_
int main(int argc, char **argv)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
nav_2d_msgs::Pose2DStamped start_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Plugin-based global wavefront planner that conforms to the nav_core2 GlobalPlanner interface...
void publishPointMarker(nav_2d_msgs::Pose2DStamped pose, bool start)
nav_2d_msgs::Path2D makePlan(const nav_2d_msgs::Pose2DStamped &start, const nav_2d_msgs::Pose2DStamped &goal) override
nav_core2::Costmap::Ptr costmap_
static Time now()
void initialize(const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) override
std::shared_ptr< Costmap > Ptr
std::shared_ptr< tf::TransformListener > TFListenerPtr
dlux_global_planner::DluxGlobalPlanner gp_
#define ROS_ERROR(...)
void goalCB(const geometry_msgs::PoseStamped::ConstPtr &goal)


dlux_global_planner
Author(s):
autogenerated on Wed Jun 26 2019 20:06:30