trajectory_planner_ros.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 
40 #ifdef HAVE_SYS_TIME_H
41 #include <sys/time.h>
42 #endif
43 
44 #include <boost/tokenizer.hpp>
45 
46 #include <Eigen/Core>
47 #include <cmath>
48 
49 #include <ros/console.h>
50 
52 
54 #include <nav_msgs/Path.h>
55 
57 #include <tf2/utils.h>
58 
59 //register this planner as a BaseLocalPlanner plugin
61 
62 namespace base_local_planner {
63 
64  void TrajectoryPlannerROS::reconfigureCB(BaseLocalPlannerConfig &config, uint32_t level) {
65  if (setup_ && config.restore_defaults) {
66  config = default_config_;
67  //Avoid looping
68  config.restore_defaults = false;
69  }
70  if ( ! setup_) {
71  default_config_ = config;
72  setup_ = true;
73  }
74  tc_->reconfigure(config);
75  reached_goal_ = false;
76  }
77 
79  world_model_(NULL), tc_(NULL), costmap_ros_(NULL), tf_(NULL), setup_(false), initialized_(false), odom_helper_("odom") {}
80 
82  world_model_(NULL), tc_(NULL), costmap_ros_(NULL), tf_(NULL), setup_(false), initialized_(false), odom_helper_("odom") {
83 
84  //initialize the planner
85  initialize(name, tf, costmap_ros);
86  }
87 
89  std::string name,
91  costmap_2d::Costmap2DROS* costmap_ros){
92  if (! isInitialized()) {
93 
94  ros::NodeHandle private_nh("~/" + name);
95  g_plan_pub_ = private_nh.advertise<nav_msgs::Path>("global_plan", 1);
96  l_plan_pub_ = private_nh.advertise<nav_msgs::Path>("local_plan", 1);
97 
98 
99  tf_ = tf;
100  costmap_ros_ = costmap_ros;
101  rot_stopped_velocity_ = 1e-2;
103  double sim_time, sim_granularity, angular_sim_granularity;
104  int vx_samples, vtheta_samples;
105  double path_distance_bias, goal_distance_bias, occdist_scale, heading_lookahead, oscillation_reset_dist, escape_reset_dist, escape_reset_theta;
106  bool holonomic_robot, dwa, simple_attractor, heading_scoring;
107  double heading_scoring_timestep;
108  double max_vel_x, min_vel_x;
109  double backup_vel;
110  double stop_time_buffer;
111  std::string world_model_type;
112  rotating_to_goal_ = false;
113 
114  //initialize the copy of the costmap the controller will use
116 
117 
120  private_nh.param("prune_plan", prune_plan_, true);
121 
122  private_nh.param("yaw_goal_tolerance", yaw_goal_tolerance_, 0.05);
123  private_nh.param("xy_goal_tolerance", xy_goal_tolerance_, 0.10);
124  private_nh.param("acc_lim_x", acc_lim_x_, 2.5);
125  private_nh.param("acc_lim_y", acc_lim_y_, 2.5);
126  private_nh.param("acc_lim_theta", acc_lim_theta_, 3.2);
127 
128  private_nh.param("stop_time_buffer", stop_time_buffer, 0.2);
129 
130  private_nh.param("latch_xy_goal_tolerance", latch_xy_goal_tolerance_, false);
131 
132  //Since I screwed up nicely in my documentation, I'm going to add errors
133  //informing the user if they've set one of the wrong parameters
134  if(private_nh.hasParam("acc_limit_x"))
135  ROS_ERROR("You are using acc_limit_x where you should be using acc_lim_x. Please change your configuration files appropriately. The documentation used to be wrong on this, sorry for any confusion.");
136 
137  if(private_nh.hasParam("acc_limit_y"))
138  ROS_ERROR("You are using acc_limit_y where you should be using acc_lim_y. Please change your configuration files appropriately. The documentation used to be wrong on this, sorry for any confusion.");
139 
140  if(private_nh.hasParam("acc_limit_th"))
141  ROS_ERROR("You are using acc_limit_th where you should be using acc_lim_th. Please change your configuration files appropriately. The documentation used to be wrong on this, sorry for any confusion.");
142 
143  //Assuming this planner is being run within the navigation stack, we can
144  //just do an upward search for the frequency at which its being run. This
145  //also allows the frequency to be overwritten locally.
146  std::string controller_frequency_param_name;
147  if(!private_nh.searchParam("controller_frequency", controller_frequency_param_name))
148  sim_period_ = 0.05;
149  else
150  {
151  double controller_frequency = 0;
152  private_nh.param(controller_frequency_param_name, controller_frequency, 20.0);
153  if(controller_frequency > 0)
154  sim_period_ = 1.0 / controller_frequency;
155  else
156  {
157  ROS_WARN("A controller_frequency less than 0 has been set. Ignoring the parameter, assuming a rate of 20Hz");
158  sim_period_ = 0.05;
159  }
160  }
161  ROS_INFO("Sim period is set to %.2f", sim_period_);
162 
163  private_nh.param("sim_time", sim_time, 1.0);
164  private_nh.param("sim_granularity", sim_granularity, 0.025);
165  private_nh.param("angular_sim_granularity", angular_sim_granularity, sim_granularity);
166  private_nh.param("vx_samples", vx_samples, 3);
167  private_nh.param("vtheta_samples", vtheta_samples, 20);
168 
169  path_distance_bias = nav_core::loadParameterWithDeprecation(private_nh,
170  "path_distance_bias",
171  "pdist_scale",
172  0.6);
173  goal_distance_bias = nav_core::loadParameterWithDeprecation(private_nh,
174  "goal_distance_bias",
175  "gdist_scale",
176  0.6);
177  // values of the deprecated params need to be applied to the current params, as defaults
178  // of defined for dynamic reconfigure will override them otherwise.
179  if (private_nh.hasParam("pdist_scale") & !private_nh.hasParam("path_distance_bias"))
180  {
181  private_nh.setParam("path_distance_bias", path_distance_bias);
182  }
183  if (private_nh.hasParam("gdist_scale") & !private_nh.hasParam("goal_distance_bias"))
184  {
185  private_nh.setParam("goal_distance_bias", goal_distance_bias);
186  }
187 
188  private_nh.param("occdist_scale", occdist_scale, 0.01);
189 
190  bool meter_scoring;
191  if ( ! private_nh.hasParam("meter_scoring")) {
192  ROS_WARN("Trajectory Rollout planner initialized with param meter_scoring not set. Set it to true to make your settings robust against changes of costmap resolution.");
193  } else {
194  private_nh.param("meter_scoring", meter_scoring, false);
195 
196  if(meter_scoring) {
197  //if we use meter scoring, then we want to multiply the biases by the resolution of the costmap
198  double resolution = costmap_->getResolution();
199  goal_distance_bias *= resolution;
200  path_distance_bias *= resolution;
201  } else {
202  ROS_WARN("Trajectory Rollout planner initialized with param meter_scoring set to false. Set it to true to make your settings robust against changes of costmap resolution.");
203  }
204  }
205 
206  private_nh.param("heading_lookahead", heading_lookahead, 0.325);
207  private_nh.param("oscillation_reset_dist", oscillation_reset_dist, 0.05);
208  private_nh.param("escape_reset_dist", escape_reset_dist, 0.10);
209  private_nh.param("escape_reset_theta", escape_reset_theta, M_PI_4);
210  private_nh.param("holonomic_robot", holonomic_robot, true);
211  private_nh.param("max_vel_x", max_vel_x, 0.5);
212  private_nh.param("min_vel_x", min_vel_x, 0.1);
213 
214  double max_rotational_vel;
215  private_nh.param("max_rotational_vel", max_rotational_vel, 1.0);
216  max_vel_th_ = max_rotational_vel;
217  min_vel_th_ = -1.0 * max_rotational_vel;
218 
220  "min_in_place_vel_theta",
221  "min_in_place_rotational_vel", 0.4);
222  reached_goal_ = false;
223  backup_vel = -0.1;
224  if(private_nh.getParam("backup_vel", backup_vel))
225  ROS_WARN("The backup_vel parameter has been deprecated in favor of the escape_vel parameter. To switch, just change the parameter name in your configuration files.");
226 
227  //if both backup_vel and escape_vel are set... we'll use escape_vel
228  private_nh.getParam("escape_vel", backup_vel);
229 
230  if(backup_vel >= 0.0)
231  ROS_WARN("You've specified a positive escape velocity. This is probably not what you want and will cause the robot to move forward instead of backward. You should probably change your escape_vel parameter to be negative");
232 
233  private_nh.param("world_model", world_model_type, std::string("costmap"));
234  private_nh.param("dwa", dwa, true);
235  private_nh.param("heading_scoring", heading_scoring, false);
236  private_nh.param("heading_scoring_timestep", heading_scoring_timestep, 0.8);
237 
238  simple_attractor = false;
239 
240  //parameters for using the freespace controller
241  double min_pt_separation, max_obstacle_height, grid_resolution;
242  private_nh.param("point_grid/max_sensor_range", max_sensor_range_, 2.0);
243  private_nh.param("point_grid/min_pt_separation", min_pt_separation, 0.01);
244  private_nh.param("point_grid/max_obstacle_height", max_obstacle_height, 2.0);
245  private_nh.param("point_grid/grid_resolution", grid_resolution, 0.2);
246 
247  ROS_ASSERT_MSG(world_model_type == "costmap", "At this time, only costmap world models are supported by this controller");
248  world_model_ = new CostmapModel(*costmap_);
249  std::vector<double> y_vels = loadYVels(private_nh);
250 
252 
253  tc_ = new TrajectoryPlanner(*world_model_, *costmap_, footprint_spec_,
254  acc_lim_x_, acc_lim_y_, acc_lim_theta_, sim_time, sim_granularity, vx_samples, vtheta_samples, path_distance_bias,
255  goal_distance_bias, occdist_scale, heading_lookahead, oscillation_reset_dist, escape_reset_dist, escape_reset_theta, holonomic_robot,
256  max_vel_x, min_vel_x, max_vel_th_, min_vel_th_, min_in_place_vel_th_, backup_vel,
257  dwa, heading_scoring, heading_scoring_timestep, meter_scoring, simple_attractor, y_vels, stop_time_buffer, sim_period_, angular_sim_granularity);
258 
259  map_viz_.initialize(name,
261  [this](int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost){
262  return tc_->getCellCosts(cx, cy, path_cost, goal_cost, occ_cost, total_cost);
263  });
264  initialized_ = true;
265 
266  dsrv_ = new dynamic_reconfigure::Server<BaseLocalPlannerConfig>(private_nh);
267  dynamic_reconfigure::Server<BaseLocalPlannerConfig>::CallbackType cb = [this](auto& config, auto level){ reconfigureCB(config, level); };
268  dsrv_->setCallback(cb);
269 
270  } else {
271  ROS_WARN("This planner has already been initialized, doing nothing");
272  }
273  }
274 
275  std::vector<double> TrajectoryPlannerROS::loadYVels(ros::NodeHandle node){
276  std::vector<double> y_vels;
277 
278  std::string y_vel_list;
279  if(node.getParam("y_vels", y_vel_list)){
280  typedef boost::tokenizer<boost::char_separator<char> > tokenizer;
281  boost::char_separator<char> sep("[], ");
282  tokenizer tokens(y_vel_list, sep);
283 
284  for(tokenizer::iterator i = tokens.begin(); i != tokens.end(); i++){
285  y_vels.push_back(atof((*i).c_str()));
286  }
287  }
288  else{
289  //if no values are passed in, we'll provide defaults
290  y_vels.push_back(-0.3);
291  y_vels.push_back(-0.1);
292  y_vels.push_back(0.1);
293  y_vels.push_back(0.3);
294  }
295 
296  return y_vels;
297  }
298 
300  //make sure to clean things up
301  delete dsrv_;
302 
303  if(tc_ != NULL)
304  delete tc_;
305 
306  if(world_model_ != NULL)
307  delete world_model_;
308  }
309 
310  bool TrajectoryPlannerROS::stopWithAccLimits(const geometry_msgs::PoseStamped& global_pose, const geometry_msgs::PoseStamped& robot_vel, geometry_msgs::Twist& cmd_vel){
311  //slow down with the maximum possible acceleration... we should really use the frequency that we're running at to determine what is feasible
312  //but we'll use a tenth of a second to be consistent with the implementation of the local planner.
313  double vx = sign(robot_vel.pose.position.x) * std::max(0.0, (fabs(robot_vel.pose.position.x) - acc_lim_x_ * sim_period_));
314  double vy = sign(robot_vel.pose.position.y) * std::max(0.0, (fabs(robot_vel.pose.position.y) - acc_lim_y_ * sim_period_));
315 
316  double vel_yaw = tf2::getYaw(robot_vel.pose.orientation);
317  double vth = sign(vel_yaw) * std::max(0.0, (fabs(vel_yaw) - acc_lim_theta_ * sim_period_));
318 
319  //we do want to check whether or not the command is valid
320  double yaw = tf2::getYaw(global_pose.pose.orientation);
321  bool valid_cmd = tc_->checkTrajectory(global_pose.pose.position.x, global_pose.pose.position.y, yaw,
322  robot_vel.pose.position.x, robot_vel.pose.position.y, vel_yaw, vx, vy, vth);
323 
324  //if we have a valid command, we'll pass it on, otherwise we'll command all zeros
325  if(valid_cmd){
326  ROS_DEBUG("Slowing down... using vx, vy, vth: %.2f, %.2f, %.2f", vx, vy, vth);
327  cmd_vel.linear.x = vx;
328  cmd_vel.linear.y = vy;
329  cmd_vel.angular.z = vth;
330  return true;
331  }
332 
333  cmd_vel.linear.x = 0.0;
334  cmd_vel.linear.y = 0.0;
335  cmd_vel.angular.z = 0.0;
336  return false;
337  }
338 
339  bool TrajectoryPlannerROS::rotateToGoal(const geometry_msgs::PoseStamped& global_pose, const geometry_msgs::PoseStamped& robot_vel, double goal_th, geometry_msgs::Twist& cmd_vel){
340  double yaw = tf2::getYaw(global_pose.pose.orientation);
341  double vel_yaw = tf2::getYaw(robot_vel.pose.orientation);
342  cmd_vel.linear.x = 0;
343  cmd_vel.linear.y = 0;
344  double ang_diff = angles::shortest_angular_distance(yaw, goal_th);
345 
346  double v_theta_samp = ang_diff > 0.0 ? std::min(max_vel_th_,
347  std::max(min_in_place_vel_th_, ang_diff)) : std::max(min_vel_th_,
348  std::min(-1.0 * min_in_place_vel_th_, ang_diff));
349 
350  //take the acceleration limits of the robot into account
351  double max_acc_vel = fabs(vel_yaw) + acc_lim_theta_ * sim_period_;
352  double min_acc_vel = fabs(vel_yaw) - acc_lim_theta_ * sim_period_;
353 
354  v_theta_samp = sign(v_theta_samp) * std::min(std::max(fabs(v_theta_samp), min_acc_vel), max_acc_vel);
355 
356  //we also want to make sure to send a velocity that allows us to stop when we reach the goal given our acceleration limits
357  double max_speed_to_stop = sqrt(2 * acc_lim_theta_ * fabs(ang_diff));
358 
359  v_theta_samp = sign(v_theta_samp) * std::min(max_speed_to_stop, fabs(v_theta_samp));
360 
361  // Re-enforce min_in_place_vel_th_. It is more important than the acceleration limits.
362  v_theta_samp = v_theta_samp > 0.0
363  ? std::min( max_vel_th_, std::max( min_in_place_vel_th_, v_theta_samp ))
364  : std::max( min_vel_th_, std::min( -1.0 * min_in_place_vel_th_, v_theta_samp ));
365 
366  //we still want to lay down the footprint of the robot and check if the action is legal
367  bool valid_cmd = tc_->checkTrajectory(global_pose.pose.position.x, global_pose.pose.position.y, yaw,
368  robot_vel.pose.position.x, robot_vel.pose.position.y, vel_yaw, 0.0, 0.0, v_theta_samp);
369 
370  ROS_DEBUG("Moving to desired goal orientation, th cmd: %.2f, valid_cmd: %d", v_theta_samp, valid_cmd);
371 
372  if(valid_cmd){
373  cmd_vel.angular.z = v_theta_samp;
374  return true;
375  }
376 
377  cmd_vel.angular.z = 0.0;
378  return false;
379 
380  }
381 
382  bool TrajectoryPlannerROS::setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan){
383  if (! isInitialized()) {
384  ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
385  return false;
386  }
387 
388  //reset the global plan
389  global_plan_.clear();
390  global_plan_ = orig_global_plan;
391 
392  //when we get a new plan, we also want to clear any latch we may have on goal tolerances
393  xy_tolerance_latch_ = false;
394  //reset the at goal flag
395  reached_goal_ = false;
396  return true;
397  }
398 
399  bool TrajectoryPlannerROS::computeVelocityCommands(geometry_msgs::Twist& cmd_vel){
400  if (! isInitialized()) {
401  ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
402  return false;
403  }
404 
405  std::vector<geometry_msgs::PoseStamped> local_plan;
406  geometry_msgs::PoseStamped global_pose;
407  if (!costmap_ros_->getRobotPose(global_pose)) {
408  return false;
409  }
410 
411  std::vector<geometry_msgs::PoseStamped> transformed_plan;
412  //get the global plan in our frame
413  if (!transformGlobalPlan(*tf_, global_plan_, global_pose, *costmap_, global_frame_, transformed_plan)) {
414  ROS_WARN("Could not transform the global plan to the frame of the controller");
415  return false;
416  }
417 
418  //now we'll prune the plan based on the position of the robot
419  if(prune_plan_)
420  prunePlan(global_pose, transformed_plan, global_plan_);
421 
422  geometry_msgs::PoseStamped drive_cmds;
423  drive_cmds.header.frame_id = robot_base_frame_;
424 
425  geometry_msgs::PoseStamped robot_vel;
426  odom_helper_.getRobotVel(robot_vel);
427 
428  /* For timing uncomment
429  struct timeval start, end;
430  double start_t, end_t, t_diff;
431  gettimeofday(&start, NULL);
432  */
433 
434  //if the global plan passed in is empty... we won't do anything
435  if(transformed_plan.empty())
436  return false;
437 
438  const geometry_msgs::PoseStamped& goal_point = transformed_plan.back();
439  //we assume the global goal is the last point in the global plan
440  const double goal_x = goal_point.pose.position.x;
441  const double goal_y = goal_point.pose.position.y;
442 
443  const double yaw = tf2::getYaw(goal_point.pose.orientation);
444 
445  double goal_th = yaw;
446 
447  //check to see if we've reached the goal position
448  if (xy_tolerance_latch_ || (getGoalPositionDistance(global_pose, goal_x, goal_y) <= xy_goal_tolerance_)) {
449 
450  //if the user wants to latch goal tolerance, if we ever reach the goal location, we'll
451  //just rotate in place
453  xy_tolerance_latch_ = true;
454  }
455 
456  double angle = getGoalOrientationAngleDifference(global_pose, goal_th);
457  //check to see if the goal orientation has been reached
458  if (fabs(angle) <= yaw_goal_tolerance_) {
459  //set the velocity command to zero
460  cmd_vel.linear.x = 0.0;
461  cmd_vel.linear.y = 0.0;
462  cmd_vel.angular.z = 0.0;
463  rotating_to_goal_ = false;
464  xy_tolerance_latch_ = false;
465  reached_goal_ = true;
466  } else {
467  //we need to call the next two lines to make sure that the trajectory
468  //planner updates its path distance and goal distance grids
469  tc_->updatePlan(transformed_plan);
470  Trajectory path = tc_->findBestPath(global_pose, robot_vel, drive_cmds);
472 
473  //copy over the odometry information
474  nav_msgs::Odometry base_odom;
475  odom_helper_.getOdom(base_odom);
476 
477  //if we're not stopped yet... we want to stop... taking into account the acceleration limits of the robot
479  if ( ! stopWithAccLimits(global_pose, robot_vel, cmd_vel)) {
480  return false;
481  }
482  }
483  //if we're stopped... then we want to rotate to goal
484  else{
485  //set this so that we know its OK to be moving
486  rotating_to_goal_ = true;
487  if(!rotateToGoal(global_pose, robot_vel, goal_th, cmd_vel)) {
488  return false;
489  }
490  }
491  }
492 
493  //publish an empty plan because we've reached our goal position
494  publishPlan(transformed_plan, g_plan_pub_);
495  publishPlan(local_plan, l_plan_pub_);
496 
497  //we don't actually want to run the controller when we're just rotating to goal
498  return true;
499  }
500 
501  tc_->updatePlan(transformed_plan);
502 
503  //compute what trajectory to drive along
504  Trajectory path = tc_->findBestPath(global_pose, robot_vel, drive_cmds);
505 
507  /* For timing uncomment
508  gettimeofday(&end, NULL);
509  start_t = start.tv_sec + double(start.tv_usec) / 1e6;
510  end_t = end.tv_sec + double(end.tv_usec) / 1e6;
511  t_diff = end_t - start_t;
512  ROS_INFO("Cycle time: %.9f", t_diff);
513  */
514 
515  //pass along drive commands
516  cmd_vel.linear.x = drive_cmds.pose.position.x;
517  cmd_vel.linear.y = drive_cmds.pose.position.y;
518  cmd_vel.angular.z = tf2::getYaw(drive_cmds.pose.orientation);
519 
520  //if we cannot move... tell someone
521  if (path.cost_ < 0) {
522  ROS_DEBUG_NAMED("trajectory_planner_ros",
523  "The rollout planner failed to find a valid plan. This means that the footprint of the robot was in collision for all simulated trajectories.");
524  local_plan.clear();
525  publishPlan(transformed_plan, g_plan_pub_);
526  publishPlan(local_plan, l_plan_pub_);
527  return false;
528  }
529 
530  ROS_DEBUG_NAMED("trajectory_planner_ros", "A valid velocity command of (%.2f, %.2f, %.2f) was found for this cycle.",
531  cmd_vel.linear.x, cmd_vel.linear.y, cmd_vel.angular.z);
532 
533  // Fill out the local plan
534  for (unsigned int i = 0; i < path.getPointsSize(); ++i) {
535  double p_x, p_y, p_th;
536  path.getPoint(i, p_x, p_y, p_th);
537  geometry_msgs::PoseStamped pose;
538  pose.header.frame_id = global_frame_;
539  pose.header.stamp = ros::Time::now();
540  pose.pose.position.x = p_x;
541  pose.pose.position.y = p_y;
542  pose.pose.position.z = 0.0;
543  tf2::Quaternion q;
544  q.setRPY(0, 0, p_th);
545  tf2::convert(q, pose.pose.orientation);
546  local_plan.push_back(pose);
547  }
548 
549  //publish information to the visualizer
550  publishPlan(transformed_plan, g_plan_pub_);
551  publishPlan(local_plan, l_plan_pub_);
552  return true;
553  }
554 
555  bool TrajectoryPlannerROS::checkTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map){
556  geometry_msgs::PoseStamped global_pose;
557  if(costmap_ros_->getRobotPose(global_pose)){
558  if(update_map){
559  //we need to give the planne some sort of global plan, since we're only checking for legality
560  //we'll just give the robots current position
561  std::vector<geometry_msgs::PoseStamped> plan;
562  plan.push_back(global_pose);
563  tc_->updatePlan(plan, true);
564  }
565 
566  //copy over the odometry information
567  nav_msgs::Odometry base_odom;
568  {
569  boost::recursive_mutex::scoped_lock lock(odom_lock_);
570  base_odom = base_odom_;
571  }
572 
573  return tc_->checkTrajectory(global_pose.pose.position.x, global_pose.pose.position.y, tf2::getYaw(global_pose.pose.orientation),
574  base_odom.twist.twist.linear.x,
575  base_odom.twist.twist.linear.y,
576  base_odom.twist.twist.angular.z, vx_samp, vy_samp, vtheta_samp);
577 
578  }
579  ROS_WARN("Failed to get the pose of the robot. No trajectories will pass as legal in this case.");
580  return false;
581  }
582 
583 
584  double TrajectoryPlannerROS::scoreTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map){
585  // Copy of checkTrajectory that returns a score instead of True / False
586  geometry_msgs::PoseStamped global_pose;
587  if(costmap_ros_->getRobotPose(global_pose)){
588  if(update_map){
589  //we need to give the planne some sort of global plan, since we're only checking for legality
590  //we'll just give the robots current position
591  std::vector<geometry_msgs::PoseStamped> plan;
592  plan.push_back(global_pose);
593  tc_->updatePlan(plan, true);
594  }
595 
596  //copy over the odometry information
597  nav_msgs::Odometry base_odom;
598  {
599  boost::recursive_mutex::scoped_lock lock(odom_lock_);
600  base_odom = base_odom_;
601  }
602 
603  return tc_->scoreTrajectory(global_pose.pose.position.x, global_pose.pose.position.y, tf2::getYaw(global_pose.pose.orientation),
604  base_odom.twist.twist.linear.x,
605  base_odom.twist.twist.linear.y,
606  base_odom.twist.twist.angular.z, vx_samp, vy_samp, vtheta_samp);
607 
608  }
609  ROS_WARN("Failed to get the pose of the robot. No trajectories will pass as legal in this case.");
610  return -1.0;
611  }
612 
614  if (! isInitialized()) {
615  ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
616  return false;
617  }
618  //return flag set in controller
619  return reached_goal_;
620  }
621 };
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
nav_core::loadParameterWithDeprecation
param_t loadParameterWithDeprecation(const ros::NodeHandle &nh, const std::string current_name, const std::string old_name, const param_t &default_value)
tf2::convert
void convert(const A &a, B &b)
angles::shortest_angular_distance
static double shortest_angular_distance(double from, double to)
min
int min(int a, int b)
base_local_planner::TrajectoryPlannerROS::default_config_
base_local_planner::BaseLocalPlannerConfig default_config_
Definition: trajectory_planner_ros.h:256
angle
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
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
base_local_planner::TrajectoryPlannerROS::tc_
TrajectoryPlanner * tc_
The trajectory controller.
Definition: trajectory_planner_ros.h:230
tf2::getYaw
double getYaw(const A &a)
utils.h
base_local_planner::TrajectoryPlannerROS
A ROS wrapper for the trajectory controller that queries the param server to construct a controller.
Definition: trajectory_planner_ros.h:113
base_local_planner::OdometryHelperRos::getOdom
void getOdom(nav_msgs::Odometry &base_odom)
Definition: odometry_helper_ros.cpp:97
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
base_local_planner::TrajectoryPlannerROS::min_vel_th_
double min_vel_th_
Definition: trajectory_planner_ros.h:246
base_local_planner::TrajectoryPlannerROS::checkTrajectory
bool checkTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map=true)
Generate and score a single trajectory.
Definition: trajectory_planner_ros.cpp:590
tf2::Quaternion::setRPY
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
base_local_planner::TrajectoryPlannerROS::l_plan_pub_
ros::Publisher l_plan_pub_
Definition: trajectory_planner_ros.h:253
trajectory_planner_ros.h
base_local_planner::TrajectoryPlannerROS::base_odom_
nav_msgs::Odometry base_odom_
Used to get the velocity of the robot.
Definition: trajectory_planner_ros.h:238
base_local_planner::TrajectoryPlannerROS::odom_helper_
base_local_planner::OdometryHelperRos odom_helper_
Definition: trajectory_planner_ros.h:261
base_local_planner::TrajectoryPlannerROS::computeVelocityCommands
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel)
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
Definition: trajectory_planner_ros.cpp:434
costmap_2d::Costmap2DROS::getBaseFrameID
const std::string & getBaseFrameID() const noexcept
base_local_planner::transformGlobalPlan
bool transformGlobalPlan(const tf2_ros::Buffer &tf, const std::vector< geometry_msgs::PoseStamped > &global_plan, const geometry_msgs::PoseStamped &global_robot_pose, const costmap_2d::Costmap2D &costmap, const std::string &global_frame, std::vector< geometry_msgs::PoseStamped > &transformed_plan)
Transforms the global plan of the robot from the planner frame to the frame of the costmap,...
Definition: goal_functions.cpp:96
base_local_planner::getGoalPositionDistance
double getGoalPositionDistance(const geometry_msgs::PoseStamped &global_pose, double goal_x, double goal_y)
return squared distance to check if the goal position has been achieved
Definition: goal_functions.cpp:49
base_local_planner::TrajectoryPlannerROS::scoreTrajectory
double scoreTrajectory(double vx_samp, double vy_samp, double vtheta_samp, bool update_map=true)
Generate and score a single trajectory.
Definition: trajectory_planner_ros.cpp:619
base_local_planner::TrajectoryPlannerROS::max_vel_th_
double max_vel_th_
Definition: trajectory_planner_ros.h:246
base_local_planner::TrajectoryPlannerROS::~TrajectoryPlannerROS
~TrajectoryPlannerROS()
Destructor for the wrapper.
Definition: trajectory_planner_ros.cpp:334
base_local_planner::TrajectoryPlannerROS::rotating_to_goal_
bool rotating_to_goal_
Definition: trajectory_planner_ros.h:249
base_local_planner::OdometryHelperRos::getRobotVel
void getRobotVel(geometry_msgs::PoseStamped &robot_vel)
Definition: odometry_helper_ros.cpp:103
base_local_planner::TrajectoryPlannerROS::min_in_place_vel_th_
double min_in_place_vel_th_
Definition: trajectory_planner_ros.h:241
base_local_planner::TrajectoryPlannerROS::reconfigureCB
void reconfigureCB(BaseLocalPlannerConfig &config, uint32_t level)
Callback to update the local planner's parameters based on dynamic reconfigure.
Definition: trajectory_planner_ros.cpp:99
base_local_planner::TrajectoryPlannerROS::world_model_
WorldModel * world_model_
The world model that the controller will use.
Definition: trajectory_planner_ros.h:229
costmap_2d::Costmap2DROS::getRobotFootprint
const std::vector< geometry_msgs::Point > & getRobotFootprint() const noexcept
base_local_planner::TrajectoryPlannerROS::global_frame_
std::string global_frame_
The frame in which the controller will run.
Definition: trajectory_planner_ros.h:236
console.h
base_local_planner::TrajectoryPlannerROS::setup_
bool setup_
Definition: trajectory_planner_ros.h:257
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::TrajectoryPlannerROS::initialize
void initialize(std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *costmap_ros)
Constructs the ros wrapper.
Definition: trajectory_planner_ros.cpp:123
base_local_planner::TrajectoryPlannerROS::prune_plan_
bool prune_plan_
Definition: trajectory_planner_ros.h:243
base_local_planner::TrajectoryPlannerROS::odom_lock_
boost::recursive_mutex odom_lock_
Definition: trajectory_planner_ros.h:244
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
base_local_planner::TrajectoryPlannerROS::rot_stopped_velocity_
double rot_stopped_velocity_
Definition: trajectory_planner_ros.h:240
ROS_DEBUG
#define ROS_DEBUG(...)
ROS_DEBUG_NAMED
#define ROS_DEBUG_NAMED(name,...)
base_local_planner::TrajectoryPlannerROS::costmap_ros_
costmap_2d::Costmap2DROS * costmap_ros_
The ROS wrapper for the costmap the controller will use.
Definition: trajectory_planner_ros.h:232
base_local_planner::TrajectoryPlannerROS::latch_xy_goal_tolerance_
bool latch_xy_goal_tolerance_
Definition: trajectory_planner_ros.h:251
base_local_planner::TrajectoryPlannerROS::footprint_spec_
std::vector< geometry_msgs::Point > footprint_spec_
Definition: trajectory_planner_ros.h:263
base_local_planner::getGoalOrientationAngleDifference
double getGoalOrientationAngleDifference(const geometry_msgs::PoseStamped &global_pose, double goal_th)
return angle difference to goal to check if the goal orientation has been achieved
Definition: goal_functions.cpp:53
goal_functions.h
ROS_ASSERT_MSG
#define ROS_ASSERT_MSG(cond,...)
ROS_WARN
#define ROS_WARN(...)
tf2_ros::Buffer
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::TrajectoryPlannerROS::acc_lim_theta_
double acc_lim_theta_
Definition: trajectory_planner_ros.h:247
base_local_planner::TrajectoryPlannerROS::robot_base_frame_
std::string robot_base_frame_
Used as the base frame id of the robot.
Definition: trajectory_planner_ros.h:239
base_local_planner::TrajectoryPlannerROS::costmap_
costmap_2d::Costmap2D * costmap_
The costmap the controller will use.
Definition: trajectory_planner_ros.h:233
base_local_planner::TrajectoryPlannerROS::xy_goal_tolerance_
double xy_goal_tolerance_
Definition: trajectory_planner_ros.h:241
base_local_planner::TrajectoryPlannerROS::global_plan_
std::vector< geometry_msgs::PoseStamped > global_plan_
Definition: trajectory_planner_ros.h:242
base_local_planner::TrajectoryPlannerROS::acc_lim_y_
double acc_lim_y_
Definition: trajectory_planner_ros.h:247
base_local_planner::TrajectoryPlannerROS::xy_tolerance_latch_
bool xy_tolerance_latch_
Definition: trajectory_planner_ros.h:251
base_local_planner::prunePlan
void prunePlan(const geometry_msgs::PoseStamped &global_pose, std::vector< geometry_msgs::PoseStamped > &plan, std::vector< geometry_msgs::PoseStamped > &global_plan)
Trim off parts of the global plan that are far enough behind the robot.
Definition: goal_functions.cpp:77
base_local_planner::TrajectoryPlannerROS::acc_lim_x_
double acc_lim_x_
Definition: trajectory_planner_ros.h:247
costmap_2d::Costmap2DROS::getRobotPose
bool getRobotPose(geometry_msgs::PoseStamped &global_pose) const
base_local_planner::MapGridVisualizer::initialize
void initialize(const std::string &name, std::string frame, boost::function< bool(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost)> cost_function)
Initializes the MapGridVisualizer.
Definition: map_grid_visualizer.cpp:77
base_local_planner::TrajectoryPlannerROS::reached_goal_
bool reached_goal_
Definition: trajectory_planner_ros.h:250
base_local_planner::TrajectoryPlannerROS::setPlan
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &orig_global_plan)
Set the plan that the controller is following.
Definition: trajectory_planner_ros.cpp:417
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::TrajectoryPlannerROS::isInitialized
bool isInitialized()
Definition: trajectory_planner_ros.h:191
base_local_planner::TrajectoryPlannerROS::isGoalReached
bool isGoalReached()
Check if the goal pose has been achieved.
Definition: trajectory_planner_ros.cpp:648
base_local_planner::MapGridVisualizer::publishCostCloud
void publishCostCloud(const costmap_2d::Costmap2D *costmap_p_)
Build and publish a PointCloud if the publish_cost_grid_pc parameter was true. Only include points fo...
Definition: map_grid_visualizer.cpp:86
base_local_planner::TrajectoryPlanner::reconfigure
void reconfigure(BaseLocalPlannerConfig &cfg)
Reconfigures the trajectory planner.
Definition: trajectory_planner.cpp:61
initialize
ROSCONSOLE_DECL void initialize()
ROS_ERROR
#define ROS_ERROR(...)
base_local_planner::TrajectoryPlannerROS::loadYVels
std::vector< double > loadYVels(ros::NodeHandle node)
Definition: trajectory_planner_ros.cpp:310
class_list_macros.hpp
tf2::Quaternion
costmap_2d::Costmap2D::getResolution
double getResolution() const
base_local_planner::TrajectoryPlannerROS::max_sensor_range_
double max_sensor_range_
Keep track of the effective maximum range of our sensors.
Definition: trajectory_planner_ros.h:237
tf
base_local_planner::TrajectoryPlannerROS::dsrv_
dynamic_reconfigure::Server< BaseLocalPlannerConfig > * dsrv_
Definition: trajectory_planner_ros.h:255
base_local_planner::TrajectoryPlannerROS::map_viz_
MapGridVisualizer map_viz_
The map grid visualizer for outputting the potential field generated by the cost function.
Definition: trajectory_planner_ros.h:234
base_local_planner::TrajectoryPlannerROS::stopWithAccLimits
bool stopWithAccLimits(const geometry_msgs::PoseStamped &global_pose, const geometry_msgs::PoseStamped &robot_vel, geometry_msgs::Twist &cmd_vel)
Stop the robot taking into account acceleration limits.
Definition: trajectory_planner_ros.cpp:345
base_local_planner::TrajectoryPlannerROS::initialized_
bool initialized_
Definition: trajectory_planner_ros.h:260
costmap_2d::Costmap2DROS::getCostmap
Costmap2D * getCostmap() const
costmap_2d::Costmap2DROS::getGlobalFrameID
const std::string & getGlobalFrameID() const noexcept
base_local_planner
Definition: costmap_model.h:44
base_local_planner::TrajectoryPlannerROS::tf_
tf2_ros::Buffer * tf_
Used for transforming point clouds.
Definition: trajectory_planner_ros.h:235
tf_
tf2_ros::Buffer * tf_
ROS_INFO
#define ROS_INFO(...)
base_local_planner::TrajectoryPlannerROS::TrajectoryPlannerROS
TrajectoryPlannerROS()
Default constructor for the ros wrapper.
Definition: trajectory_planner_ros.cpp:113
base_local_planner::publishPlan
void publishPlan(const std::vector< geometry_msgs::PoseStamped > &path, const ros::Publisher &pub)
Publish a plan for visualization purposes.
Definition: goal_functions.cpp:58
costmap_2d::Costmap2DROS
base_local_planner::TrajectoryPlannerROS::g_plan_pub_
ros::Publisher g_plan_pub_
Definition: trajectory_planner_ros.h:253
nav_core::BaseLocalPlanner
base_local_planner::TrajectoryPlannerROS::sim_period_
double sim_period_
Definition: trajectory_planner_ros.h:248
ros::NodeHandle
base_local_planner::stopped
bool stopped(const nav_msgs::Odometry &base_odom, const double &rot_stopped_velocity, const double &trans_stopped_velocity)
Check whether the robot is stopped or not.
Definition: goal_functions.cpp:239
base_local_planner::TrajectoryPlannerROS::sign
double sign(double x)
Definition: trajectory_planner_ros.h:225
base_local_planner::TrajectoryPlannerROS::rotateToGoal
bool rotateToGoal(const geometry_msgs::PoseStamped &global_pose, const geometry_msgs::PoseStamped &robot_vel, double goal_th, geometry_msgs::Twist &cmd_vel)
Once a goal position is reached... rotate to the goal orientation.
Definition: trajectory_planner_ros.cpp:374
parameter_magic.h
ros::Time::now
static Time now()
base_local_planner::TrajectoryPlannerROS::yaw_goal_tolerance_
double yaw_goal_tolerance_
Definition: trajectory_planner_ros.h:241
base_local_planner::TrajectoryPlannerROS::trans_stopped_velocity_
double trans_stopped_velocity_
Definition: trajectory_planner_ros.h:240


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