From 42ff99e39bbeec5e36446cf9c64e1b3adc3c0ba9 Mon Sep 17 00:00:00 2001 From: sea-bass Date: Tue, 3 Dec 2024 20:11:43 -0500 Subject: [PATCH] Update status message --- .../src/check_start_state_bounds.cpp | 2 +- .../test/test_check_start_state_bounds.cpp | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/moveit_ros/planning/planning_request_adapter_plugins/src/check_start_state_bounds.cpp b/moveit_ros/planning/planning_request_adapter_plugins/src/check_start_state_bounds.cpp index 770e1326db..4b22eee85a 100644 --- a/moveit_ros/planning/planning_request_adapter_plugins/src/check_start_state_bounds.cpp +++ b/moveit_ros/planning/planning_request_adapter_plugins/src/check_start_state_bounds.cpp @@ -188,7 +188,7 @@ class CheckStartStateBounds : public planning_interface::PlanningRequestAdapter } else if (params.fix_start_state && should_fix_state) { - constexpr auto msg_string = "Changing start state."; + constexpr auto msg_string = "Normalized start state."; status.message = msg_string; RCLCPP_WARN(logger_, msg_string); moveit::core::robotStateToRobotStateMsg(start_state, req.start_state); diff --git a/moveit_ros/planning/planning_request_adapter_plugins/test/test_check_start_state_bounds.cpp b/moveit_ros/planning/planning_request_adapter_plugins/test/test_check_start_state_bounds.cpp index d7448e9655..9a65375f2f 100644 --- a/moveit_ros/planning/planning_request_adapter_plugins/test/test_check_start_state_bounds.cpp +++ b/moveit_ros/planning/planning_request_adapter_plugins/test/test_check_start_state_bounds.cpp @@ -147,9 +147,9 @@ TEST_F(TestCheckStartStateBounds, TestContinuousJointFixedBounds) const auto result = adapter_->adapt(planning_scene_, request); EXPECT_EQ(result.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS); - EXPECT_EQ(result.message, "Changing start state."); + EXPECT_EQ(result.message, "Normalized start state."); - // Validate that the start state in the request was actually changed. + // Validate that the large continuous joint position value in the request start state was normalized. const auto& joint_names = request.start_state.joint_state.name; const size_t joint_idx = std::find(joint_names.begin(), joint_names.end(), "r_forearm_roll_joint") - joint_names.begin();