Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix speed limits #372

Open
wants to merge 3 commits into
base: ros2-master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 3 additions & 3 deletions teb_local_planner/include/teb_local_planner/teb_config.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
4 changes: 4 additions & 0 deletions teb_local_planner/src/teb_config.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
60 changes: 41 additions & 19 deletions teb_local_planner/src/teb_local_planner_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1041,30 +1041,44 @@ void TebLocalPlannerROS::configureBackupModes(std::vector<geometry_msgs::msg::Po
RCLCPP_INFO(logger_, "TebLocalPlannerROS: oscillation recovery disabled/expired.");
}
}

}


void TebLocalPlannerROS::setSpeedLimit(
const double & speed_limit, const bool & percentage)
{
void TebLocalPlannerROS::setSpeedLimit(const double& speed_limit,
const bool& percentage) {
if (speed_limit == nav2_costmap_2d::NO_SPEED_LIMIT) {
// Restore default value
// Restore Defaults
cfg_->robot.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
Expand All @@ -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;
}
}
}
Expand Down