diff --git a/teb_local_planner/include/teb_local_planner/teb_config.h b/teb_local_planner/include/teb_local_planner/teb_config.h index a6851fbe..ac969e88 100644 --- a/teb_local_planner/include/teb_local_planner/teb_config.h +++ b/teb_local_planner/include/teb_local_planner/teb_config.h @@ -271,9 +271,9 @@ class TebConfig robot.max_vel_y = 0.0; robot.max_vel_theta = 0.3; robot.base_max_vel_x = robot.max_vel_x; - robot.base_max_vel_x_backwards = robot.base_max_vel_x_backwards; - robot.base_max_vel_y = robot.base_max_vel_y; - robot.base_max_vel_theta = robot.base_max_vel_theta; + robot.base_max_vel_x_backwards = robot.max_vel_x_backwards; + robot.base_max_vel_y = robot.max_vel_y; + robot.base_max_vel_theta = robot.max_vel_theta; robot.acc_lim_x = 0.5; robot.acc_lim_y = 0.5; robot.acc_lim_theta = 0.5; diff --git a/teb_local_planner/src/teb_config.cpp b/teb_local_planner/src/teb_config.cpp index 23b254e1..686ca00d 100644 --- a/teb_local_planner/src/teb_config.cpp +++ b/teb_local_planner/src/teb_config.cpp @@ -197,9 +197,13 @@ void TebConfig::loadRosParamFromNodeHandle(const nav2_util::LifecycleNode::Share // Robot nh->get_parameter_or(name + "." + "max_vel_x", robot.max_vel_x, robot.max_vel_x); + nh->get_parameter_or(name + "." + "max_vel_x", robot.base_max_vel_x, robot.base_max_vel_x); nh->get_parameter_or(name + "." + "max_vel_x_backwards", robot.max_vel_x_backwards, robot.max_vel_x_backwards); + nh->get_parameter_or(name + "." + "max_vel_x_backwards", robot.base_max_vel_x_backwards, robot.base_max_vel_x_backwards); nh->get_parameter_or(name + "." + "max_vel_y", robot.max_vel_y, robot.max_vel_y); + nh->get_parameter_or(name + "." + "max_vel_y", robot.base_max_vel_y, robot.base_max_vel_y); nh->get_parameter_or(name + "." + "max_vel_theta", robot.max_vel_theta, robot.max_vel_theta); + nh->get_parameter_or(name + "." + "max_vel_theta", robot.base_max_vel_theta, robot.base_max_vel_theta); nh->get_parameter_or(name + "." + "acc_lim_x", robot.acc_lim_x, robot.acc_lim_x); nh->get_parameter_or(name + "." + "acc_lim_y", robot.acc_lim_y, robot.acc_lim_y); nh->get_parameter_or(name + "." + "acc_lim_theta", robot.acc_lim_theta, robot.acc_lim_theta); diff --git a/teb_local_planner/src/teb_local_planner_ros.cpp b/teb_local_planner/src/teb_local_planner_ros.cpp index d5592d2a..520c1b83 100644 --- a/teb_local_planner/src/teb_local_planner_ros.cpp +++ b/teb_local_planner/src/teb_local_planner_ros.cpp @@ -1041,30 +1041,44 @@ void TebLocalPlannerROS::configureBackupModes(std::vectorrobot.max_vel_x = cfg_->robot.base_max_vel_x; - cfg_->robot.base_max_vel_x_backwards = cfg_->robot.base_max_vel_x_backwards; - cfg_->robot.base_max_vel_y = cfg_->robot.base_max_vel_y; - cfg_->robot.base_max_vel_theta = cfg_->robot.base_max_vel_theta; + cfg_->robot.max_vel_x_backwards = cfg_->robot.base_max_vel_x_backwards; + cfg_->robot.max_vel_y = cfg_->robot.base_max_vel_y; + cfg_->robot.max_vel_theta = cfg_->robot.base_max_vel_theta; } else { if (percentage) { - // Speed limit is expressed in % from maximum speed of robot - cfg_->robot.max_vel_x = cfg_->robot.base_max_vel_x * speed_limit / 100.0; - cfg_->robot.base_max_vel_x_backwards = cfg_->robot.base_max_vel_x_backwards * speed_limit / 100.0; - cfg_->robot.base_max_vel_y = cfg_->robot.base_max_vel_y * speed_limit / 100.0; - cfg_->robot.base_max_vel_theta = cfg_->robot.base_max_vel_theta * speed_limit / 100.0; + if (speed_limit > 1.0 || speed_limit < 0.0) { + RCLCPP_WARN_THROTTLE( + logger_, *(clock_), 100, + "Percentage given outside the range 0-1. Using base velocities."); + // Restore defaults + cfg_->robot.max_vel_x = cfg_->robot.base_max_vel_x; + cfg_->robot.max_vel_x_backwards = cfg_->robot.base_max_vel_x_backwards; + cfg_->robot.max_vel_y = cfg_->robot.base_max_vel_y; + cfg_->robot.max_vel_theta = cfg_->robot.base_max_vel_theta; + } else { + // Speed limit is expressed in % from maximum speed of robot + cfg_->robot.max_vel_x = + cfg_->robot.base_max_vel_x * speed_limit / 100.0; + cfg_->robot.max_vel_x_backwards = + cfg_->robot.base_max_vel_x_backwards * speed_limit / 100.0; + cfg_->robot.max_vel_y = + cfg_->robot.base_max_vel_y * speed_limit / 100.0; + cfg_->robot.max_vel_theta = + cfg_->robot.base_max_vel_theta * speed_limit / 100.0; + } } else { // Speed limit is expressed in absolute value - double max_speed_xy = std::max( - std::max(cfg_->robot.base_max_vel_x,cfg_->robot.base_max_vel_x_backwards),cfg_->robot.base_max_vel_y); + double max_speed_xy = + std::max(std::max(cfg_->robot.base_max_vel_x, + cfg_->robot.base_max_vel_x_backwards), + cfg_->robot.base_max_vel_y); if (speed_limit < max_speed_xy) { // Handling components and angular velocity changes: // Max velocities are being changed in the same proportion @@ -1073,9 +1087,17 @@ void TebLocalPlannerROS::setSpeedLimit( // G. Doisy: not sure if that's applicable to base_max_vel_x_backwards. const double ratio = speed_limit / max_speed_xy; cfg_->robot.max_vel_x = cfg_->robot.base_max_vel_x * ratio; - cfg_->robot.base_max_vel_x_backwards = cfg_->robot.base_max_vel_x_backwards * ratio; - cfg_->robot.base_max_vel_y = cfg_->robot.base_max_vel_y * ratio; - cfg_->robot.base_max_vel_theta = cfg_->robot.base_max_vel_theta * ratio; + cfg_->robot.max_vel_x_backwards = + cfg_->robot.base_max_vel_x_backwards * ratio; + cfg_->robot.max_vel_y = cfg_->robot.base_max_vel_y * ratio; + cfg_->robot.max_vel_theta = cfg_->robot.base_max_vel_theta * ratio; + + } else { + // Restore defaults + cfg_->robot.max_vel_x = cfg_->robot.base_max_vel_x; + cfg_->robot.max_vel_x_backwards = cfg_->robot.base_max_vel_x_backwards; + cfg_->robot.max_vel_y = cfg_->robot.base_max_vel_y; + cfg_->robot.max_vel_theta = cfg_->robot.base_max_vel_theta; } } }