Skip to content

Commit 6f4d597

Browse files
mikefergusonSteveMacenski
authored andcommitted
fix bug in use of v_angular_min_in_place (#4813)
Signed-off-by: Michael Ferguson <[email protected]>
1 parent d0691f5 commit 6f4d597

File tree

2 files changed

+14
-1
lines changed

2 files changed

+14
-1
lines changed

nav2_graceful_controller/src/graceful_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -364,7 +364,7 @@ geometry_msgs::msg::Twist GracefulController::rotateToTarget(double angle_to_tar
364364
geometry_msgs::msg::Twist vel;
365365
vel.linear.x = 0.0;
366366
vel.angular.z = params_->rotation_scaling_factor * angle_to_target * params_->v_angular_max;
367-
vel.angular.z = std::copysign(1.0, vel.angular.z) * std::min(abs(vel.angular.z),
367+
vel.angular.z = std::copysign(1.0, vel.angular.z) * std::max(abs(vel.angular.z),
368368
params_->v_angular_min_in_place);
369369
return vel;
370370
}

nav2_graceful_controller/test/test_graceful_controller.cpp

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -461,6 +461,19 @@ TEST(GracefulControllerTest, rotateToTarget) {
461461
// Check results: it must be a negative rotation
462462
EXPECT_EQ(cmd_vel.linear.x, 0.0);
463463
EXPECT_EQ(cmd_vel.angular.z, -0.25);
464+
465+
// Set very high v_angular_min_in_place velocity
466+
results = params->set_parameters_atomically(
467+
{rclcpp::Parameter("test.v_angular_min_in_place", 1.0)});
468+
rclcpp::spin_until_future_complete(node->get_node_base_interface(), results);
469+
470+
// Set a new angle to target
471+
angle_to_target = 0.5;
472+
cmd_vel = controller->rotateToTarget(angle_to_target);
473+
474+
// Check results: positive velocity, at least as high as min_in_place
475+
EXPECT_EQ(cmd_vel.linear.x, 0.0);
476+
EXPECT_EQ(cmd_vel.angular.z, 1.0);
464477
}
465478

466479
TEST(GracefulControllerTest, setSpeedLimit) {

0 commit comments

Comments
 (0)