40 #ifdef HAVE_SYS_TIME_H
44 #include <boost/tokenizer.hpp>
54 #include <nav_msgs/Path.h>
65 if (
setup_ && config.restore_defaults) {
68 config.restore_defaults =
false;
79 world_model_(NULL), tc_(NULL), costmap_ros_(NULL),
tf_(NULL), setup_(false), initialized_(false), odom_helper_(
"odom") {}
82 world_model_(NULL), tc_(NULL), costmap_ros_(NULL),
tf_(NULL), setup_(false), initialized_(false), odom_helper_(
"odom") {
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);
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;
110 double stop_time_buffer;
111 std::string world_model_type;
124 private_nh.param(
"acc_lim_x",
acc_lim_x_, 2.5);
125 private_nh.param(
"acc_lim_y",
acc_lim_y_, 2.5);
128 private_nh.param(
"stop_time_buffer", stop_time_buffer, 0.2);
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.");
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.");
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.");
146 std::string controller_frequency_param_name;
147 if(!private_nh.searchParam(
"controller_frequency", controller_frequency_param_name))
151 double controller_frequency = 0;
152 private_nh.param(controller_frequency_param_name, controller_frequency, 20.0);
153 if(controller_frequency > 0)
157 ROS_WARN(
"A controller_frequency less than 0 has been set. Ignoring the parameter, assuming a rate of 20Hz");
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);
170 "path_distance_bias",
174 "goal_distance_bias",
179 if (private_nh.hasParam(
"pdist_scale") & !private_nh.hasParam(
"path_distance_bias"))
181 private_nh.setParam(
"path_distance_bias", path_distance_bias);
183 if (private_nh.hasParam(
"gdist_scale") & !private_nh.hasParam(
"goal_distance_bias"))
185 private_nh.setParam(
"goal_distance_bias", goal_distance_bias);
188 private_nh.param(
"occdist_scale", occdist_scale, 0.01);
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.");
194 private_nh.param(
"meter_scoring", meter_scoring,
false);
199 goal_distance_bias *= resolution;
200 path_distance_bias *= resolution;
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.");
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);
214 double max_rotational_vel;
215 private_nh.param(
"max_rotational_vel", max_rotational_vel, 1.0);
220 "min_in_place_vel_theta",
221 "min_in_place_rotational_vel", 0.4);
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.");
228 private_nh.getParam(
"escape_vel", backup_vel);
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");
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);
238 simple_attractor =
false;
241 double min_pt_separation, max_obstacle_height, grid_resolution;
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);
247 ROS_ASSERT_MSG(world_model_type ==
"costmap",
"At this time, only costmap world models are supported by this controller");
249 std::vector<double> y_vels =
loadYVels(private_nh);
255 goal_distance_bias, occdist_scale, heading_lookahead, oscillation_reset_dist, escape_reset_dist, escape_reset_theta, holonomic_robot,
257 dwa, heading_scoring, heading_scoring_timestep, meter_scoring, simple_attractor, y_vels, stop_time_buffer,
sim_period_, angular_sim_granularity);
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);
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);
271 ROS_WARN(
"This planner has already been initialized, doing nothing");
276 std::vector<double> y_vels;
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);
284 for(tokenizer::iterator i = tokens.begin(); i != tokens.end(); i++){
285 y_vels.push_back(atof((*i).c_str()));
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);
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_));
316 double vel_yaw =
tf2::getYaw(robot_vel.pose.orientation);
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);
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;
333 cmd_vel.linear.x = 0.0;
334 cmd_vel.linear.y = 0.0;
335 cmd_vel.angular.z = 0.0;
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;
346 double v_theta_samp = ang_diff > 0.0 ? std::min(
max_vel_th_,
354 v_theta_samp =
sign(v_theta_samp) * std::min(std::max(fabs(v_theta_samp), min_acc_vel), max_acc_vel);
357 double max_speed_to_stop = sqrt(2 *
acc_lim_theta_ * fabs(ang_diff));
359 v_theta_samp =
sign(v_theta_samp) * std::min(max_speed_to_stop, fabs(v_theta_samp));
362 v_theta_samp = v_theta_samp > 0.0
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);
370 ROS_DEBUG(
"Moving to desired goal orientation, th cmd: %.2f, valid_cmd: %d", v_theta_samp, valid_cmd);
373 cmd_vel.angular.z = v_theta_samp;
377 cmd_vel.angular.z = 0.0;
384 ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
401 ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");
405 std::vector<geometry_msgs::PoseStamped> local_plan;
406 geometry_msgs::PoseStamped global_pose;
411 std::vector<geometry_msgs::PoseStamped> transformed_plan;
414 ROS_WARN(
"Could not transform the global plan to the frame of the controller");
422 geometry_msgs::PoseStamped drive_cmds;
425 geometry_msgs::PoseStamped robot_vel;
435 if(transformed_plan.empty())
438 const geometry_msgs::PoseStamped& goal_point = transformed_plan.back();
440 const double goal_x = goal_point.pose.position.x;
441 const double goal_y = goal_point.pose.position.y;
443 const double yaw =
tf2::getYaw(goal_point.pose.orientation);
445 double goal_th = yaw;
460 cmd_vel.linear.x = 0.0;
461 cmd_vel.linear.y = 0.0;
462 cmd_vel.angular.z = 0.0;
470 Trajectory path =
tc_->
findBestPath(global_pose, robot_vel, drive_cmds);
474 nav_msgs::Odometry base_odom;
487 if(!
rotateToGoal(global_pose, robot_vel, goal_th, cmd_vel)) {
504 Trajectory path =
tc_->
findBestPath(global_pose, robot_vel, drive_cmds);
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);
521 if (path.cost_ < 0) {
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.");
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);
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;
540 pose.pose.position.x = p_x;
541 pose.pose.position.y = p_y;
542 pose.pose.position.z = 0.0;
546 local_plan.push_back(pose);
556 geometry_msgs::PoseStamped global_pose;
561 std::vector<geometry_msgs::PoseStamped> plan;
562 plan.push_back(global_pose);
567 nav_msgs::Odometry base_odom;
569 boost::recursive_mutex::scoped_lock lock(
odom_lock_);
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);
579 ROS_WARN(
"Failed to get the pose of the robot. No trajectories will pass as legal in this case.");
586 geometry_msgs::PoseStamped global_pose;
591 std::vector<geometry_msgs::PoseStamped> plan;
592 plan.push_back(global_pose);
597 nav_msgs::Odometry base_odom;
599 boost::recursive_mutex::scoped_lock lock(
odom_lock_);
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);
609 ROS_WARN(
"Failed to get the pose of the robot. No trajectories will pass as legal in this case.");
615 ROS_ERROR(
"This planner has not been initialized, please call initialize() before using this planner");