Skip to content

Commit 1e47bf9

Browse files
author
Tony Najjar
committed
.
1 parent eee6e15 commit 1e47bf9

File tree

1 file changed

+3
-3
lines changed

1 file changed

+3
-3
lines changed

teb_local_planner/src/teb_local_planner_ros.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1061,9 +1061,9 @@ 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

0 commit comments

Comments
 (0)