diff --git a/rclcpp_action/include/rclcpp_action/client.hpp b/rclcpp_action/include/rclcpp_action/client.hpp index 8470b07226..7872bda8f2 100644 --- a/rclcpp_action/include/rclcpp_action/client.hpp +++ b/rclcpp_action/include/rclcpp_action/client.hpp @@ -582,7 +582,7 @@ class Client : public ClientBase goal_status == GoalStatus::STATUS_SUCCEEDED || goal_status == GoalStatus::STATUS_CANCELED || goal_status == GoalStatus::STATUS_ABORTED || - goal_status == GoalStatus::STATUS_PREEMPTED) + goal_status == 7) // GoalStatus::STATUS_PREEMPTED) { goal_handles_.erase(goal_id); } diff --git a/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp b/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp index f34a8abc3e..b740fb7e90 100644 --- a/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp +++ b/rclcpp_action/include/rclcpp_action/server_goal_handle.hpp @@ -189,7 +189,7 @@ class ServerGoalHandle : public ServerGoalHandleBase { _abort(); auto response = std::make_shared(); - response->status = action_msgs::msg::GoalStatus::STATUS_PREEMPTED; + response->status = 7; // action_msgs::msg::GoalStatus::STATUS_PREEMPTED; response->result = *result_msg; on_terminal_state_(uuid_, response); } diff --git a/rclcpp_action/test/test_server.cpp b/rclcpp_action/test/test_server.cpp index 9bad95a46a..5578db99bf 100644 --- a/rclcpp_action/test/test_server.cpp +++ b/rclcpp_action/test/test_server.cpp @@ -725,7 +725,8 @@ TEST_F(TestServer, publish_status_preemped) rclcpp::spin_until_future_complete(node, future)); auto response = future.get(); - EXPECT_EQ(action_msgs::msg::GoalStatus::STATUS_PREEMPTED, response->status); + // EXPECT_EQ(action_msgs::msg::GoalStatus::STATUS_PREEMPTED, response->status); + EXPECT_EQ(7, response->status); EXPECT_EQ(result->sequence, response->result.sequence); ASSERT_LT(0u, received_msgs.size());