Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 2 additions & 0 deletions rclc/src/rclc/action_client.c
Original file line number Diff line number Diff line change
Expand Up @@ -190,12 +190,14 @@ rclc_action_client_fini(
action_client->allocator->deallocate(
action_client->goal_handles_memory,
action_client->allocator->state);
action_client->goal_handles_memory = NULL;
}

if (NULL != action_client->ros_cancel_response.goals_canceling.data) {
action_client->allocator->deallocate(
action_client->ros_cancel_response.goals_canceling.data,
action_client->allocator->state);
action_client->ros_cancel_response.goals_canceling.data = NULL;
}

rc = rcl_action_client_fini(&action_client->rcl_handle, node);
Expand Down
1 change: 1 addition & 0 deletions rclc/src/rclc/action_server.c
Original file line number Diff line number Diff line change
Expand Up @@ -207,6 +207,7 @@ rclc_action_server_fini(
action_server->allocator->deallocate(
action_server->goal_handles_memory,
action_server->allocator->state);
action_server->goal_handles_memory = NULL;
}

rc = rcl_action_server_fini(&action_server->rcl_handle, node);
Expand Down
47 changes: 47 additions & 0 deletions rclc/test/rclc/test_action_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -706,6 +706,53 @@ TEST_F(ActionServerTest, multi_goal_accept_feedback_and_result) {
ASSERT_EQ(goals.size(), 0U);
}

TEST(Test, rclc_action_server_regression_1) {
rclc_support_t support;
rcl_node_t node;
rcl_ret_t rc;

rcl_allocator_t allocator = rcl_get_default_allocator();
rc = rclc_support_init(&support, 0, nullptr, &allocator);
rc = rclc_node_init_default(&node, "my_node", "my_namespace", &support);
EXPECT_EQ(RCL_RET_OK, rc);

rclc_action_server_t action_server;
rc = rclc_action_server_init_default(
&action_server,
&node,
&support,
ROSIDL_GET_ACTION_TYPE_SUPPORT(example_interfaces, Fibonacci),
"fibonacci"
);
EXPECT_EQ(RCL_RET_OK, rc);

rclc_executor_t executor;
rclc_executor_init(&executor, &support.context, 1, &allocator);

example_interfaces__action__Fibonacci_SendGoal_Request ros_goal_request[RCLC_MAX_GOALS];

rc = rclc_executor_add_action_server(
&executor,
&action_server,
RCLC_MAX_GOALS,
ros_goal_request,
sizeof(example_interfaces__action__Fibonacci_SendGoal_Request),
[](rclc_action_goal_handle_t * /* goal_handle */, void * /* context */) -> rcl_ret_t {
return RCL_RET_ACTION_GOAL_REJECTED;
},
[](rclc_action_goal_handle_t * /* goal_handle */, void * /* context */) -> bool {
return false;
},
&action_server);

EXPECT_EQ(RCL_RET_OK, rc);

EXPECT_EQ(RCL_RET_OK, rclc_action_server_fini(&action_server, &node));

// Second time should be safe
EXPECT_EQ(RCL_RET_OK, rclc_action_server_fini(&action_server, &node));
}

int main(int args, char ** argv)
{
::testing::InitGoogleTest(&args, argv);
Expand Down