planner_core.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: Eitan Marder-Eppstein
36  * David V. Lu!!
37  *********************************************************************/
40 #include <tf/transform_listener.h>
41 #include <costmap_2d/cost_values.h>
42 #include <costmap_2d/costmap_2d.h>
43 
45 #include <global_planner/astar.h>
49 
50 //register this planner as a BaseGlobalPlanner plugin
52 
53 namespace global_planner {
54 
55 void GlobalPlanner::outlineMap(unsigned char* costarr, int nx, int ny, unsigned char value) {
56  unsigned char* pc = costarr;
57  for (int i = 0; i < nx; i++)
58  *pc++ = value;
59  pc = costarr + (ny - 1) * nx;
60  for (int i = 0; i < nx; i++)
61  *pc++ = value;
62  pc = costarr;
63  for (int i = 0; i < ny; i++, pc += nx)
64  *pc = value;
65  pc = costarr + nx - 1;
66  for (int i = 0; i < ny; i++, pc += nx)
67  *pc = value;
68 }
69 
70 GlobalPlanner::GlobalPlanner() :
71  costmap_(NULL), initialized_(false), allow_unknown_(true) {
72 }
73 
74 GlobalPlanner::GlobalPlanner(std::string name, costmap_2d::Costmap2D* costmap, std::string frame_id) :
75  costmap_(NULL), initialized_(false), allow_unknown_(true) {
76  //initialize the planner
77  initialize(name, costmap, frame_id);
78 }
79 
81  if (p_calc_)
82  delete p_calc_;
83  if (planner_)
84  delete planner_;
85  if (path_maker_)
86  delete path_maker_;
87  if (dsrv_)
88  delete dsrv_;
89 }
90 
91 void GlobalPlanner::initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros) {
92  initialize(name, costmap_ros->getCostmap(), costmap_ros->getGlobalFrameID());
93 }
94 
95 void GlobalPlanner::initialize(std::string name, costmap_2d::Costmap2D* costmap, std::string frame_id) {
96  if (!initialized_) {
97  ros::NodeHandle private_nh("~/" + name);
98  costmap_ = costmap;
99  frame_id_ = frame_id;
100 
101  unsigned int cx = costmap->getSizeInCellsX(), cy = costmap->getSizeInCellsY();
102 
103  private_nh.param("old_navfn_behavior", old_navfn_behavior_, false);
105  convert_offset_ = 0.5;
106  else
107  convert_offset_ = 0.0;
108 
109  bool use_quadratic;
110  private_nh.param("use_quadratic", use_quadratic, true);
111  if (use_quadratic)
112  p_calc_ = new QuadraticCalculator(cx, cy);
113  else
114  p_calc_ = new PotentialCalculator(cx, cy);
115 
116  bool use_dijkstra;
117  private_nh.param("use_dijkstra", use_dijkstra, true);
118  if (use_dijkstra)
119  {
120  DijkstraExpansion* de = new DijkstraExpansion(p_calc_, cx, cy);
122  de->setPreciseStart(true);
123  planner_ = de;
124  }
125  else
126  planner_ = new AStarExpansion(p_calc_, cx, cy);
127 
128  bool use_grid_path;
129  private_nh.param("use_grid_path", use_grid_path, false);
130  if (use_grid_path)
132  else
134 
136 
137  plan_pub_ = private_nh.advertise<nav_msgs::Path>("plan", 1);
138  potential_pub_ = private_nh.advertise<nav_msgs::OccupancyGrid>("potential", 1);
139 
140  private_nh.param("allow_unknown", allow_unknown_, true);
142  private_nh.param("planner_window_x", planner_window_x_, 0.0);
143  private_nh.param("planner_window_y", planner_window_y_, 0.0);
144  private_nh.param("default_tolerance", default_tolerance_, 0.0);
145  private_nh.param("publish_scale", publish_scale_, 100);
146 
147  double costmap_pub_freq;
148  private_nh.param("planner_costmap_publish_frequency", costmap_pub_freq, 0.0);
149 
150  //get the tf prefix
151  ros::NodeHandle prefix_nh;
152  tf_prefix_ = tf::getPrefixParam(prefix_nh);
153 
154  make_plan_srv_ = private_nh.advertiseService("make_plan", &GlobalPlanner::makePlanService, this);
155 
156  dsrv_ = new dynamic_reconfigure::Server<global_planner::GlobalPlannerConfig>(ros::NodeHandle("~/" + name));
157  dynamic_reconfigure::Server<global_planner::GlobalPlannerConfig>::CallbackType cb = boost::bind(
158  &GlobalPlanner::reconfigureCB, this, _1, _2);
159  dsrv_->setCallback(cb);
160 
161  initialized_ = true;
162  } else
163  ROS_WARN("This planner has already been initialized, you can't call it twice, doing nothing");
164 
165 }
166 
167 void GlobalPlanner::reconfigureCB(global_planner::GlobalPlannerConfig& config, uint32_t level) {
168  planner_->setLethalCost(config.lethal_cost);
169  path_maker_->setLethalCost(config.lethal_cost);
170  planner_->setNeutralCost(config.neutral_cost);
171  planner_->setFactor(config.cost_factor);
172  publish_potential_ = config.publish_potential;
173  orientation_filter_->setMode(config.orientation_mode);
174  orientation_filter_->setWindowSize(config.orientation_window_size);
175 }
176 
177 void GlobalPlanner::clearRobotCell(const tf::Stamped<tf::Pose>& global_pose, unsigned int mx, unsigned int my) {
178  if (!initialized_) {
179  ROS_ERROR(
180  "This planner has not been initialized yet, but it is being used, please call initialize() before use");
181  return;
182  }
183 
184  //set the associated costs in the cost map to be free
186 }
187 
188 bool GlobalPlanner::makePlanService(nav_msgs::GetPlan::Request& req, nav_msgs::GetPlan::Response& resp) {
189  makePlan(req.start, req.goal, resp.plan.poses);
190 
191  resp.plan.header.stamp = ros::Time::now();
192  resp.plan.header.frame_id = frame_id_;
193 
194  return true;
195 }
196 
197 void GlobalPlanner::mapToWorld(double mx, double my, double& wx, double& wy) {
200 }
201 
202 bool GlobalPlanner::worldToMap(double wx, double wy, double& mx, double& my) {
203  double origin_x = costmap_->getOriginX(), origin_y = costmap_->getOriginY();
204  double resolution = costmap_->getResolution();
205 
206  if (wx < origin_x || wy < origin_y)
207  return false;
208 
209  mx = (wx - origin_x) / resolution - convert_offset_;
210  my = (wy - origin_y) / resolution - convert_offset_;
211 
212  if (mx < costmap_->getSizeInCellsX() && my < costmap_->getSizeInCellsY())
213  return true;
214 
215  return false;
216 }
217 
218 bool GlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal,
219  std::vector<geometry_msgs::PoseStamped>& plan) {
220  return makePlan(start, goal, default_tolerance_, plan);
221 }
222 
223 bool GlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, const geometry_msgs::PoseStamped& goal,
224  double tolerance, std::vector<geometry_msgs::PoseStamped>& plan) {
225  boost::mutex::scoped_lock lock(mutex_);
226  if (!initialized_) {
227  ROS_ERROR(
228  "This planner has not been initialized yet, but it is being used, please call initialize() before use");
229  return false;
230  }
231 
232  //clear the plan, just in case
233  plan.clear();
234 
235  ros::NodeHandle n;
236  std::string global_frame = frame_id_;
237 
238  //until tf can handle transforming things that are way in the past... we'll require the goal to be in our global frame
239  if (tf::resolve(tf_prefix_, goal.header.frame_id) != tf::resolve(tf_prefix_, global_frame)) {
240  ROS_ERROR(
241  "The goal pose passed to this planner must be in the %s frame. It is instead in the %s frame.", tf::resolve(tf_prefix_, global_frame).c_str(), tf::resolve(tf_prefix_, goal.header.frame_id).c_str());
242  return false;
243  }
244 
245  if (tf::resolve(tf_prefix_, start.header.frame_id) != tf::resolve(tf_prefix_, global_frame)) {
246  ROS_ERROR(
247  "The start pose passed to this planner must be in the %s frame. It is instead in the %s frame.", tf::resolve(tf_prefix_, global_frame).c_str(), tf::resolve(tf_prefix_, start.header.frame_id).c_str());
248  return false;
249  }
250 
251  double wx = start.pose.position.x;
252  double wy = start.pose.position.y;
253 
254  unsigned int start_x_i, start_y_i, goal_x_i, goal_y_i;
255  double start_x, start_y, goal_x, goal_y;
256 
257  if (!costmap_->worldToMap(wx, wy, start_x_i, start_y_i)) {
258  ROS_WARN(
259  "The robot's start position is off the global costmap. Planning will always fail, are you sure the robot has been properly localized?");
260  return false;
261  }
263  start_x = start_x_i;
264  start_y = start_y_i;
265  }else{
266  worldToMap(wx, wy, start_x, start_y);
267  }
268 
269  wx = goal.pose.position.x;
270  wy = goal.pose.position.y;
271 
272  if (!costmap_->worldToMap(wx, wy, goal_x_i, goal_y_i)) {
273  ROS_WARN_THROTTLE(1.0,
274  "The goal sent to the global planner is off the global costmap. Planning will always fail to this goal.");
275  return false;
276  }
278  goal_x = goal_x_i;
279  goal_y = goal_y_i;
280  }else{
281  worldToMap(wx, wy, goal_x, goal_y);
282  }
283 
284  //clear the starting cell within the costmap because we know it can't be an obstacle
285  tf::Stamped<tf::Pose> start_pose;
286  tf::poseStampedMsgToTF(start, start_pose);
287  clearRobotCell(start_pose, start_x_i, start_y_i);
288 
289  int nx = costmap_->getSizeInCellsX(), ny = costmap_->getSizeInCellsY();
290 
291  //make sure to resize the underlying array that Navfn uses
292  p_calc_->setSize(nx, ny);
293  planner_->setSize(nx, ny);
294  path_maker_->setSize(nx, ny);
295  potential_array_ = new float[nx * ny];
296 
298 
299  bool found_legal = planner_->calculatePotentials(costmap_->getCharMap(), start_x, start_y, goal_x, goal_y,
300  nx * ny * 2, potential_array_);
301 
303  planner_->clearEndpoint(costmap_->getCharMap(), potential_array_, goal_x_i, goal_y_i, 2);
306 
307  if (found_legal) {
308  //extract the plan
309  if (getPlanFromPotential(start_x, start_y, goal_x, goal_y, goal, plan)) {
310  //make sure the goal we push on has the same timestamp as the rest of the plan
311  geometry_msgs::PoseStamped goal_copy = goal;
312  goal_copy.header.stamp = ros::Time::now();
313  plan.push_back(goal_copy);
314  } else {
315  ROS_ERROR("Failed to get a plan from potential when a legal potential was found. This shouldn't happen.");
316  }
317  }else{
318  ROS_ERROR("Failed to get a plan.");
319  }
320 
321  // add orientations if needed
322  orientation_filter_->processPath(start, plan);
323 
324  //publish the plan for visualization purposes
325  publishPlan(plan);
326  delete potential_array_;
327  return !plan.empty();
328 }
329 
330 void GlobalPlanner::publishPlan(const std::vector<geometry_msgs::PoseStamped>& path) {
331  if (!initialized_) {
332  ROS_ERROR(
333  "This planner has not been initialized yet, but it is being used, please call initialize() before use");
334  return;
335  }
336 
337  //create a message for the plan
338  nav_msgs::Path gui_path;
339  gui_path.poses.resize(path.size());
340 
341  gui_path.header.frame_id = frame_id_;
342  gui_path.header.stamp = ros::Time::now();
343 
344  // Extract the plan in world co-ordinates, we assume the path is all in the same frame
345  for (unsigned int i = 0; i < path.size(); i++) {
346  gui_path.poses[i] = path[i];
347  }
348 
349  plan_pub_.publish(gui_path);
350 }
351 
352 bool GlobalPlanner::getPlanFromPotential(double start_x, double start_y, double goal_x, double goal_y,
353  const geometry_msgs::PoseStamped& goal,
354  std::vector<geometry_msgs::PoseStamped>& plan) {
355  if (!initialized_) {
356  ROS_ERROR(
357  "This planner has not been initialized yet, but it is being used, please call initialize() before use");
358  return false;
359  }
360 
361  std::string global_frame = frame_id_;
362 
363  //clear the plan, just in case
364  plan.clear();
365 
366  std::vector<std::pair<float, float> > path;
367 
368  if (!path_maker_->getPath(potential_array_, start_x, start_y, goal_x, goal_y, path)) {
369  ROS_ERROR("NO PATH!");
370  return false;
371  }
372 
373  ros::Time plan_time = ros::Time::now();
374  for (int i = path.size() -1; i>=0; i--) {
375  std::pair<float, float> point = path[i];
376  //convert the plan to world coordinates
377  double world_x, world_y;
378  mapToWorld(point.first, point.second, world_x, world_y);
379 
380  geometry_msgs::PoseStamped pose;
381  pose.header.stamp = plan_time;
382  pose.header.frame_id = global_frame;
383  pose.pose.position.x = world_x;
384  pose.pose.position.y = world_y;
385  pose.pose.position.z = 0.0;
386  pose.pose.orientation.x = 0.0;
387  pose.pose.orientation.y = 0.0;
388  pose.pose.orientation.z = 0.0;
389  pose.pose.orientation.w = 1.0;
390  plan.push_back(pose);
391  }
393  plan.push_back(goal);
394  }
395  return !plan.empty();
396 }
397 
398 void GlobalPlanner::publishPotential(float* potential)
399 {
400  int nx = costmap_->getSizeInCellsX(), ny = costmap_->getSizeInCellsY();
401  double resolution = costmap_->getResolution();
402  nav_msgs::OccupancyGrid grid;
403  // Publish Whole Grid
404  grid.header.frame_id = frame_id_;
405  grid.header.stamp = ros::Time::now();
406  grid.info.resolution = resolution;
407 
408  grid.info.width = nx;
409  grid.info.height = ny;
410 
411  double wx, wy;
412  costmap_->mapToWorld(0, 0, wx, wy);
413  grid.info.origin.position.x = wx - resolution / 2;
414  grid.info.origin.position.y = wy - resolution / 2;
415  grid.info.origin.position.z = 0.0;
416  grid.info.origin.orientation.w = 1.0;
417 
418  grid.data.resize(nx * ny);
419 
420  float max = 0.0;
421  for (unsigned int i = 0; i < grid.data.size(); i++) {
422  float potential = potential_array_[i];
423  if (potential < POT_HIGH) {
424  if (potential > max) {
425  max = potential;
426  }
427  }
428  }
429 
430  for (unsigned int i = 0; i < grid.data.size(); i++) {
431  if (potential_array_[i] >= POT_HIGH) {
432  grid.data[i] = -1;
433  } else
434  grid.data[i] = potential_array_[i] * publish_scale_ / max;
435  }
436  potential_pub_.publish(grid);
437 }
438 
439 } //end namespace global_planner
440 
void setCost(unsigned int mx, unsigned int my, unsigned char cost)
void clearRobotCell(const tf::Stamped< tf::Pose > &global_pose, unsigned int mx, unsigned int my)
void publishPotential(float *potential)
~GlobalPlanner()
Default deconstructor for the PlannerCore object.
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.
void mapToWorld(double mx, double my, double &wx, double &wy)
void publish(const boost::shared_ptr< M > &message) const
std::string getPrefixParam(ros::NodeHandle &nh)
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
virtual void processPath(const geometry_msgs::PoseStamped &start, std::vector< geometry_msgs::PoseStamped > &path)
void setLethalCost(unsigned char lethal_cost)
Definition: expander.h:64
void outlineMap(unsigned char *costarr, int nx, int ny, unsigned char value)
virtual void setSize(int nx, int ny)
Sets or resets the size of the map.
Definition: expander.h:59
void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)
Initialization function for the PlannerCore object.
std::string getGlobalFrameID()
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
double getOriginX() const
costmap_2d::Costmap2D * costmap_
Store a copy of the current costmap in costmap. Called by makePlan.
Definition: planner_core.h:172
virtual bool getPath(float *potential, double start_x, double start_y, double end_x, double end_y, std::vector< std::pair< float, float > > &path)=0
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
void reconfigureCB(global_planner::GlobalPlannerConfig &config, uint32_t level)
static const unsigned char FREE_SPACE
#define ROS_WARN(...)
PotentialCalculator * p_calc_
Definition: planner_core.h:188
unsigned char * getCharMap() const
#define POT_HIGH
Definition: planner_core.h:40
void clearEndpoint(unsigned char *costs, float *potential, int gx, int gy, int s)
Definition: expander.h:77
std::string resolve(const std::string &prefix, const std::string &frame_name)
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path)
Publish a path for visualization purposes.
bool getPlanFromPotential(double start_x, double start_y, double end_x, double end_y, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan)
Compute a plan to a goal after the potential for a start point has already been computed (Note: You s...
#define ROS_WARN_THROTTLE(period,...)
void setPreciseStart(bool precise)
Definition: dijkstra.h:75
void setLethalCost(unsigned char lethal_cost)
Definition: traceback.h:57
bool param(const std::string &param_name, T &param_val, const T &default_val) const
bool worldToMap(double wx, double wy, double &mx, double &my)
double getOriginY() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
unsigned int getSizeInCellsY() const
GlobalPlanner()
Default constructor for the PlannerCore object.
virtual void setSize(int xs, int ys)
Definition: traceback.h:50
OrientationFilter * orientation_filter_
Definition: planner_core.h:191
void setHasUnknown(bool unknown)
Definition: expander.h:73
unsigned int getSizeInCellsX() const
bool makePlanService(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &resp)
ros::ServiceServer make_plan_srv_
Definition: planner_core.h:186
static const unsigned char LETHAL_OBSTACLE
static Time now()
virtual bool calculatePotentials(unsigned char *costs, double start_x, double start_y, double end_x, double end_y, int cycles, float *potential)=0
void setMode(OrientationMode new_mode)
static void poseStampedMsgToTF(const geometry_msgs::PoseStamped &msg, Stamped< Pose > &bt)
void setNeutralCost(unsigned char neutral_cost)
Definition: expander.h:67
double getResolution() const
Costmap2D * getCostmap()
#define ROS_ERROR(...)
void setWindowSize(size_t window_size)
void setFactor(float factor)
Definition: expander.h:70
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
dynamic_reconfigure::Server< global_planner::GlobalPlannerConfig > * dsrv_
Definition: planner_core.h:205
virtual void setSize(int nx, int ny)
Sets or resets the size of the map.


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