sbpl_lattice_planner.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2008, 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 the Willow Garage 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: Mike Phillips
36 *********************************************************************/
37 
40 #include <nav_msgs/Path.h>
41 #include <sbpl_lattice_planner/SBPLLatticePlannerStats.h>
42 
45 #include <tf/transform_datatypes.h>
46 
47 using namespace std;
48 using namespace ros;
49 
50 
52 
53 namespace geometry_msgs {
54  bool operator== (const Point &p1, const Point &p2)
55  {
56  return p1.x == p2.x && p1.y == p2.y && p1.z == p2.z;
57  }
58 }
59 
60 namespace sbpl_lattice_planner{
61 
62 class LatticeSCQ : public StateChangeQuery{
63  public:
64  LatticeSCQ(EnvironmentNAVXYTHETALAT* env, std::vector<nav2dcell_t> const & changedcellsV)
65  : env_(env), changedcellsV_(changedcellsV) {
66  }
67 
68  // lazy init, because we do not always end up calling this method
69  virtual std::vector<int> const * getPredecessors() const{
70  if(predsOfChangedCells_.empty() && !changedcellsV_.empty())
71  env_->GetPredsofChangedEdges(&changedcellsV_, &predsOfChangedCells_);
72  return &predsOfChangedCells_;
73  }
74 
75  // lazy init, because we do not always end up calling this method
76  virtual std::vector<int> const * getSuccessors() const{
77  if(succsOfChangedCells_.empty() && !changedcellsV_.empty())
78  env_->GetSuccsofChangedEdges(&changedcellsV_, &succsOfChangedCells_);
79  return &succsOfChangedCells_;
80  }
81 
82  EnvironmentNAVXYTHETALAT * env_;
83  std::vector<nav2dcell_t> const & changedcellsV_;
84  mutable std::vector<int> predsOfChangedCells_;
85  mutable std::vector<int> succsOfChangedCells_;
86 };
87 
88 SBPLLatticePlanner::SBPLLatticePlanner()
89  : initialized_(false), costmap_ros_(NULL){
90 }
91 
93  : initialized_(false), costmap_ros_(NULL){
94  initialize(name, costmap_ros);
95 }
96 
97 
98 void SBPLLatticePlanner::initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros){
99  if(!initialized_){
100  ros::NodeHandle private_nh("~/"+name);
101 
102  ROS_INFO("Name is %s", name.c_str());
103 
104  private_nh.param("planner_type", planner_type_, string("ARAPlanner"));
105  private_nh.param("allocated_time", allocated_time_, 10.0);
106  private_nh.param("initial_epsilon",initial_epsilon_,3.0);
107  private_nh.param("environment_type", environment_type_, string("XYThetaLattice"));
108  private_nh.param("forward_search", forward_search_, bool(false));
109  private_nh.param("primitive_filename",primitive_filename_,string(""));
110  private_nh.param("force_scratch_limit",force_scratch_limit_,500);
111 
112  double nominalvel_mpersecs, timetoturn45degsinplace_secs;
113  private_nh.param("nominalvel_mpersecs", nominalvel_mpersecs, 0.4);
114  private_nh.param("timetoturn45degsinplace_secs", timetoturn45degsinplace_secs, 0.6);
115 
116  int lethal_obstacle;
117  private_nh.param("lethal_obstacle",lethal_obstacle,20);
118  lethal_obstacle_ = (unsigned char) lethal_obstacle;
121  ROS_DEBUG("SBPL: lethal: %uz, inscribed inflated: %uz, multiplier: %uz",lethal_obstacle,inscribed_inflated_obstacle_,sbpl_cost_multiplier_);
122 
123  private_nh.param("publish_footprint_path", publish_footprint_path_, bool(true));
124  private_nh.param<int>("visualizer_skip_poses", visualizer_skip_poses_, 5);
125 
126  private_nh.param("allow_unknown", allow_unknown_, bool(true));
127 
128  name_ = name;
129  costmap_ros_ = costmap_ros;
130 
132 
133  if ("XYThetaLattice" == environment_type_){
134  ROS_DEBUG("Using a 3D costmap for theta lattice\n");
135  env_ = new EnvironmentNAVXYTHETALAT();
136  }
137  else{
138  ROS_ERROR("XYThetaLattice is currently the only supported environment!\n");
139  exit(1);
140  }
141 
143 
144  if (circumscribed_cost_ == 0) {
145  // Unfortunately, the inflation_radius is not taken into account by
146  // inflation_layer->computeCost(). If inflation_radius is smaller than
147  // the circumscribed radius, SBPL will ignore some obstacles, but we
148  // cannot detect this problem. If the cost_scaling_factor is too large,
149  // SBPL won't run into obstacles, but will always perform an expensive
150  // footprint check, no matter how far the nearest obstacle is.
151  ROS_WARN("The costmap value at the robot's circumscribed radius (%f m) is 0.", costmap_ros_->getLayeredCostmap()->getCircumscribedRadius());
152  ROS_WARN("SBPL performance will suffer.");
153  ROS_WARN("Please decrease the costmap's cost_scaling_factor.");
154  }
155  if(!env_->SetEnvParameter("cost_inscribed_thresh",costMapCostToSBPLCost(costmap_2d::INSCRIBED_INFLATED_OBSTACLE))){
156  ROS_ERROR("Failed to set cost_inscribed_thresh parameter");
157  exit(1);
158  }
159  if(!env_->SetEnvParameter("cost_possibly_circumscribed_thresh", circumscribed_cost_)){
160  ROS_ERROR("Failed to set cost_possibly_circumscribed_thresh parameter");
161  exit(1);
162  }
163  int obst_cost_thresh = costMapCostToSBPLCost(costmap_2d::LETHAL_OBSTACLE);
164  vector<sbpl_2Dpt_t> perimeterptsV;
165  perimeterptsV.reserve(footprint_.size());
166  for (size_t ii(0); ii < footprint_.size(); ++ii) {
167  sbpl_2Dpt_t pt;
168  pt.x = footprint_[ii].x;
169  pt.y = footprint_[ii].y;
170  perimeterptsV.push_back(pt);
171  }
172 
173  bool ret;
174  try{
175  ret = env_->InitializeEnv(costmap_ros_->getCostmap()->getSizeInCellsX(), // width
176  costmap_ros_->getCostmap()->getSizeInCellsY(), // height
177  0, // mapdata
178  0, 0, 0, // start (x, y, theta, t)
179  0, 0, 0, // goal (x, y, theta)
180  0, 0, 0, //goal tolerance
181  perimeterptsV, costmap_ros_->getCostmap()->getResolution(), nominalvel_mpersecs,
182  timetoturn45degsinplace_secs, obst_cost_thresh,
183  primitive_filename_.c_str());
186  }
187  catch(SBPL_Exception *e){
188  ROS_ERROR("SBPL encountered a fatal exception: %s", e->what());
189  ret = false;
190  }
191  if(!ret){
192  ROS_ERROR("SBPL initialization failed!");
193  exit(1);
194  }
195  for (ssize_t ix(0); ix < costmap_ros_->getCostmap()->getSizeInCellsX(); ++ix)
196  for (ssize_t iy(0); iy < costmap_ros_->getCostmap()->getSizeInCellsY(); ++iy)
197  env_->UpdateCost(ix, iy, costMapCostToSBPLCost(costmap_ros_->getCostmap()->getCost(ix,iy)));
198 
199  if ("ARAPlanner" == planner_type_){
200  ROS_INFO("Planning with ARA*");
201  planner_ = new ARAPlanner(env_, forward_search_);
202  }
203  else if ("ADPlanner" == planner_type_){
204  ROS_INFO("Planning with AD*");
205  planner_ = new ADPlanner(env_, forward_search_);
206  }
207  else{
208  ROS_ERROR("ARAPlanner and ADPlanner are currently the only supported planners!\n");
209  exit(1);
210  }
211 
212  ROS_INFO("[sbpl_lattice_planner] Initialized successfully");
213  plan_pub_ = private_nh.advertise<nav_msgs::Path>("plan", 1);
214  stats_publisher_ = private_nh.advertise<sbpl_lattice_planner::SBPLLatticePlannerStats>("sbpl_lattice_planner_stats", 1);
215  sbpl_plan_footprint_pub_ = private_nh.advertise<visualization_msgs::Marker>("footprint_markers", 1);
216 
217  initialized_ = true;
218  }
219 }
220 
221 //Taken from Sachin's sbpl_cart_planner
222 //This rescales the costmap according to a rosparam which sets the obstacle cost
223 unsigned char SBPLLatticePlanner::costMapCostToSBPLCost(unsigned char newcost){
225  return lethal_obstacle_;
226  else if(newcost == costmap_2d::INSCRIBED_INFLATED_OBSTACLE)
228  else if(newcost == 0 || newcost == costmap_2d::NO_INFORMATION)
229  return 0;
230  else {
231  unsigned char sbpl_cost = newcost / sbpl_cost_multiplier_;
232  if (sbpl_cost == 0)
233  sbpl_cost = 1;
234  return sbpl_cost;
235  }
236 }
237 
238 void SBPLLatticePlanner::publishStats(int solution_cost, int solution_size,
239  const geometry_msgs::PoseStamped& start,
240  const geometry_msgs::PoseStamped& goal){
241  // Fill up statistics and publish
242  sbpl_lattice_planner::SBPLLatticePlannerStats stats;
243  stats.initial_epsilon = initial_epsilon_;
244  stats.plan_to_first_solution = false;
245  stats.final_number_of_expands = planner_->get_n_expands();
246  stats.allocated_time = allocated_time_;
247 
248  stats.time_to_first_solution = planner_->get_initial_eps_planning_time();
249  stats.actual_time = planner_->get_final_eps_planning_time();
250  stats.number_of_expands_initial_solution = planner_->get_n_expands_init_solution();
251  stats.final_epsilon = planner_->get_final_epsilon();
252 
253  stats.solution_cost = solution_cost;
254  stats.path_size = solution_size;
255  stats.start = start;
256  stats.goal = goal;
257  stats_publisher_.publish(stats);
258 }
259 
261  unsigned char result = 0;
262 
263  if (!costmap_ros_) {
264  ROS_ERROR("Costmap is not initialized");
265  return 0;
266  }
267 
268  // check if the costmap has an inflation layer
269  for(std::vector<boost::shared_ptr<costmap_2d::Layer> >::const_iterator layer = costmap_ros_->getLayeredCostmap()->getPlugins()->begin();
270  layer != costmap_ros_->getLayeredCostmap()->getPlugins()->end();
271  ++layer) {
272  boost::shared_ptr<costmap_2d::InflationLayer> inflation_layer = boost::dynamic_pointer_cast<costmap_2d::InflationLayer>(*layer);
273  if (!inflation_layer) continue;
274 
276  }
277  return result;
278 }
279 
280 bool SBPLLatticePlanner::makePlan(const geometry_msgs::PoseStamped& start,
281  const geometry_msgs::PoseStamped& goal,
282  std::vector<geometry_msgs::PoseStamped>& plan){
283  if(!initialized_){
284  ROS_ERROR("Global planner is not initialized");
285  return false;
286  }
287 
288  bool do_init = false;
291  ROS_INFO("Costmap dimensions have changed from (%d x %d) to (%d x %d), reinitializing sbpl_lattice_planner.",
294  do_init = true;
295  }
296  else if (footprint_ != costmap_ros_->getRobotFootprint()) {
297  ROS_INFO("Robot footprint has changed, reinitializing sbpl_lattice_planner.");
298  do_init = true;
299  }
301  ROS_INFO("Cost at circumscribed radius has changed, reinitializing sbpl_lattice_planner.");
302  do_init = true;
303  }
304 
305  if (do_init) {
306  initialized_ = false;
307  delete planner_;
308  planner_ = NULL;
309  delete env_;
310  env_ = NULL;
312  }
313 
314  plan.clear();
315 
316  ROS_INFO("[sbpl_lattice_planner] getting start point (%g,%g) goal point (%g,%g)",
317  start.pose.position.x, start.pose.position.y,goal.pose.position.x, goal.pose.position.y);
318  double theta_start = 2 * atan2(start.pose.orientation.z, start.pose.orientation.w);
319  double theta_goal = 2 * atan2(goal.pose.orientation.z, goal.pose.orientation.w);
320 
321  try{
322  int ret = env_->SetStart(start.pose.position.x - costmap_ros_->getCostmap()->getOriginX(), start.pose.position.y - costmap_ros_->getCostmap()->getOriginY(), theta_start);
323  if(ret < 0 || planner_->set_start(ret) == 0){
324  ROS_ERROR("ERROR: failed to set start state\n");
325  return false;
326  }
327  }
328  catch(SBPL_Exception *e){
329  ROS_ERROR("SBPL encountered a fatal exception while setting the start state");
330  return false;
331  }
332 
333  try{
334  int ret = env_->SetGoal(goal.pose.position.x - costmap_ros_->getCostmap()->getOriginX(), goal.pose.position.y - costmap_ros_->getCostmap()->getOriginY(), theta_goal);
335  if(ret < 0 || planner_->set_goal(ret) == 0){
336  ROS_ERROR("ERROR: failed to set goal state\n");
337  return false;
338  }
339  }
340  catch(SBPL_Exception *e){
341  ROS_ERROR("SBPL encountered a fatal exception while setting the goal state");
342  return false;
343  }
344 
345  int offOnCount = 0;
346  int onOffCount = 0;
347  int allCount = 0;
348  vector<nav2dcell_t> changedcellsV;
349 
350  for(unsigned int ix = 0; ix < costmap_ros_->getCostmap()->getSizeInCellsX(); ix++) {
351  for(unsigned int iy = 0; iy < costmap_ros_->getCostmap()->getSizeInCellsY(); iy++) {
352 
353  unsigned char oldCost = env_->GetMapCost(ix,iy);
354  unsigned char newCost = costMapCostToSBPLCost(costmap_ros_->getCostmap()->getCost(ix,iy));
355 
356  if(oldCost == newCost) continue;
357 
358  allCount++;
359 
360  //first case - off cell goes on
361 
364  offOnCount++;
365  }
366 
369  onOffCount++;
370  }
371  env_->UpdateCost(ix, iy, costMapCostToSBPLCost(costmap_ros_->getCostmap()->getCost(ix,iy)));
372 
373  nav2dcell_t nav2dcell;
374  nav2dcell.x = ix;
375  nav2dcell.y = iy;
376  changedcellsV.push_back(nav2dcell);
377  }
378  }
379 
380  try{
381  if(!changedcellsV.empty()){
382  StateChangeQuery* scq = new LatticeSCQ(env_, changedcellsV);
383  planner_->costs_changed(*scq);
384  delete scq;
385  }
386 
387  if(allCount > force_scratch_limit_)
388  planner_->force_planning_from_scratch();
389  }
390  catch(SBPL_Exception *e){
391  ROS_ERROR("SBPL failed to update the costmap");
392  return false;
393  }
394 
395  //setting planner parameters
396  ROS_DEBUG("allocated:%f, init eps:%f\n",allocated_time_,initial_epsilon_);
397  planner_->set_initialsolution_eps(initial_epsilon_);
398  planner_->set_search_mode(false);
399 
400  ROS_DEBUG("[sbpl_lattice_planner] run planner");
401  vector<int> solution_stateIDs;
402  int solution_cost;
403  try{
404  int ret = planner_->replan(allocated_time_, &solution_stateIDs, &solution_cost);
405  if(ret)
406  ROS_DEBUG("Solution is found\n");
407  else{
408  ROS_INFO("Solution not found\n");
409  publishStats(solution_cost, 0, start, goal);
410  return false;
411  }
412  }
413  catch(SBPL_Exception *e){
414  ROS_ERROR("SBPL encountered a fatal exception while planning");
415  return false;
416  }
417 
418  ROS_DEBUG("size of solution=%d", (int)solution_stateIDs.size());
419 
420  vector<EnvNAVXYTHETALAT3Dpt_t> sbpl_path;
421  try{
422  env_->ConvertStateIDPathintoXYThetaPath(&solution_stateIDs, &sbpl_path);
423  }
424  catch(SBPL_Exception *e){
425  ROS_ERROR("SBPL encountered a fatal exception while reconstructing the path");
426  return false;
427  }
428  // if the plan has zero points, add a single point to make move_base happy
429  if( sbpl_path.size() == 0 ) {
430  EnvNAVXYTHETALAT3Dpt_t s(
431  start.pose.position.x - costmap_ros_->getCostmap()->getOriginX(),
432  start.pose.position.y - costmap_ros_->getCostmap()->getOriginY(),
433  theta_start);
434  sbpl_path.push_back(s);
435  }
436 
437  ROS_DEBUG("Plan has %d points.\n", (int)sbpl_path.size());
438  ros::Time plan_time = ros::Time::now();
439 
441  {
442  visualization_msgs::Marker sbpl_plan_footprint;
443  getFootprintList(sbpl_path, costmap_ros_->getGlobalFrameID(), sbpl_plan_footprint);
444  sbpl_plan_footprint_pub_.publish(sbpl_plan_footprint);
445  }
446 
447  //create a message for the plan
448  nav_msgs::Path gui_path;
449  gui_path.poses.resize(sbpl_path.size());
450  gui_path.header.frame_id = costmap_ros_->getGlobalFrameID();
451  gui_path.header.stamp = plan_time;
452  for(unsigned int i=0; i<sbpl_path.size(); i++){
453  geometry_msgs::PoseStamped pose;
454  pose.header.stamp = plan_time;
455  pose.header.frame_id = costmap_ros_->getGlobalFrameID();
456 
457  pose.pose.position.x = sbpl_path[i].x + costmap_ros_->getCostmap()->getOriginX();
458  pose.pose.position.y = sbpl_path[i].y + costmap_ros_->getCostmap()->getOriginY();
459  pose.pose.position.z = start.pose.position.z;
460 
461  tf2::Quaternion temp;
462  temp.setRPY(0,0,sbpl_path[i].theta);
463  pose.pose.orientation.x = temp.getX();
464  pose.pose.orientation.y = temp.getY();
465  pose.pose.orientation.z = temp.getZ();
466  pose.pose.orientation.w = temp.getW();
467 
468  plan.push_back(pose);
469 
470  gui_path.poses[i] = plan[i];
471  }
472  plan_pub_.publish(gui_path);
473  publishStats(solution_cost, sbpl_path.size(), start, goal);
474 
475  return true;
476 }
477 
478 void SBPLLatticePlanner::getFootprintList(const std::vector<EnvNAVXYTHETALAT3Dpt_t>& sbpl_path,
479  const std::string& path_frame_id, visualization_msgs::Marker& ma)
480 {
481  ma.header.frame_id = path_frame_id;
482  ma.header.stamp = ros::Time();
483  ma.ns = "sbpl_robot_footprint";
484  ma.id = 0;
485  ma.type = visualization_msgs::Marker::LINE_LIST;
486  ma.action = visualization_msgs::Marker::ADD;
487  ma.scale.x = 0.05;
488  ma.color.a = 1.0;
489  ma.color.r = 0.0;
490  ma.color.g = 0.0;
491  ma.color.b = 1.0;
492  ma.pose.orientation.w = 1.0;
493 
494  for (unsigned int i = 0; i < sbpl_path.size(); i = i + visualizer_skip_poses_)
495  {
496  std::vector<geometry_msgs::Point> transformed_rfp;
497  geometry_msgs::Pose robot_pose;
498  robot_pose.position.x = sbpl_path[i].x + costmap_ros_->getCostmap()->getOriginX();
499  ;
500  robot_pose.position.y = sbpl_path[i].y + costmap_ros_->getCostmap()->getOriginY();
501  ;
502  robot_pose.position.z = 0.0;
503  tf::Quaternion quat;
504  quat.setRPY(0.0, 0.0, sbpl_path[i].theta);
505  tf::quaternionTFToMsg(quat, robot_pose.orientation);
506  transformFootprintToEdges(robot_pose, footprint_, transformed_rfp);
507 
508  for (auto & point : transformed_rfp)
509  ma.points.push_back(point);
510  }
511 }
512 
513 void SBPLLatticePlanner::transformFootprintToEdges(const geometry_msgs::Pose& robot_pose,
514  const std::vector<geometry_msgs::Point>& footprint,
515  std::vector<geometry_msgs::Point>& out_footprint)
516 {
517  out_footprint.resize(2 * footprint.size());
518  double yaw = tf::getYaw(robot_pose.orientation);
519  for (unsigned int i = 0; i < footprint.size(); i++)
520  {
521  out_footprint[2 * i].x = robot_pose.position.x + cos(yaw) * footprint[i].x - sin(yaw) * footprint[i].y;
522  out_footprint[2 * i].y = robot_pose.position.y + sin(yaw) * footprint[i].x + cos(yaw) * footprint[i].y;
523  if (i == 0)
524  {
525  out_footprint.back().x = out_footprint[i].x;
526  out_footprint.back().y = out_footprint[i].y;
527  }
528  else
529  {
530  out_footprint[2 * i - 1].x = out_footprint[2 * i].x;
531  out_footprint[2 * i - 1].y = out_footprint[2 * i].y;
532  }
533  }
534 }
535 };
sbpl_lattice_planner::SBPLLatticePlanner::publishStats
void publishStats(int solution_cost, int solution_size, const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal)
Definition: sbpl_lattice_planner.cpp:238
sbpl_lattice_planner::SBPLLatticePlanner::primitive_filename_
std::string primitive_filename_
Definition: sbpl_lattice_planner.h:92
sbpl_lattice_planner::SBPLLatticePlanner::getFootprintList
void getFootprintList(const std::vector< EnvNAVXYTHETALAT3Dpt_t > &sbpl_path, const std::string &path_frame_id, visualization_msgs::Marker &ma)
Definition: sbpl_lattice_planner.cpp:478
sbpl_lattice_planner::SBPLLatticePlanner::transformFootprintToEdges
static void transformFootprintToEdges(const geometry_msgs::Pose &robot_pose, const std::vector< geometry_msgs::Point > &footprint, std::vector< geometry_msgs::Point > &out_footprint)
Definition: sbpl_lattice_planner.cpp:513
boost::shared_ptr
sbpl_lattice_planner::LatticeSCQ::getSuccessors
virtual const std::vector< int > * getSuccessors() const
Definition: sbpl_lattice_planner.cpp:76
tf::Quaternion::setRPY
void setRPY(const tfScalar &roll, const tfScalar &pitch, const tfScalar &yaw)
sbpl_lattice_planner::SBPLLatticePlanner::allow_unknown_
bool allow_unknown_
Definition: sbpl_lattice_planner.h:103
tf2::Quaternion::getW
const TF2SIMD_FORCE_INLINE tf2Scalar & getW() const
s
XmlRpcServer s
ros
costmap_2d::INSCRIBED_INFLATED_OBSTACLE
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
sbpl_lattice_planner::SBPLLatticePlanner::costmap_ros_
costmap_2d::Costmap2DROS * costmap_ros_
Definition: sbpl_lattice_planner.h:106
tf2::Quaternion::setRPY
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
costmap_2d::NO_INFORMATION
static const unsigned char NO_INFORMATION
sbpl_lattice_planner::SBPLLatticePlanner::force_scratch_limit_
int force_scratch_limit_
Definition: sbpl_lattice_planner.h:93
sbpl_lattice_planner::SBPLLatticePlanner::current_env_width_
unsigned int current_env_width_
Definition: sbpl_lattice_planner.h:108
geometry_msgs
sbpl_lattice_planner::LatticeSCQ::LatticeSCQ
LatticeSCQ(EnvironmentNAVXYTHETALAT *env, std::vector< nav2dcell_t > const &changedcellsV)
Definition: sbpl_lattice_planner.cpp:64
sbpl_lattice_planner::LatticeSCQ
Definition: sbpl_lattice_planner.cpp:62
sbpl_lattice_planner::SBPLLatticePlanner
Definition: sbpl_lattice_planner.h:25
costmap_2d::Costmap2D::getOriginX
double getOriginX() const
sbpl_lattice_planner::SBPLLatticePlanner::visualizer_skip_poses_
int visualizer_skip_poses_
Definition: sbpl_lattice_planner.h:101
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
sbpl_lattice_planner::LatticeSCQ::changedcellsV_
const std::vector< nav2dcell_t > & changedcellsV_
Definition: sbpl_lattice_planner.cpp:83
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
geometry_msgs::operator==
bool operator==(const Point &p1, const Point &p2)
Definition: sbpl_lattice_planner.cpp:54
tf::getYaw
static double getYaw(const geometry_msgs::Quaternion &msg_q)
costmap_2d::Costmap2DROS::getRobotFootprint
const std::vector< geometry_msgs::Point > & getRobotFootprint() const noexcept
sbpl_lattice_planner::SBPLLatticePlanner::environment_type_
std::string environment_type_
Definition: sbpl_lattice_planner.h:88
inflation_layer.h
Point
tf::Vector3 Point
sbpl_lattice_planner::SBPLLatticePlanner::initialized_
bool initialized_
Definition: sbpl_lattice_planner.h:78
sbpl_lattice_planner::SBPLLatticePlanner::env_
EnvironmentNAVXYTHETALAT * env_
Definition: sbpl_lattice_planner.h:81
sbpl_lattice_planner::SBPLLatticePlanner::sbpl_cost_multiplier_
unsigned char sbpl_cost_multiplier_
Definition: sbpl_lattice_planner.h:98
sbpl_lattice_planner::SBPLLatticePlanner::sbpl_plan_footprint_pub_
ros::Publisher sbpl_plan_footprint_pub_
Definition: sbpl_lattice_planner.h:113
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
costmap_2d::LayeredCostmap::getPlugins
std::vector< boost::shared_ptr< Layer > > * getPlugins()
ROS_DEBUG
#define ROS_DEBUG(...)
sbpl_lattice_planner::SBPLLatticePlanner::name_
std::string name_
Definition: sbpl_lattice_planner.h:105
sbpl_lattice_planner::LatticeSCQ::succsOfChangedCells_
std::vector< int > succsOfChangedCells_
Definition: sbpl_lattice_planner.cpp:85
Quaternion.h
sbpl_lattice_planner.h
costmap_2d::Costmap2DROS::getLayeredCostmap
LayeredCostmap * getLayeredCostmap() const
sbpl_lattice_planner::SBPLLatticePlanner::publish_footprint_path_
bool publish_footprint_path_
Definition: sbpl_lattice_planner.h:100
sbpl_lattice_planner::SBPLLatticePlanner::computeCircumscribedCost
unsigned char computeCircumscribedCost()
Definition: sbpl_lattice_planner.cpp:260
sbpl_lattice_planner::SBPLLatticePlanner::plan_pub_
ros::Publisher plan_pub_
Definition: sbpl_lattice_planner.h:111
sbpl_lattice_planner::LatticeSCQ::env_
EnvironmentNAVXYTHETALAT * env_
Definition: sbpl_lattice_planner.cpp:82
costmap_2d::Costmap2D::getSizeInCellsY
unsigned int getSizeInCellsY() const
ROS_WARN
#define ROS_WARN(...)
costmap_2d::LETHAL_OBSTACLE
static const unsigned char LETHAL_OBSTACLE
sbpl_lattice_planner::LatticeSCQ::getPredecessors
virtual const std::vector< int > * getPredecessors() const
Definition: sbpl_lattice_planner.cpp:69
sbpl_lattice_planner::SBPLLatticePlanner::initial_epsilon_
double initial_epsilon_
Definition: sbpl_lattice_planner.h:86
sbpl_lattice_planner::SBPLLatticePlanner::stats_publisher_
ros::Publisher stats_publisher_
Definition: sbpl_lattice_planner.h:112
sbpl_lattice_planner::SBPLLatticePlanner::lethal_obstacle_
unsigned char lethal_obstacle_
Definition: sbpl_lattice_planner.h:95
sbpl_lattice_planner
Definition: sbpl_lattice_planner.h:23
start
ROSCPP_DECL void start()
costmap_2d::Costmap2D::getOriginY
double getOriginY() const
transform_datatypes.h
sbpl_lattice_planner::LatticeSCQ::predsOfChangedCells_
std::vector< int > predsOfChangedCells_
Definition: sbpl_lattice_planner.cpp:84
ros::Time
sbpl_lattice_planner::SBPLLatticePlanner::planner_type_
std::string planner_type_
Definition: sbpl_lattice_planner.h:83
sbpl_lattice_planner::SBPLLatticePlanner::circumscribed_cost_
unsigned char circumscribed_cost_
Definition: sbpl_lattice_planner.h:97
sbpl_lattice_planner::SBPLLatticePlanner::planner_
SBPLPlanner * planner_
Definition: sbpl_lattice_planner.h:80
std
sbpl_lattice_planner::SBPLLatticePlanner::inscribed_inflated_obstacle_
unsigned char inscribed_inflated_obstacle_
Definition: sbpl_lattice_planner.h:96
tf::quaternionTFToMsg
static void quaternionTFToMsg(const Quaternion &bt, geometry_msgs::Quaternion &msg)
ROS_ERROR
#define ROS_ERROR(...)
class_list_macros.hpp
sbpl_lattice_planner::SBPLLatticePlanner::allocated_time_
double allocated_time_
Definition: sbpl_lattice_planner.h:85
sbpl_lattice_planner::SBPLLatticePlanner::costMapCostToSBPLCost
unsigned char costMapCostToSBPLCost(unsigned char newcost)
Definition: sbpl_lattice_planner.cpp:223
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
tf2::Quaternion
costmap_2d::Costmap2D::getResolution
double getResolution() const
sbpl_lattice_planner::SBPLLatticePlanner::footprint_
std::vector< geometry_msgs::Point > footprint_
Definition: sbpl_lattice_planner.h:107
costmap_2d::Costmap2DROS::getCostmap
Costmap2D * getCostmap() const
costmap_2d::Costmap2D::getSizeInCellsX
unsigned int getSizeInCellsX() const
costmap_2d::Costmap2DROS::getGlobalFrameID
const std::string & getGlobalFrameID() const noexcept
nav_core::BaseGlobalPlanner
ROS_INFO
#define ROS_INFO(...)
sbpl_lattice_planner::SBPLLatticePlanner::current_env_height_
unsigned int current_env_height_
Definition: sbpl_lattice_planner.h:109
sbpl_lattice_planner::SBPLLatticePlanner::initialize
virtual void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)
Initialization function for the SBPLLatticePlanner object.
Definition: sbpl_lattice_planner.cpp:98
costmap_2d::Costmap2D::getCost
unsigned char getCost(unsigned int mx, unsigned int my) const
sbpl_lattice_planner::SBPLLatticePlanner::SBPLLatticePlanner
SBPLLatticePlanner()
Default constructor for the NavFnROS object.
Definition: sbpl_lattice_planner.cpp:88
tf::Quaternion
costmap_2d::Costmap2DROS
sbpl_lattice_planner::SBPLLatticePlanner::forward_search_
bool forward_search_
Definition: sbpl_lattice_planner.h:91
ros::NodeHandle
sbpl_lattice_planner::SBPLLatticePlanner::makePlan
virtual 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: sbpl_lattice_planner.cpp:280
ros::Time::now
static Time now()
costmap_2d::LayeredCostmap::getCircumscribedRadius
double getCircumscribedRadius()


sbpl_lattice_planner
Author(s): Michael Phillips
autogenerated on Fri Aug 26 2022 02:17:53