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