Skip to content

Commit

Permalink
Remove action_msgs::msg::GoalStatus::STATUS_PREEMPTED references and …
Browse files Browse the repository at this point in the history
…hard code to 7

Signed-off-by: Sarthak Mittal <[email protected]>
  • Loading branch information
naiveHobo committed May 17, 2020
1 parent d4f73e7 commit 8a18f0c
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 3 deletions.
2 changes: 1 addition & 1 deletion rclcpp_action/include/rclcpp_action/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
Expand Down
2 changes: 1 addition & 1 deletion rclcpp_action/include/rclcpp_action/server_goal_handle.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -189,7 +189,7 @@ class ServerGoalHandle : public ServerGoalHandleBase
{
_abort();
auto response = std::make_shared<typename ActionT::Impl::GetResultService::Response>();
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);
}
Expand Down
3 changes: 2 additions & 1 deletion rclcpp_action/test/test_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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());
Expand Down

0 comments on commit 8a18f0c

Please sign in to comment.