Skip to content

Commit 16ba34f

Browse files
committed
rclcpp_action changes that I missed
Signed-off-by: William Woodall <[email protected]>
1 parent d4906d6 commit 16ba34f

File tree

4 files changed

+12
-15
lines changed

4 files changed

+12
-15
lines changed

rclcpp_action/include/rclcpp_action/server.hpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -279,19 +279,19 @@ class ServerBase : public rclcpp::Waitable
279279
/// \internal
280280
RCLCPP_ACTION_PUBLIC
281281
void
282-
execute_goal_request_received(std::shared_ptr<void> & data);
282+
execute_goal_request_received(const std::shared_ptr<void> & data);
283283

284284
/// Handle a request to cancel goals on the server
285285
/// \internal
286286
RCLCPP_ACTION_PUBLIC
287287
void
288-
execute_cancel_request_received(std::shared_ptr<void> & data);
288+
execute_cancel_request_received(const std::shared_ptr<void> & data);
289289

290290
/// Handle a request to get the result of an action
291291
/// \internal
292292
RCLCPP_ACTION_PUBLIC
293293
void
294-
execute_result_request_received(std::shared_ptr<void> & data);
294+
execute_result_request_received(const std::shared_ptr<void> & data);
295295

296296
/// Handle a timeout indicating a completed goal should be forgotten by the server
297297
/// \internal

rclcpp_action/src/server.cpp

Lines changed: 3 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -307,7 +307,7 @@ ServerBase::execute(const std::shared_ptr<void> & data)
307307
}
308308

309309
void
310-
ServerBase::execute_goal_request_received(std::shared_ptr<void> & data)
310+
ServerBase::execute_goal_request_received(const std::shared_ptr<void> & data)
311311
{
312312
auto shared_ptr = std::static_pointer_cast
313313
<std::tuple<rcl_ret_t, rcl_action_goal_info_t, rmw_request_id_t, std::shared_ptr<void>>>(data);
@@ -405,11 +405,10 @@ ServerBase::execute_goal_request_received(std::shared_ptr<void> & data)
405405
// Tell user to start executing action
406406
call_goal_accepted_callback(handle, uuid, message);
407407
}
408-
data.reset();
409408
}
410409

411410
void
412-
ServerBase::execute_cancel_request_received(std::shared_ptr<void> & data)
411+
ServerBase::execute_cancel_request_received(const std::shared_ptr<void> & data)
413412
{
414413
auto shared_ptr = std::static_pointer_cast
415414
<std::tuple<rcl_ret_t, std::shared_ptr<action_msgs::srv::CancelGoal::Request>,
@@ -504,11 +503,10 @@ ServerBase::execute_cancel_request_received(std::shared_ptr<void> & data)
504503
if (RCL_RET_OK != ret) {
505504
rclcpp::exceptions::throw_from_rcl_error(ret);
506505
}
507-
data.reset();
508506
}
509507

510508
void
511-
ServerBase::execute_result_request_received(std::shared_ptr<void> & data)
509+
ServerBase::execute_result_request_received(const std::shared_ptr<void> & data)
512510
{
513511
auto shared_ptr = std::static_pointer_cast
514512
<std::tuple<rcl_ret_t, std::shared_ptr<void>, rmw_request_id_t>>(data);
@@ -568,7 +566,6 @@ ServerBase::execute_result_request_received(std::shared_ptr<void> & data)
568566
rclcpp::exceptions::throw_from_rcl_error(rcl_ret);
569567
}
570568
}
571-
data.reset();
572569
}
573570

574571
void

rclcpp_action/test/test_client.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -397,13 +397,13 @@ TEST_F(TestClient, is_ready) {
397397
ASSERT_EQ(
398398
RCL_RET_OK,
399399
rcl_wait_set_init(&wait_set, 10, 10, 10, 10, 10, 10, rcl_context, allocator));
400-
ASSERT_NO_THROW(action_client->add_to_wait_set(&wait_set));
401-
EXPECT_TRUE(action_client->is_ready(&wait_set));
400+
ASSERT_NO_THROW(action_client->add_to_wait_set(wait_set));
401+
EXPECT_TRUE(action_client->is_ready(wait_set));
402402

403403
{
404404
auto mock = mocking_utils::patch_and_return(
405405
"lib:rclcpp_action", rcl_action_client_wait_set_get_entities_ready, RCL_RET_ERROR);
406-
EXPECT_THROW(action_client->is_ready(&wait_set), rclcpp::exceptions::RCLError);
406+
EXPECT_THROW(action_client->is_ready(wait_set), rclcpp::exceptions::RCLError);
407407
}
408408
client_node.reset(); // Drop node before action client
409409
}

rclcpp_action/test/test_server.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1107,12 +1107,12 @@ TEST_F(TestGoalRequestServer, is_ready_rcl_error) {
11071107
{
11081108
EXPECT_EQ(RCL_RET_OK, rcl_wait_set_fini(&wait_set));
11091109
});
1110-
EXPECT_NO_THROW(action_server_->add_to_wait_set(&wait_set));
1110+
EXPECT_NO_THROW(action_server_->add_to_wait_set(wait_set));
11111111

1112-
EXPECT_TRUE(action_server_->is_ready(&wait_set));
1112+
EXPECT_TRUE(action_server_->is_ready(wait_set));
11131113
auto mock = mocking_utils::patch_and_return(
11141114
"lib:rclcpp_action", rcl_action_server_wait_set_get_entities_ready, RCL_RET_ERROR);
1115-
EXPECT_THROW(action_server_->is_ready(&wait_set), rclcpp::exceptions::RCLError);
1115+
EXPECT_THROW(action_server_->is_ready(wait_set), rclcpp::exceptions::RCLError);
11161116
}
11171117

11181118
TEST_F(TestGoalRequestServer, execute_goal_request_received_take_goal_request_errors)

0 commit comments

Comments
 (0)