trajectory_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: Eitan Marder-Eppstein
36 *********************************************************************/
37 
39 #include <costmap_2d/footprint.h>
40 #include <string>
41 #include <sstream>
42 #include <math.h>
43 #include <angles/angles.h>
44 
45 
46 
47 #include <boost/algorithm/string.hpp>
48 
49 #include <ros/console.h>
50 
51 //for computing path distance
52 #include <queue>
54 #include <tf2/utils.h>
55 
56 using namespace std;
57 using namespace costmap_2d;
58 
59 namespace base_local_planner{
60 
61  void TrajectoryPlanner::reconfigure(BaseLocalPlannerConfig &cfg)
62  {
63  BaseLocalPlannerConfig config(cfg);
64 
65  boost::mutex::scoped_lock l(configuration_mutex_);
66 
67  acc_lim_x_ = config.acc_lim_x;
68  acc_lim_y_ = config.acc_lim_y;
69  acc_lim_theta_ = config.acc_lim_theta;
70 
71  max_vel_x_ = config.max_vel_x;
72  min_vel_x_ = config.min_vel_x;
73 
74  max_vel_th_ = config.max_vel_theta;
75  min_vel_th_ = config.min_vel_theta;
76  min_in_place_vel_th_ = config.min_in_place_vel_theta;
77 
78  sim_time_ = config.sim_time;
79  sim_granularity_ = config.sim_granularity;
80  angular_sim_granularity_ = config.angular_sim_granularity;
81 
82  path_distance_bias_ = config.path_distance_bias;
83  goal_distance_bias_ = config.goal_distance_bias;
84  occdist_scale_ = config.occdist_scale;
85 
86  if (meter_scoring_) {
87  //if we use meter scoring, then we want to multiply the biases by the resolution of the costmap
88  double resolution = costmap_.getResolution();
89  goal_distance_bias_ *= resolution;
90  path_distance_bias_ *= resolution;
91  }
92 
93  oscillation_reset_dist_ = config.oscillation_reset_dist;
94  escape_reset_dist_ = config.escape_reset_dist;
95  escape_reset_theta_ = config.escape_reset_theta;
96 
97  vx_samples_ = config.vx_samples;
98  vtheta_samples_ = config.vtheta_samples;
99 
100  if (vx_samples_ <= 0) {
101  config.vx_samples = 1;
102  vx_samples_ = config.vx_samples;
103  ROS_WARN("You've specified that you don't want any samples in the x dimension. We'll at least assume that you want to sample one value... so we're going to set vx_samples to 1 instead");
104  }
105  if(vtheta_samples_ <= 0) {
106  config.vtheta_samples = 1;
107  vtheta_samples_ = config.vtheta_samples;
108  ROS_WARN("You've specified that you don't want any samples in the theta dimension. We'll at least assume that you want to sample one value... so we're going to set vtheta_samples to 1 instead");
109  }
110 
111  heading_lookahead_ = config.heading_lookahead;
112 
113  holonomic_robot_ = config.holonomic_robot;
114 
115  backup_vel_ = config.escape_vel;
116 
117  dwa_ = config.dwa;
118 
119  heading_scoring_ = config.heading_scoring;
120  heading_scoring_timestep_ = config.heading_scoring_timestep;
121 
122  simple_attractor_ = config.simple_attractor;
123 
124  //y-vels
125  string y_string = config.y_vels;
126  vector<string> y_strs;
127  boost::split(y_strs, y_string, boost::is_any_of(", "), boost::token_compress_on);
128 
129  vector<double>y_vels;
130  for(vector<string>::iterator it=y_strs.begin(); it != y_strs.end(); ++it) {
131  istringstream iss(*it);
132  double temp;
133  iss >> temp;
134  y_vels.push_back(temp);
135  //ROS_INFO("Adding y_vel: %e", temp);
136  }
137 
138  y_vels_ = y_vels;
139 
140  }
141 
142  TrajectoryPlanner::TrajectoryPlanner(WorldModel& world_model,
143  const Costmap2D& costmap,
144  std::vector<geometry_msgs::Point> footprint_spec,
145  double acc_lim_x, double acc_lim_y, double acc_lim_theta,
146  double sim_time, double sim_granularity,
147  int vx_samples, int vtheta_samples,
148  double path_distance_bias, double goal_distance_bias, double occdist_scale,
149  double heading_lookahead, double oscillation_reset_dist,
150  double escape_reset_dist, double escape_reset_theta,
151  bool holonomic_robot,
152  double max_vel_x, double min_vel_x,
153  double max_vel_th, double min_vel_th, double min_in_place_vel_th,
154  double backup_vel,
155  bool dwa, bool heading_scoring, double heading_scoring_timestep, bool meter_scoring, bool simple_attractor,
156  vector<double> y_vels, double stop_time_buffer, double sim_period, double angular_sim_granularity)
157  : path_map_(costmap.getSizeInCellsX(), costmap.getSizeInCellsY()),
158  goal_map_(costmap.getSizeInCellsX(), costmap.getSizeInCellsY()),
159  costmap_(costmap),
160  world_model_(world_model), footprint_spec_(footprint_spec),
161  sim_time_(sim_time), sim_granularity_(sim_granularity), angular_sim_granularity_(angular_sim_granularity),
162  vx_samples_(vx_samples), vtheta_samples_(vtheta_samples),
163  path_distance_bias_(path_distance_bias), goal_distance_bias_(goal_distance_bias), occdist_scale_(occdist_scale),
164  acc_lim_x_(acc_lim_x), acc_lim_y_(acc_lim_y), acc_lim_theta_(acc_lim_theta),
165  prev_x_(0), prev_y_(0), escape_x_(0), escape_y_(0), escape_theta_(0), heading_lookahead_(heading_lookahead),
166  oscillation_reset_dist_(oscillation_reset_dist), escape_reset_dist_(escape_reset_dist),
167  escape_reset_theta_(escape_reset_theta), holonomic_robot_(holonomic_robot),
168  max_vel_x_(max_vel_x), min_vel_x_(min_vel_x),
169  max_vel_th_(max_vel_th), min_vel_th_(min_vel_th), min_in_place_vel_th_(min_in_place_vel_th),
170  backup_vel_(backup_vel),
171  dwa_(dwa), heading_scoring_(heading_scoring), heading_scoring_timestep_(heading_scoring_timestep),
172  simple_attractor_(simple_attractor), y_vels_(y_vels), stop_time_buffer_(stop_time_buffer), sim_period_(sim_period)
173  {
174  //the robot is not stuck to begin with
175  stuck_left = false;
176  stuck_right = false;
177  stuck_left_strafe = false;
178  stuck_right_strafe = false;
179  rotating_left = false;
180  rotating_right = false;
181  strafe_left = false;
182  strafe_right = false;
183 
184  escaping_ = false;
186 
187 
189  }
190 
192 
193  bool TrajectoryPlanner::getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost) {
194  MapCell cell = path_map_(cx, cy);
195  MapCell goal_cell = goal_map_(cx, cy);
196  if (cell.within_robot) {
197  return false;
198  }
199  occ_cost = costmap_.getCost(cx, cy);
200  if (cell.target_dist == path_map_.obstacleCosts() ||
203  return false;
204  }
205  path_cost = cell.target_dist;
206  goal_cost = goal_cell.target_dist;
207  total_cost = path_distance_bias_ * path_cost + goal_distance_bias_ * goal_cost + occdist_scale_ * occ_cost;
208  return true;
209  }
210 
215  double x, double y, double theta,
216  double vx, double vy, double vtheta,
217  double vx_samp, double vy_samp, double vtheta_samp,
218  double acc_x, double acc_y, double acc_theta,
219  double impossible_cost,
220  Trajectory& traj) {
221 
222  // make sure the configuration doesn't change mid run
223  boost::mutex::scoped_lock l(configuration_mutex_);
224 
225  double x_i = x;
226  double y_i = y;
227  double theta_i = theta;
228 
229  double vx_i, vy_i, vtheta_i;
230 
231  vx_i = vx;
232  vy_i = vy;
233  vtheta_i = vtheta;
234 
235  //compute the magnitude of the velocities
236  double vmag = hypot(vx_samp, vy_samp);
237 
238  //compute the number of steps we must take along this trajectory to be "safe"
239  int num_steps;
240  if(!heading_scoring_) {
241  num_steps = int(max((vmag * sim_time_) / sim_granularity_, fabs(vtheta_samp) / angular_sim_granularity_) + 0.5);
242  } else {
243  num_steps = int(sim_time_ / sim_granularity_ + 0.5);
244  }
245 
246  //we at least want to take one step... even if we won't move, we want to score our current position
247  if(num_steps == 0) {
248  num_steps = 1;
249  }
250 
251  double dt = sim_time_ / num_steps;
252  double time = 0.0;
253 
254  //create a potential trajectory
255  traj.resetPoints();
256  traj.xv_ = vx_samp;
257  traj.yv_ = vy_samp;
258  traj.thetav_ = vtheta_samp;
259  traj.cost_ = -1.0;
260 
261  //initialize the costs for the trajectory
262  double path_dist = 0.0;
263  double goal_dist = 0.0;
264  double occ_cost = 0.0;
265  double heading_diff = 0.0;
266 
267  for(int i = 0; i < num_steps; ++i){
268  //get map coordinates of a point
269  unsigned int cell_x, cell_y;
270 
271  //we don't want a path that goes off the know map
272  if(!costmap_.worldToMap(x_i, y_i, cell_x, cell_y)){
273  traj.cost_ = -1.0;
274  return;
275  }
276 
277  //check the point on the trajectory for legality
278  double footprint_cost = footprintCost(x_i, y_i, theta_i);
279 
280  //if the footprint hits an obstacle this trajectory is invalid
281  if(footprint_cost < 0){
282  traj.cost_ = -1.0;
283  return;
284  //TODO: Really look at getMaxSpeedToStopInTime... dues to discretization errors and high acceleration limits,
285  //it can actually cause the robot to hit obstacles. There may be something to be done to fix, but I'll have to
286  //come back to it when I have time. Right now, pulling it out as it'll just make the robot a bit more conservative,
287  //but safe.
288  /*
289  double max_vel_x, max_vel_y, max_vel_th;
290  //we want to compute the max allowable speeds to be able to stop
291  //to be safe... we'll make sure we can stop some time before we actually hit
292  getMaxSpeedToStopInTime(time - stop_time_buffer_ - dt, max_vel_x, max_vel_y, max_vel_th);
293 
294  //check if we can stop in time
295  if(fabs(vx_samp) < max_vel_x && fabs(vy_samp) < max_vel_y && fabs(vtheta_samp) < max_vel_th){
296  ROS_ERROR("v: (%.2f, %.2f, %.2f), m: (%.2f, %.2f, %.2f) t:%.2f, st: %.2f, dt: %.2f", vx_samp, vy_samp, vtheta_samp, max_vel_x, max_vel_y, max_vel_th, time, stop_time_buffer_, dt);
297  //if we can stop... we'll just break out of the loop here.. no point in checking future points
298  break;
299  }
300  else{
301  traj.cost_ = -1.0;
302  return;
303  }
304  */
305  }
306 
307  occ_cost = std::max(std::max(occ_cost, footprint_cost), double(costmap_.getCost(cell_x, cell_y)));
308 
309  //do we want to follow blindly
310  if (simple_attractor_) {
311  goal_dist = (x_i - global_plan_[global_plan_.size() -1].pose.position.x) *
312  (x_i - global_plan_[global_plan_.size() -1].pose.position.x) +
313  (y_i - global_plan_[global_plan_.size() -1].pose.position.y) *
314  (y_i - global_plan_[global_plan_.size() -1].pose.position.y);
315  } else {
316 
317  bool update_path_and_goal_distances = true;
318 
319  // with heading scoring, we take into account heading diff, and also only score
320  // path and goal distance for one point of the trajectory
321  if (heading_scoring_) {
322  if (time >= heading_scoring_timestep_ && time < heading_scoring_timestep_ + dt) {
323  heading_diff = headingDiff(cell_x, cell_y, x_i, y_i, theta_i);
324  } else {
325  update_path_and_goal_distances = false;
326  }
327  }
328 
329  if (update_path_and_goal_distances) {
330  //update path and goal distances
331  path_dist = path_map_(cell_x, cell_y).target_dist;
332  goal_dist = goal_map_(cell_x, cell_y).target_dist;
333 
334  //if a point on this trajectory has no clear path to goal it is invalid
335  if(impossible_cost <= goal_dist || impossible_cost <= path_dist){
336 // ROS_DEBUG("No path to goal with goal distance = %f, path_distance = %f and max cost = %f",
337 // goal_dist, path_dist, impossible_cost);
338  traj.cost_ = -2.0;
339  return;
340  }
341  }
342  }
343 
344 
345  //the point is legal... add it to the trajectory
346  traj.addPoint(x_i, y_i, theta_i);
347 
348  //calculate velocities
349  vx_i = computeNewVelocity(vx_samp, vx_i, acc_x, dt);
350  vy_i = computeNewVelocity(vy_samp, vy_i, acc_y, dt);
351  vtheta_i = computeNewVelocity(vtheta_samp, vtheta_i, acc_theta, dt);
352 
353  //calculate positions
354  x_i = computeNewXPosition(x_i, vx_i, vy_i, theta_i, dt);
355  y_i = computeNewYPosition(y_i, vx_i, vy_i, theta_i, dt);
356  theta_i = computeNewThetaPosition(theta_i, vtheta_i, dt);
357 
358  //increment time
359  time += dt;
360  } // end for i < numsteps
361 
362  //ROS_INFO("OccCost: %f, vx: %.2f, vy: %.2f, vtheta: %.2f", occ_cost, vx_samp, vy_samp, vtheta_samp);
363  double cost = -1.0;
364  if (!heading_scoring_) {
365  cost = path_distance_bias_ * path_dist + goal_dist * goal_distance_bias_ + occdist_scale_ * occ_cost;
366  } else {
367  cost = occdist_scale_ * occ_cost + path_distance_bias_ * path_dist + 0.3 * heading_diff + goal_dist * goal_distance_bias_;
368  }
369  traj.cost_ = cost;
370  }
371 
372  double TrajectoryPlanner::headingDiff(int cell_x, int cell_y, double x, double y, double heading){
373  unsigned int goal_cell_x, goal_cell_y;
374 
375  // find a clear line of sight from the robot's cell to a farthest point on the path
376  for (int i = global_plan_.size() - 1; i >=0; --i) {
377  if (costmap_.worldToMap(global_plan_[i].pose.position.x, global_plan_[i].pose.position.y, goal_cell_x, goal_cell_y)) {
378  if (lineCost(cell_x, goal_cell_x, cell_y, goal_cell_y) >= 0) {
379  double gx, gy;
380  costmap_.mapToWorld(goal_cell_x, goal_cell_y, gx, gy);
381  return fabs(angles::shortest_angular_distance(heading, atan2(gy - y, gx - x)));
382  }
383  }
384  }
385  return DBL_MAX;
386  }
387 
388  //calculate the cost of a ray-traced line
389  double TrajectoryPlanner::lineCost(int x0, int x1,
390  int y0, int y1){
391  //Bresenham Ray-Tracing
392  int deltax = abs(x1 - x0); // The difference between the x's
393  int deltay = abs(y1 - y0); // The difference between the y's
394  int x = x0; // Start x off at the first pixel
395  int y = y0; // Start y off at the first pixel
396 
397  int xinc1, xinc2, yinc1, yinc2;
398  int den, num, numadd, numpixels;
399 
400  double line_cost = 0.0;
401  double point_cost = -1.0;
402 
403  if (x1 >= x0) // The x-values are increasing
404  {
405  xinc1 = 1;
406  xinc2 = 1;
407  }
408  else // The x-values are decreasing
409  {
410  xinc1 = -1;
411  xinc2 = -1;
412  }
413 
414  if (y1 >= y0) // The y-values are increasing
415  {
416  yinc1 = 1;
417  yinc2 = 1;
418  }
419  else // The y-values are decreasing
420  {
421  yinc1 = -1;
422  yinc2 = -1;
423  }
424 
425  if (deltax >= deltay) // There is at least one x-value for every y-value
426  {
427  xinc1 = 0; // Don't change the x when numerator >= denominator
428  yinc2 = 0; // Don't change the y for every iteration
429  den = deltax;
430  num = deltax / 2;
431  numadd = deltay;
432  numpixels = deltax; // There are more x-values than y-values
433  } else { // There is at least one y-value for every x-value
434  xinc2 = 0; // Don't change the x for every iteration
435  yinc1 = 0; // Don't change the y when numerator >= denominator
436  den = deltay;
437  num = deltay / 2;
438  numadd = deltax;
439  numpixels = deltay; // There are more y-values than x-values
440  }
441 
442  for (int curpixel = 0; curpixel <= numpixels; curpixel++) {
443  point_cost = pointCost(x, y); //Score the current point
444 
445  if (point_cost < 0) {
446  return -1;
447  }
448 
449  if (line_cost < point_cost) {
450  line_cost = point_cost;
451  }
452 
453  num += numadd; // Increase the numerator by the top of the fraction
454  if (num >= den) { // Check if numerator >= denominator
455  num -= den; // Calculate the new numerator value
456  x += xinc1; // Change the x as appropriate
457  y += yinc1; // Change the y as appropriate
458  }
459  x += xinc2; // Change the x as appropriate
460  y += yinc2; // Change the y as appropriate
461  }
462 
463  return line_cost;
464  }
465 
466  double TrajectoryPlanner::pointCost(int x, int y){
467  unsigned char cost = costmap_.getCost(x, y);
468  //if the cell is in an obstacle the path is invalid
469  if(cost == LETHAL_OBSTACLE || cost == INSCRIBED_INFLATED_OBSTACLE || cost == NO_INFORMATION){
470  return -1;
471  }
472 
473  return cost;
474  }
475 
476  void TrajectoryPlanner::updatePlan(const vector<geometry_msgs::PoseStamped>& new_plan, bool compute_dists){
477  global_plan_.resize(new_plan.size());
478  for(unsigned int i = 0; i < new_plan.size(); ++i){
479  global_plan_[i] = new_plan[i];
480  }
481 
482  if( global_plan_.size() > 0 ){
483  geometry_msgs::PoseStamped& final_goal_pose = global_plan_[ global_plan_.size() - 1 ];
484  final_goal_x_ = final_goal_pose.pose.position.x;
485  final_goal_y_ = final_goal_pose.pose.position.y;
487  } else {
489  }
490 
491  if (compute_dists) {
492  //reset the map for new operations
495 
496  //make sure that we update our path based on the global plan and compute costs
499  ROS_DEBUG("Path/Goal distance computed");
500  }
501  }
502 
503  bool TrajectoryPlanner::checkTrajectory(double x, double y, double theta, double vx, double vy,
504  double vtheta, double vx_samp, double vy_samp, double vtheta_samp){
505  Trajectory t;
506 
507  double cost = scoreTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp);
508 
509  //if the trajectory is a legal one... the check passes
510  if(cost >= 0) {
511  return true;
512  }
513  ROS_WARN("Invalid Trajectory %f, %f, %f, cost: %f", vx_samp, vy_samp, vtheta_samp, cost);
514 
515  //otherwise the check fails
516  return false;
517  }
518 
519  double TrajectoryPlanner::scoreTrajectory(double x, double y, double theta, double vx, double vy,
520  double vtheta, double vx_samp, double vy_samp, double vtheta_samp) {
521  Trajectory t;
522  double impossible_cost = path_map_.obstacleCosts();
523  generateTrajectory(x, y, theta,
524  vx, vy, vtheta,
525  vx_samp, vy_samp, vtheta_samp,
527  impossible_cost, t);
528 
529  // return the cost.
530  return double( t.cost_ );
531  }
532 
533  /*
534  * create the trajectories we wish to score
535  */
536  Trajectory TrajectoryPlanner::createTrajectories(double x, double y, double theta,
537  double vx, double vy, double vtheta,
538  double acc_x, double acc_y, double acc_theta) {
539  //compute feasible velocity limits in robot space
540  double max_vel_x = max_vel_x_, max_vel_theta;
541  double min_vel_x, min_vel_theta;
542 
544  double final_goal_dist = hypot( final_goal_x_ - x, final_goal_y_ - y );
545  max_vel_x = min( max_vel_x, final_goal_dist / sim_time_ );
546  }
547 
548  //should we use the dynamic window approach?
549  if (dwa_) {
550  max_vel_x = max(min(max_vel_x, vx + acc_x * sim_period_), min_vel_x_);
551  min_vel_x = max(min_vel_x_, vx - acc_x * sim_period_);
552 
553  max_vel_theta = min(max_vel_th_, vtheta + acc_theta * sim_period_);
554  min_vel_theta = max(min_vel_th_, vtheta - acc_theta * sim_period_);
555  } else {
556  max_vel_x = max(min(max_vel_x, vx + acc_x * sim_time_), min_vel_x_);
557  min_vel_x = max(min_vel_x_, vx - acc_x * sim_time_);
558 
559  max_vel_theta = min(max_vel_th_, vtheta + acc_theta * sim_time_);
560  min_vel_theta = max(min_vel_th_, vtheta - acc_theta * sim_time_);
561  }
562 
563 
564  //we want to sample the velocity space regularly
565  double dvx = (max_vel_x - min_vel_x) / (vx_samples_ - 1);
566  double dvtheta = (max_vel_theta - min_vel_theta) / (vtheta_samples_ - 1);
567 
568  double vx_samp = min_vel_x;
569  double vtheta_samp = min_vel_theta;
570  double vy_samp = 0.0;
571 
572  //keep track of the best trajectory seen so far
573  Trajectory* best_traj = &traj_one;
574  best_traj->cost_ = -1.0;
575 
576  Trajectory* comp_traj = &traj_two;
577  comp_traj->cost_ = -1.0;
578 
579  Trajectory* swap = NULL;
580 
581  //any cell with a cost greater than the size of the map is impossible
582  double impossible_cost = path_map_.obstacleCosts();
583 
584  //if we're performing an escape we won't allow moving forward
585  if (!escaping_) {
586  //loop through all x velocities
587  for(int i = 0; i < vx_samples_; ++i) {
588  vtheta_samp = 0;
589  //first sample the straight trajectory
590  generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp,
591  acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
592 
593  //if the new trajectory is better... let's take it
594  if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){
595  swap = best_traj;
596  best_traj = comp_traj;
597  comp_traj = swap;
598  }
599 
600  vtheta_samp = min_vel_theta;
601  //next sample all theta trajectories
602  for(int j = 0; j < vtheta_samples_ - 1; ++j){
603  generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp,
604  acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
605 
606  //if the new trajectory is better... let's take it
607  if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){
608  swap = best_traj;
609  best_traj = comp_traj;
610  comp_traj = swap;
611  }
612  vtheta_samp += dvtheta;
613  }
614  vx_samp += dvx;
615  }
616 
617  //only explore y velocities with holonomic robots
618  if (holonomic_robot_) {
619  //explore trajectories that move forward but also strafe slightly
620  vx_samp = 0.1;
621  vy_samp = 0.1;
622  vtheta_samp = 0.0;
623  generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp,
624  acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
625 
626  //if the new trajectory is better... let's take it
627  if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){
628  swap = best_traj;
629  best_traj = comp_traj;
630  comp_traj = swap;
631  }
632 
633  vx_samp = 0.1;
634  vy_samp = -0.1;
635  vtheta_samp = 0.0;
636  generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp,
637  acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
638 
639  //if the new trajectory is better... let's take it
640  if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){
641  swap = best_traj;
642  best_traj = comp_traj;
643  comp_traj = swap;
644  }
645  }
646  } // end if not escaping
647 
648  //next we want to generate trajectories for rotating in place
649  vtheta_samp = min_vel_theta;
650  vx_samp = 0.0;
651  vy_samp = 0.0;
652 
653  //let's try to rotate toward open space
654  double heading_dist = DBL_MAX;
655 
656  for(int i = 0; i < vtheta_samples_; ++i) {
657  //enforce a minimum rotational velocity because the base can't handle small in-place rotations
658  double vtheta_samp_limited = vtheta_samp > 0 ? max(vtheta_samp, min_in_place_vel_th_)
659  : min(vtheta_samp, -1.0 * min_in_place_vel_th_);
660 
661  generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp_limited,
662  acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
663 
664  //if the new trajectory is better... let's take it...
665  //note if we can legally rotate in place we prefer to do that rather than move with y velocity
666  if(comp_traj->cost_ >= 0
667  && (comp_traj->cost_ <= best_traj->cost_ || best_traj->cost_ < 0 || best_traj->yv_ != 0.0)
668  && (vtheta_samp > dvtheta || vtheta_samp < -1 * dvtheta)){
669  double x_r, y_r, th_r;
670  comp_traj->getEndpoint(x_r, y_r, th_r);
671  x_r += heading_lookahead_ * cos(th_r);
672  y_r += heading_lookahead_ * sin(th_r);
673  unsigned int cell_x, cell_y;
674 
675  //make sure that we'll be looking at a legal cell
676  if (costmap_.worldToMap(x_r, y_r, cell_x, cell_y)) {
677  double ahead_gdist = goal_map_(cell_x, cell_y).target_dist;
678  if (ahead_gdist < heading_dist) {
679  //if we haven't already tried rotating left since we've moved forward
680  if (vtheta_samp < 0 && !stuck_left) {
681  swap = best_traj;
682  best_traj = comp_traj;
683  comp_traj = swap;
684  heading_dist = ahead_gdist;
685  }
686  //if we haven't already tried rotating right since we've moved forward
687  else if(vtheta_samp > 0 && !stuck_right) {
688  swap = best_traj;
689  best_traj = comp_traj;
690  comp_traj = swap;
691  heading_dist = ahead_gdist;
692  }
693  }
694  }
695  }
696 
697  vtheta_samp += dvtheta;
698  }
699 
700  //do we have a legal trajectory
701  if (best_traj->cost_ >= 0) {
702  // avoid oscillations of in place rotation and in place strafing
703  if ( ! (best_traj->xv_ > 0)) {
704  if (best_traj->thetav_ < 0) {
705  if (rotating_right) {
706  stuck_right = true;
707  }
708  rotating_right = true;
709  } else if (best_traj->thetav_ > 0) {
710  if (rotating_left){
711  stuck_left = true;
712  }
713  rotating_left = true;
714  } else if(best_traj->yv_ > 0) {
715  if (strafe_right) {
716  stuck_right_strafe = true;
717  }
718  strafe_right = true;
719  } else if(best_traj->yv_ < 0){
720  if (strafe_left) {
721  stuck_left_strafe = true;
722  }
723  strafe_left = true;
724  }
725 
726  //set the position we must move a certain distance away from
727  prev_x_ = x;
728  prev_y_ = y;
729  }
730 
731  double dist = hypot(x - prev_x_, y - prev_y_);
732  if (dist > oscillation_reset_dist_) {
733  rotating_left = false;
734  rotating_right = false;
735  strafe_left = false;
736  strafe_right = false;
737  stuck_left = false;
738  stuck_right = false;
739  stuck_left_strafe = false;
740  stuck_right_strafe = false;
741  }
742 
743  dist = hypot(x - escape_x_, y - escape_y_);
744  if(dist > escape_reset_dist_ ||
746  escaping_ = false;
747  }
748 
749  return *best_traj;
750  }
751 
752  //only explore y velocities with holonomic robots
753  if (holonomic_robot_) {
754  //if we can't rotate in place or move forward... maybe we can move sideways and rotate
755  vtheta_samp = min_vel_theta;
756  vx_samp = 0.0;
757 
758  //loop through all y velocities
759  for(unsigned int i = 0; i < y_vels_.size(); ++i){
760  vtheta_samp = 0;
761  vy_samp = y_vels_[i];
762  //sample completely horizontal trajectories
763  generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp,
764  acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
765 
766  //if the new trajectory is better... let's take it
767  if(comp_traj->cost_ >= 0 && (comp_traj->cost_ <= best_traj->cost_ || best_traj->cost_ < 0)){
768  double x_r, y_r, th_r;
769  comp_traj->getEndpoint(x_r, y_r, th_r);
770  x_r += heading_lookahead_ * cos(th_r);
771  y_r += heading_lookahead_ * sin(th_r);
772  unsigned int cell_x, cell_y;
773 
774  //make sure that we'll be looking at a legal cell
775  if(costmap_.worldToMap(x_r, y_r, cell_x, cell_y)) {
776  double ahead_gdist = goal_map_(cell_x, cell_y).target_dist;
777  if (ahead_gdist < heading_dist) {
778  //if we haven't already tried strafing left since we've moved forward
779  if (vy_samp > 0 && !stuck_left_strafe) {
780  swap = best_traj;
781  best_traj = comp_traj;
782  comp_traj = swap;
783  heading_dist = ahead_gdist;
784  }
785  //if we haven't already tried rotating right since we've moved forward
786  else if(vy_samp < 0 && !stuck_right_strafe) {
787  swap = best_traj;
788  best_traj = comp_traj;
789  comp_traj = swap;
790  heading_dist = ahead_gdist;
791  }
792  }
793  }
794  }
795  }
796  }
797 
798  //do we have a legal trajectory
799  if (best_traj->cost_ >= 0) {
800  if (!(best_traj->xv_ > 0)) {
801  if (best_traj->thetav_ < 0) {
802  if (rotating_right){
803  stuck_right = true;
804  }
805  rotating_left = true;
806  } else if(best_traj->thetav_ > 0) {
807  if(rotating_left){
808  stuck_left = true;
809  }
810  rotating_right = true;
811  } else if(best_traj->yv_ > 0) {
812  if(strafe_right){
813  stuck_right_strafe = true;
814  }
815  strafe_left = true;
816  } else if(best_traj->yv_ < 0) {
817  if(strafe_left){
818  stuck_left_strafe = true;
819  }
820  strafe_right = true;
821  }
822 
823  //set the position we must move a certain distance away from
824  prev_x_ = x;
825  prev_y_ = y;
826 
827  }
828 
829  double dist = hypot(x - prev_x_, y - prev_y_);
830  if(dist > oscillation_reset_dist_) {
831  rotating_left = false;
832  rotating_right = false;
833  strafe_left = false;
834  strafe_right = false;
835  stuck_left = false;
836  stuck_right = false;
837  stuck_left_strafe = false;
838  stuck_right_strafe = false;
839  }
840 
841  dist = hypot(x - escape_x_, y - escape_y_);
843  escaping_ = false;
844  }
845 
846  return *best_traj;
847  }
848 
849  //and finally, if we can't do anything else, we want to generate trajectories that move backwards slowly
850  vtheta_samp = 0.0;
851  vx_samp = backup_vel_;
852  vy_samp = 0.0;
853  generateTrajectory(x, y, theta, vx, vy, vtheta, vx_samp, vy_samp, vtheta_samp,
854  acc_x, acc_y, acc_theta, impossible_cost, *comp_traj);
855 
856  //if the new trajectory is better... let's take it
857  /*
858  if(comp_traj->cost_ >= 0 && (comp_traj->cost_ < best_traj->cost_ || best_traj->cost_ < 0)){
859  swap = best_traj;
860  best_traj = comp_traj;
861  comp_traj = swap;
862  }
863  */
864 
865  //we'll allow moving backwards slowly even when the static map shows it as blocked
866  swap = best_traj;
867  best_traj = comp_traj;
868  comp_traj = swap;
869 
870  double dist = hypot(x - prev_x_, y - prev_y_);
871  if (dist > oscillation_reset_dist_) {
872  rotating_left = false;
873  rotating_right = false;
874  strafe_left = false;
875  strafe_right = false;
876  stuck_left = false;
877  stuck_right = false;
878  stuck_left_strafe = false;
879  stuck_right_strafe = false;
880  }
881 
882  //only enter escape mode when the planner has given a valid goal point
883  if (!escaping_ && best_traj->cost_ > -2.0) {
884  escape_x_ = x;
885  escape_y_ = y;
886  escape_theta_ = theta;
887  escaping_ = true;
888  }
889 
890  dist = hypot(x - escape_x_, y - escape_y_);
891 
892  if (dist > escape_reset_dist_ ||
894  escaping_ = false;
895  }
896 
897 
898  //if the trajectory failed because the footprint hits something, we're still going to back up
899  if(best_traj->cost_ == -1.0)
900  best_traj->cost_ = 1.0;
901 
902  return *best_traj;
903 
904  }
905 
906  //given the current state of the robot, find a good trajectory
907  Trajectory TrajectoryPlanner::findBestPath(const geometry_msgs::PoseStamped& global_pose,
908  geometry_msgs::PoseStamped& global_vel, geometry_msgs::PoseStamped& drive_velocities) {
909 
910  Eigen::Vector3f pos(global_pose.pose.position.x, global_pose.pose.position.y, tf2::getYaw(global_pose.pose.orientation));
911  Eigen::Vector3f vel(global_vel.pose.position.x, global_vel.pose.position.y, tf2::getYaw(global_vel.pose.orientation));
912 
913  //reset the map for new operations
916 
917  //temporarily remove obstacles that are within the footprint of the robot
918  std::vector<base_local_planner::Position2DInt> footprint_list =
920  pos,
922  costmap_,
923  true);
924 
925  //mark cells within the initial footprint of the robot
926  for (unsigned int i = 0; i < footprint_list.size(); ++i) {
927  path_map_(footprint_list[i].x, footprint_list[i].y).within_robot = true;
928  }
929 
930  //make sure that we update our path based on the global plan and compute costs
933  ROS_DEBUG("Path/Goal distance computed");
934 
935  //rollout trajectories and find the minimum cost one
936  Trajectory best = createTrajectories(pos[0], pos[1], pos[2],
937  vel[0], vel[1], vel[2],
939  ROS_DEBUG("Trajectories created");
940 
941  /*
942  //If we want to print a ppm file to draw goal dist
943  char buf[4096];
944  sprintf(buf, "base_local_planner.ppm");
945  FILE *fp = fopen(buf, "w");
946  if(fp){
947  fprintf(fp, "P3\n");
948  fprintf(fp, "%d %d\n", map_.size_x_, map_.size_y_);
949  fprintf(fp, "255\n");
950  for(int j = map_.size_y_ - 1; j >= 0; --j){
951  for(unsigned int i = 0; i < map_.size_x_; ++i){
952  int g_dist = 255 - int(map_(i, j).goal_dist);
953  int p_dist = 255 - int(map_(i, j).path_dist);
954  if(g_dist < 0)
955  g_dist = 0;
956  if(p_dist < 0)
957  p_dist = 0;
958  fprintf(fp, "%d 0 %d ", g_dist, 0);
959  }
960  fprintf(fp, "\n");
961  }
962  fclose(fp);
963  }
964  */
965 
966  if(best.cost_ < 0){
967  drive_velocities.pose.position.x = 0;
968  drive_velocities.pose.position.y = 0;
969  drive_velocities.pose.position.z = 0;
970  drive_velocities.pose.orientation.w = 1;
971  drive_velocities.pose.orientation.x = 0;
972  drive_velocities.pose.orientation.y = 0;
973  drive_velocities.pose.orientation.z = 0;
974  }
975  else{
976  drive_velocities.pose.position.x = best.xv_;
977  drive_velocities.pose.position.y = best.yv_;
978  drive_velocities.pose.position.z = 0;
979  tf2::Quaternion q;
980  q.setRPY(0, 0, best.thetav_);
981  tf2::convert(q, drive_velocities.pose.orientation);
982  }
983 
984  return best;
985  }
986 
987  //we need to take the footprint of the robot into account when we calculate cost to obstacles
988  double TrajectoryPlanner::footprintCost(double x_i, double y_i, double theta_i){
989  //check if the footprint is legal
991  }
992 
993 
994  void TrajectoryPlanner::getLocalGoal(double& x, double& y){
995  x = path_map_.goal_x_;
996  y = path_map_.goal_y_;
997  }
998 
999 };
1000 
1001 
base_local_planner::TrajectoryPlanner::checkTrajectory
bool checkTrajectory(double x, double y, double theta, double vx, double vy, double vtheta, double vx_samp, double vy_samp, double vtheta_samp)
Generate and score a single trajectory.
Definition: trajectory_planner.cpp:503
base_local_planner::TrajectoryPlanner::inscribed_radius_
double inscribed_radius_
Definition: trajectory_planner.h:351
base_local_planner::TrajectoryPlanner::occdist_scale_
double occdist_scale_
Scaling factors for the controller's cost function.
Definition: trajectory_planner.h:324
tf2::convert
void convert(const A &a, B &b)
angles::shortest_angular_distance
static double shortest_angular_distance(double from, double to)
base_local_planner::Trajectory::resetPoints
void resetPoints()
Clear the trajectory's points.
Definition: trajectory.cpp:97
min
int min(int a, int b)
base_local_planner::TrajectoryPlanner::~TrajectoryPlanner
~TrajectoryPlanner()
Destructs a trajectory controller.
Definition: trajectory_planner.cpp:191
base_local_planner::TrajectoryPlanner::min_in_place_vel_th_
double min_in_place_vel_th_
Velocity limits for the controller.
Definition: trajectory_planner.h:337
base_local_planner::Trajectory::xv_
double xv_
Definition: trajectory.h:92
base_local_planner::MapGrid::unreachableCellCosts
double unreachableCellCosts()
Definition: map_grid.h:176
base_local_planner::TrajectoryPlanner::computeNewVelocity
double computeNewVelocity(double vg, double vi, double a_max, double dt)
Compute velocity based on acceleration.
Definition: trajectory_planner.h:401
base_local_planner::TrajectoryPlanner::vtheta_samples_
int vtheta_samples_
The number of samples we'll take in the theta dimension of the control space.
Definition: trajectory_planner.h:322
base_local_planner::TrajectoryPlanner::createTrajectories
Trajectory createTrajectories(double x, double y, double theta, double vx, double vy, double vtheta, double acc_x, double acc_y, double acc_theta)
Create the trajectories we wish to explore, score them, and return the best option.
Definition: trajectory_planner.cpp:536
base_local_planner::WorldModel::footprintCost
virtual double footprintCost(const geometry_msgs::Point &position, const std::vector< geometry_msgs::Point > &footprint, double inscribed_radius, double circumscribed_radius)=0
Subclass will implement this method to check a footprint at a given position and orientation for lega...
base_local_planner::TrajectoryPlanner::traj_one
Trajectory traj_one
Definition: trajectory_planner.h:330
base_local_planner::TrajectoryPlanner::strafe_left
bool strafe_left
Booleans to keep track of strafe direction for the robot.
Definition: trajectory_planner.h:307
base_local_planner::TrajectoryPlanner::getCellCosts
bool getCellCosts(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost)
Compute the components and total cost for a map grid cell.
Definition: trajectory_planner.cpp:193
costmap_2d::Costmap2D::worldToMap
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
tf2::getYaw
double getYaw(const A &a)
base_local_planner::TrajectoryPlanner::path_distance_bias_
double path_distance_bias_
Definition: trajectory_planner.h:324
base_local_planner::TrajectoryPlanner::goal_map_
MapGrid goal_map_
The local map grid where we propagate goal distance.
Definition: trajectory_planner.h:295
utils.h
base_local_planner::TrajectoryPlanner::escape_reset_dist_
double escape_reset_dist_
Definition: trajectory_planner.h:334
base_local_planner::MapGrid::goal_x_
double goal_x_
Definition: map_grid.h:221
base_local_planner::TrajectoryPlanner::computeNewThetaPosition
double computeNewThetaPosition(double thetai, double vth, double dt)
Compute orientation based on velocity.
Definition: trajectory_planner.h:388
base_local_planner::TrajectoryPlanner::oscillation_reset_dist_
double oscillation_reset_dist_
The distance the robot must travel before it can explore rotational velocities that were unsuccessful...
Definition: trajectory_planner.h:333
base_local_planner::TrajectoryPlanner::escaping_
bool escaping_
Boolean to keep track of whether we're in escape mode.
Definition: trajectory_planner.h:309
costmap_2d::INSCRIBED_INFLATED_OBSTACLE
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
base_local_planner::TrajectoryPlanner::stuck_right_strafe
bool stuck_right_strafe
Booleans to keep the robot from oscillating during strafing.
Definition: trajectory_planner.h:306
base_local_planner::TrajectoryPlanner::pointCost
double pointCost(int x, int y)
Definition: trajectory_planner.cpp:466
tf2::Quaternion::setRPY
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
base_local_planner::TrajectoryPlanner::computeNewXPosition
double computeNewXPosition(double xi, double vx, double vy, double theta, double dt)
Compute x position based on velocity.
Definition: trajectory_planner.h:364
base_local_planner::TrajectoryPlanner::stuck_left
bool stuck_left
Definition: trajectory_planner.h:303
base_local_planner::TrajectoryPlanner::final_goal_y_
double final_goal_y_
The end position of the plan.
Definition: trajectory_planner.h:314
base_local_planner::TrajectoryPlanner::footprintCost
double footprintCost(double x_i, double y_i, double theta_i)
Checks the legality of the robot footprint at a position and orientation using the world model.
Definition: trajectory_planner.cpp:988
costmap_2d::Costmap2D
base_local_planner::TrajectoryPlanner::headingDiff
double headingDiff(int cell_x, int cell_y, double x, double y, double heading)
Definition: trajectory_planner.cpp:372
swap
void swap(Bag &a, Bag &b)
costmap_2d::calculateMinAndMaxDistances
void calculateMinAndMaxDistances(const std::vector< geometry_msgs::Point > &footprint, double &min_dist, double &max_dist)
costmap_2d::Costmap2D::mapToWorld
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
base_local_planner::TrajectoryPlanner::footprint_helper_
base_local_planner::FootprintHelper footprint_helper_
Definition: trajectory_planner.h:292
base_local_planner::TrajectoryPlanner::sim_period_
double sim_period_
The number of seconds to use to compute max/min vels for dwa.
Definition: trajectory_planner.h:349
base_local_planner::TrajectoryPlanner::goal_distance_bias_
double goal_distance_bias_
Definition: trajectory_planner.h:324
base_local_planner::TrajectoryPlanner::prev_y_
double prev_y_
Used to calculate the distance the robot has traveled before reseting oscillation booleans.
Definition: trajectory_planner.h:327
base_local_planner::TrajectoryPlanner::getLocalGoal
void getLocalGoal(double &x, double &y)
Accessor for the goal the robot is currently pursuing in world corrdinates.
Definition: trajectory_planner.cpp:994
base_local_planner::TrajectoryPlanner::costmap_
const costmap_2d::Costmap2D & costmap_
Provides access to cost map information.
Definition: trajectory_planner.h:296
base_local_planner::TrajectoryPlanner::computeNewYPosition
double computeNewYPosition(double yi, double vx, double vy, double theta, double dt)
Compute y position based on velocity.
Definition: trajectory_planner.h:377
base_local_planner::TrajectoryPlanner::escape_theta_
double escape_theta_
Used to calculate the distance the robot has traveled before reseting escape booleans.
Definition: trajectory_planner.h:328
base_local_planner::Trajectory::addPoint
void addPoint(double x, double y, double th)
Add a point to the end of a trajectory.
Definition: trajectory.cpp:91
console.h
base_local_planner::TrajectoryPlanner::final_goal_x_
double final_goal_x_
Definition: trajectory_planner.h:314
base_local_planner::TrajectoryPlanner::updatePlan
void updatePlan(const std::vector< geometry_msgs::PoseStamped > &new_plan, bool compute_dists=false)
Update the plan that the controller is following.
Definition: trajectory_planner.cpp:476
base_local_planner::TrajectoryPlanner::max_vel_th_
double max_vel_th_
Definition: trajectory_planner.h:337
base_local_planner::MapGrid::obstacleCosts
double obstacleCosts()
Definition: map_grid.h:168
base_local_planner::TrajectoryPlanner::path_map_
MapGrid path_map_
The local map grid where we propagate path distance.
Definition: trajectory_planner.h:294
base_local_planner::MapGrid::setLocalGoal
void setLocalGoal(const costmap_2d::Costmap2D &costmap, const std::vector< geometry_msgs::PoseStamped > &global_plan)
Update what cell is considered the next local goal.
Definition: map_grid.cpp:210
base_local_planner::TrajectoryPlanner::escape_y_
double escape_y_
Definition: trajectory_planner.h:328
base_local_planner::TrajectoryPlanner::angular_sim_granularity_
double angular_sim_granularity_
The distance between angular simulation points.
Definition: trajectory_planner.h:319
ROS_DEBUG
#define ROS_DEBUG(...)
base_local_planner::Trajectory::cost_
double cost_
The cost/score of the trajectory.
Definition: trajectory.h:94
base_local_planner::TrajectoryPlanner::acc_lim_theta_
double acc_lim_theta_
The acceleration limits of the robot.
Definition: trajectory_planner.h:325
base_local_planner::TrajectoryPlanner::heading_lookahead_
double heading_lookahead_
How far the robot should look ahead of itself when differentiating between different rotational veloc...
Definition: trajectory_planner.h:332
base_local_planner::MapGrid::resetPathDist
void resetPathDist()
reset path distance fields for all cells
Definition: map_grid.cpp:125
base_local_planner::TrajectoryPlanner::world_model_
WorldModel & world_model_
The world model that the controller uses for collision detection.
Definition: trajectory_planner.h:297
base_local_planner::Trajectory::yv_
double yv_
Definition: trajectory.h:92
ROS_WARN
#define ROS_WARN(...)
base_local_planner::TrajectoryPlanner::scoreTrajectory
double scoreTrajectory(double x, double y, double theta, double vx, double vy, double vtheta, double vx_samp, double vy_samp, double vtheta_samp)
Generate and score a single trajectory.
Definition: trajectory_planner.cpp:519
base_local_planner::TrajectoryPlanner::circumscribed_radius_
double circumscribed_radius_
Definition: trajectory_planner.h:351
base_local_planner::TrajectoryPlanner::sim_granularity_
double sim_granularity_
The distance between simulation points.
Definition: trajectory_planner.h:318
base_local_planner::TrajectoryPlanner::generateTrajectory
void generateTrajectory(double x, double y, double theta, double vx, double vy, double vtheta, double vx_samp, double vy_samp, double vtheta_samp, double acc_x, double acc_y, double acc_theta, double impossible_cost, Trajectory &traj)
Generate and score a single trajectory.
Definition: trajectory_planner.cpp:214
base_local_planner::WorldModel
An interface the trajectory controller uses to interact with the world regardless of the underlying w...
Definition: world_model.h:87
base_local_planner::MapCell::target_dist
double target_dist
Distance to planner's path.
Definition: map_cell.h:91
base_local_planner::TrajectoryPlanner::final_goal_position_valid_
bool final_goal_position_valid_
True if final_goal_x_ and final_goal_y_ have valid data. Only false if an empty path is sent.
Definition: trajectory_planner.h:315
DBL_MAX
#define DBL_MAX
Definition: trajectory_inc.h:40
trajectory_planner.h
base_local_planner::TrajectoryPlanner::vx_samples_
int vx_samples_
The number of samples we'll take in the x dimenstion of the control space.
Definition: trajectory_planner.h:321
base_local_planner::Trajectory::getEndpoint
void getEndpoint(double &x, double &y, double &th) const
Get the last point of the trajectory.
Definition: trajectory.cpp:103
base_local_planner::TrajectoryPlanner::holonomic_robot_
bool holonomic_robot_
Is the robot holonomic or not?
Definition: trajectory_planner.h:335
std
base_local_planner::TrajectoryPlanner::findBestPath
Trajectory findBestPath(const geometry_msgs::PoseStamped &global_pose, geometry_msgs::PoseStamped &global_vel, geometry_msgs::PoseStamped &drive_velocities)
Given the current position, orientation, and velocity of the robot, return a trajectory to follow.
Definition: trajectory_planner.cpp:907
base_local_planner::TrajectoryPlanner::min_vel_x_
double min_vel_x_
Definition: trajectory_planner.h:337
base_local_planner::TrajectoryPlanner::escape_x_
double escape_x_
Definition: trajectory_planner.h:328
base_local_planner::TrajectoryPlanner::heading_scoring_
bool heading_scoring_
Should we score based on the rollout approach or the heading approach.
Definition: trajectory_planner.h:342
base_local_planner::TrajectoryPlanner::dwa_
bool dwa_
Should we use the dynamic window approach?
Definition: trajectory_planner.h:341
base_local_planner::TrajectoryPlanner::max_vel_x_
double max_vel_x_
Definition: trajectory_planner.h:337
footprint.h
base_local_planner::Trajectory
Holds a trajectory generated by considering an x, y, and theta velocity.
Definition: trajectory.h:76
base_local_planner::TrajectoryPlanner::stuck_left_strafe
bool stuck_left_strafe
Definition: trajectory_planner.h:306
tf2::Quaternion
base_local_planner::MapGrid::goal_y_
double goal_y_
The goal distance was last computed from.
Definition: map_grid.h:221
base_local_planner::TrajectoryPlanner::traj_two
Trajectory traj_two
Used for scoring trajectories.
Definition: trajectory_planner.h:330
base_local_planner::TrajectoryPlanner::y_vels_
std::vector< double > y_vels_
Y velocities to explore.
Definition: trajectory_planner.h:346
base_local_planner::TrajectoryPlanner::simple_attractor_
bool simple_attractor_
Enables simple attraction to a goal point.
Definition: trajectory_planner.h:344
base_local_planner::TrajectoryPlanner::acc_lim_x_
double acc_lim_x_
Definition: trajectory_planner.h:325
base_local_planner::TrajectoryPlanner::escape_reset_theta_
double escape_reset_theta_
The distance the robot must travel before it can leave escape mode.
Definition: trajectory_planner.h:334
base_local_planner::TrajectoryPlanner::backup_vel_
double backup_vel_
The velocity to use while backing up.
Definition: trajectory_planner.h:339
base_local_planner::TrajectoryPlanner::min_vel_th_
double min_vel_th_
Definition: trajectory_planner.h:337
base_local_planner::FootprintHelper::getFootprintCells
std::vector< base_local_planner::Position2DInt > getFootprintCells(Eigen::Vector3f pos, std::vector< geometry_msgs::Point > footprint_spec, const costmap_2d::Costmap2D &, bool fill)
Used to get the cells that make up the footprint of the robot.
Definition: footprint_helper.cpp:215
base_local_planner::TrajectoryPlanner::rotating_right
bool rotating_right
Booleans to keep track of the direction of rotation for the robot.
Definition: trajectory_planner.h:304
base_local_planner::MapGrid::setTargetCells
void setTargetCells(const costmap_2d::Costmap2D &costmap, const std::vector< geometry_msgs::PoseStamped > &global_plan)
Update what cells are considered path based on the global plan.
Definition: map_grid.cpp:171
base_local_planner::MapCell::within_robot
bool within_robot
Mark for cells within the robot footprint.
Definition: map_cell.h:95
base_local_planner
Definition: costmap_model.h:44
base_local_planner::TrajectoryPlanner::lineCost
double lineCost(int x0, int x1, int y0, int y1)
Definition: trajectory_planner.cpp:389
base_local_planner::TrajectoryPlanner::sim_time_
double sim_time_
The number of seconds each trajectory is "rolled-out".
Definition: trajectory_planner.h:317
costmap_2d::Costmap2D::getCost
unsigned char getCost(unsigned int mx, unsigned int my) const
costmap_2d
base_local_planner::TrajectoryPlanner::heading_scoring_timestep_
double heading_scoring_timestep_
How far to look ahead in time when we score a heading.
Definition: trajectory_planner.h:343
base_local_planner::Trajectory::thetav_
double thetav_
The x, y, and theta velocities of the trajectory.
Definition: trajectory.h:92
Matrix3x3.h
base_local_planner::TrajectoryPlanner::global_plan_
std::vector< geometry_msgs::PoseStamped > global_plan_
The global path for the robot to follow.
Definition: trajectory_planner.h:301
base_local_planner::TrajectoryPlanner::configuration_mutex_
boost::mutex configuration_mutex_
Definition: trajectory_planner.h:353
t
geometry_msgs::TransformStamped t
base_local_planner::TrajectoryPlanner::strafe_right
bool strafe_right
Definition: trajectory_planner.h:307
base_local_planner::TrajectoryPlanner::footprint_spec_
std::vector< geometry_msgs::Point > footprint_spec_
The footprint specification of the robot.
Definition: trajectory_planner.h:299
base_local_planner::MapCell
Stores path distance and goal distance information used for scoring trajectories.
Definition: map_cell.h:76
angles.h
base_local_planner::TrajectoryPlanner::rotating_left
bool rotating_left
Definition: trajectory_planner.h:304
base_local_planner::TrajectoryPlanner::acc_lim_y_
double acc_lim_y_
Definition: trajectory_planner.h:325
base_local_planner::TrajectoryPlanner::prev_x_
double prev_x_
Definition: trajectory_planner.h:327
base_local_planner::TrajectoryPlanner::stuck_right
bool stuck_right
Booleans to keep the robot from oscillating during rotation.
Definition: trajectory_planner.h:303


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:24