Skip to content

Commit 401ade6

Browse files
author
Tony Najjar
committed
Fix speed limits
1 parent 1897546 commit 401ade6

File tree

1 file changed

+9
-9
lines changed

1 file changed

+9
-9
lines changed

teb_local_planner/src/teb_local_planner_ros.cpp

Lines changed: 9 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -1061,16 +1061,16 @@ void TebLocalPlannerROS::setSpeedLimit(
10611061
if (speed_limit == nav2_costmap_2d::NO_SPEED_LIMIT) {
10621062
// Restore default value
10631063
cfg_->robot.max_vel_x = cfg_->robot.base_max_vel_x;
1064-
cfg_->robot.base_max_vel_x_backwards = cfg_->robot.base_max_vel_x_backwards;
1065-
cfg_->robot.base_max_vel_y = cfg_->robot.base_max_vel_y;
1066-
cfg_->robot.base_max_vel_theta = cfg_->robot.base_max_vel_theta;
1064+
cfg_->robot.max_vel_x_backwards = cfg_->robot.base_max_vel_x_backwards;
1065+
cfg_->robot.max_vel_y = cfg_->robot.base_max_vel_y;
1066+
cfg_->robot.max_vel_theta = cfg_->robot.base_max_vel_theta;
10671067
} else {
10681068
if (percentage) {
10691069
// Speed limit is expressed in % from maximum speed of robot
10701070
cfg_->robot.max_vel_x = cfg_->robot.base_max_vel_x * speed_limit / 100.0;
1071-
cfg_->robot.base_max_vel_x_backwards = cfg_->robot.base_max_vel_x_backwards * speed_limit / 100.0;
1072-
cfg_->robot.base_max_vel_y = cfg_->robot.base_max_vel_y * speed_limit / 100.0;
1073-
cfg_->robot.base_max_vel_theta = cfg_->robot.base_max_vel_theta * speed_limit / 100.0;
1071+
cfg_->robot.max_vel_x_backwards = cfg_->robot.base_max_vel_x_backwards * speed_limit / 100.0;
1072+
cfg_->robot.max_vel_y = cfg_->robot.base_max_vel_y * speed_limit / 100.0;
1073+
cfg_->robot.max_vel_theta = cfg_->robot.base_max_vel_theta * speed_limit / 100.0;
10741074
} else {
10751075
// Speed limit is expressed in absolute value
10761076
double max_speed_xy = std::max(
@@ -1083,9 +1083,9 @@ void TebLocalPlannerROS::setSpeedLimit(
10831083
// G. Doisy: not sure if that's applicable to base_max_vel_x_backwards.
10841084
const double ratio = speed_limit / max_speed_xy;
10851085
cfg_->robot.max_vel_x = cfg_->robot.base_max_vel_x * ratio;
1086-
cfg_->robot.base_max_vel_x_backwards = cfg_->robot.base_max_vel_x_backwards * ratio;
1087-
cfg_->robot.base_max_vel_y = cfg_->robot.base_max_vel_y * ratio;
1088-
cfg_->robot.base_max_vel_theta = cfg_->robot.base_max_vel_theta * ratio;
1086+
cfg_->robot.max_vel_x_backwards = cfg_->robot.base_max_vel_x_backwards * ratio;
1087+
cfg_->robot.max_vel_y = cfg_->robot.base_max_vel_y * ratio;
1088+
cfg_->robot.max_vel_theta = cfg_->robot.base_max_vel_theta * ratio;
10891089
}
10901090
}
10911091
}

0 commit comments

Comments
 (0)