Skip to content

Commit

Permalink
Update status message
Browse files Browse the repository at this point in the history
  • Loading branch information
sea-bass committed Dec 4, 2024
1 parent bdd6494 commit 42ff99e
Show file tree
Hide file tree
Showing 2 changed files with 3 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down

0 comments on commit 42ff99e

Please sign in to comment.