[rcl_action] Store allocator used for message initialization in the message struct

This relieves the user from providing the correct allocator when finalizing messages.
This commit is contained in:
Jacob Perron 2018-10-31 17:45:51 -07:00
parent e64fcaf5a8
commit 88eaa3a926
3 changed files with 61 additions and 68 deletions

View file

@ -58,9 +58,19 @@ typedef struct rcl_action_server_t rcl_action_server_t;
// Typedef generated messages for convenience
typedef action_msgs__msg__GoalInfo rcl_action_goal_info_t;
typedef action_msgs__msg__GoalStatus rcl_action_goal_status_t;
typedef action_msgs__msg__GoalStatusArray rcl_action_goal_status_array_t;
typedef struct rcl_action_goal_status_array_t
{
action_msgs__msg__GoalStatusArray msg;
/// Allocator used to initialize this struct.
rcl_allocator_t allocator;
} rcl_action_goal_status_array_t;
typedef action_msgs__srv__CancelGoal_Request rcl_action_cancel_request_t;
typedef action_msgs__srv__CancelGoal_Response rcl_action_cancel_response_t;
typedef struct rcl_action_cancel_response_t
{
action_msgs__srv__CancelGoal_Response msg;
/// Allocator used to initialize this struct.
rcl_allocator_t allocator;
} rcl_action_cancel_response_t;
/// Goal states
// TODO(jacobperron): Let states be defined by action_msgs/msg/goal_status.h
@ -192,7 +202,6 @@ rcl_action_goal_status_array_init(
* Lock-Free | Yes
*
* \param[inout] status_array the goal status array message to be deinitialized
* \param[in] allocator handle to the allocator used to create the goal status array
* \return `RCL_RET_OK` if the goal status array was deinitialized successfully, or
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
* \return `RCL_RET_ERROR` if an unspecified error occurs.
@ -200,9 +209,7 @@ rcl_action_goal_status_array_init(
RCL_ACTION_PUBLIC
RCL_WARN_UNUSED
rcl_ret_t
rcl_action_goal_status_array_fini(
rcl_action_goal_status_array_t * status_array,
const rcl_allocator_t allocator);
rcl_action_goal_status_array_fini(rcl_action_goal_status_array_t * status_array);
/// Initialize a rcl_action_cancel_response_t.
/**
@ -238,7 +245,7 @@ rcl_action_goal_status_array_fini(
*
* \param[out] cancel_response a preallocated, zero-initialized, cancel response message
* to be initialized.
* \param[in] num_goals_canceling the number of goals that are canceling to add to the response.
* \param[in] num_goals_canceling the number of goals that are canceling to add to the response
* Must be greater than zero
* \param[in] allocator a valid allocator
* \return `RCL_RET_OK` if cancel response was initialized successfully, or
@ -268,7 +275,6 @@ rcl_action_cancel_response_init(
* Lock-Free | Yes
*
* \param[inout] cancel_response the cancel response message to be deinitialized
* \param[in] allocator handle to the allocator used to create the cancel response
* \return `RCL_RET_OK` if the cancel response was deinitialized successfully, or
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
* \return `RCL_RET_ERROR` if an unspecified error occurs.
@ -276,9 +282,7 @@ rcl_action_cancel_response_init(
RCL_ACTION_PUBLIC
RCL_WARN_UNUSED
rcl_ret_t
rcl_action_cancel_response_fini(
rcl_action_cancel_response_t * cancel_response,
const rcl_allocator_t allocator);
rcl_action_cancel_response_fini(rcl_action_cancel_response_t * cancel_response);
#ifdef __cplusplus
}

View file

@ -30,7 +30,7 @@ rcl_action_get_zero_initialized_goal_info(void)
rcl_action_goal_status_array_t
rcl_action_get_zero_initialized_goal_status_array(void)
{
static rcl_action_goal_status_array_t status_array = {{0, 0, 0}};
static rcl_action_goal_status_array_t status_array = {{{0, 0, 0}}, {0, 0, 0, 0, 0}};
return status_array;
}
@ -44,7 +44,7 @@ rcl_action_get_zero_initialized_cancel_request(void)
rcl_action_cancel_response_t
rcl_action_get_zero_initialized_cancel_response(void)
{
static rcl_action_cancel_response_t response = {{0, 0, 0}};
static rcl_action_cancel_response_t response = {{{0, 0, 0}}, {0, 0, 0, 0, 0}};
return response;
}
@ -62,31 +62,30 @@ rcl_action_goal_status_array_init(
return RCL_RET_INVALID_ARGUMENT;
}
// Ensure status array is zero initialized
if (status_array->status_list.size > 0) {
if (status_array->msg.status_list.size > 0) {
RCL_SET_ERROR_MSG("status_array already inititalized");
return RCL_RET_ALREADY_INIT;
}
// Allocate space for status array
status_array->status_list.data = (rcl_action_goal_status_t *) allocator.zero_allocate(
status_array->msg.status_list.data = (rcl_action_goal_status_t *) allocator.zero_allocate(
num_status, sizeof(rcl_action_goal_status_t), allocator.state);
if (!status_array->status_list.data) {
if (!status_array->msg.status_list.data) {
return RCL_RET_BAD_ALLOC;
}
status_array->status_list.size = num_status;
status_array->msg.status_list.size = num_status;
status_array->allocator = allocator;
return RCL_RET_OK;
}
rcl_ret_t
rcl_action_goal_status_array_fini(
rcl_action_goal_status_array_t * status_array,
const rcl_allocator_t allocator)
rcl_action_goal_status_array_fini(rcl_action_goal_status_array_t * status_array)
{
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(status_array, RCL_RET_INVALID_ARGUMENT);
if (!status_array->status_list.data) {
if (!status_array->msg.status_list.data) {
return RCL_RET_INVALID_ARGUMENT;
}
allocator.deallocate(status_array->status_list.data, allocator.state);
status_array->allocator.deallocate(
status_array->msg.status_list.data, status_array->allocator.state);
return RCL_RET_OK;
}
@ -104,31 +103,30 @@ rcl_action_cancel_response_init(
return RCL_RET_INVALID_ARGUMENT;
}
// Ensure cancel response is zero initialized
if (cancel_response->goals_canceling.size > 0) {
if (cancel_response->msg.goals_canceling.size > 0) {
RCL_SET_ERROR_MSG("cancel_response already inititalized");
return RCL_RET_ALREADY_INIT;
}
// Allocate space for cancel response
cancel_response->goals_canceling.data = (rcl_action_goal_info_t *) allocator.zero_allocate(
cancel_response->msg.goals_canceling.data = (rcl_action_goal_info_t *) allocator.zero_allocate(
num_goals_canceling, sizeof(rcl_action_goal_info_t), allocator.state);
if (!cancel_response->goals_canceling.data) {
if (!cancel_response->msg.goals_canceling.data) {
return RCL_RET_BAD_ALLOC;
}
cancel_response->goals_canceling.size = num_goals_canceling;
cancel_response->msg.goals_canceling.size = num_goals_canceling;
cancel_response->allocator = allocator;
return RCL_RET_OK;
}
rcl_ret_t
rcl_action_cancel_response_fini(
rcl_action_cancel_response_t * cancel_response,
const rcl_allocator_t allocator)
rcl_action_cancel_response_fini(rcl_action_cancel_response_t * cancel_response)
{
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(cancel_response, RCL_RET_INVALID_ARGUMENT);
if (!cancel_response->goals_canceling.data) {
if (!cancel_response->msg.goals_canceling.data) {
return RCL_RET_INVALID_ARGUMENT;
}
allocator.deallocate(cancel_response->goals_canceling.data, allocator.state);
cancel_response->allocator.deallocate(
cancel_response->msg.goals_canceling.data, cancel_response->allocator.state);
return RCL_RET_OK;
}

View file

@ -47,8 +47,8 @@ TEST(TestActionTypes, test_get_zero_initialized_goal_status_array)
{
rcl_action_goal_status_array_t status_array =
rcl_action_get_zero_initialized_goal_status_array();
EXPECT_EQ(status_array.status_list.size, 0u);
EXPECT_EQ(status_array.status_list.data, nullptr);
EXPECT_EQ(status_array.msg.status_list.size, 0u);
EXPECT_EQ(status_array.msg.status_list.data, nullptr);
}
TEST(TestActionTypes, test_get_zero_inititalized_cancel_request)
@ -65,8 +65,8 @@ TEST(TestActionTypes, test_get_zero_inititalized_cancel_request)
TEST(TestActionTypes, test_get_zero_initialized_cancel_response)
{
rcl_action_cancel_response_t cancel_response = rcl_action_get_zero_initialized_cancel_response();
EXPECT_EQ(cancel_response.goals_canceling.size, 0u);
EXPECT_EQ(cancel_response.goals_canceling.data, nullptr);
EXPECT_EQ(cancel_response.msg.goals_canceling.size, 0u);
EXPECT_EQ(cancel_response.msg.goals_canceling.data, nullptr);
}
TEST(TestActionTypes, test_init_fini_goal_status_array)
@ -84,38 +84,33 @@ TEST(TestActionTypes, test_init_fini_goal_status_array)
invalid_allocator.allocate = nullptr;
rcl_action_goal_status_array_t status_array =
rcl_action_get_zero_initialized_goal_status_array();
ASSERT_EQ(status_array.status_list.size, 0u);
ASSERT_EQ(status_array.msg.status_list.size, 0u);
ret = rcl_action_goal_status_array_init(&status_array, num_status, invalid_allocator);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT);
EXPECT_EQ(status_array.status_list.size, 0u);
EXPECT_EQ(status_array.status_list.data, nullptr);
EXPECT_EQ(status_array.msg.status_list.size, 0u);
EXPECT_EQ(status_array.msg.status_list.data, nullptr);
// Initialize with zero size
status_array = rcl_action_get_zero_initialized_goal_status_array();
ASSERT_EQ(status_array.status_list.size, 0u);
ASSERT_EQ(status_array.msg.status_list.size, 0u);
ret = rcl_action_goal_status_array_init(&status_array, 0, rcl_get_default_allocator());
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT);
EXPECT_EQ(status_array.status_list.size, 0u);
EXPECT_EQ(status_array.status_list.data, nullptr);
EXPECT_EQ(status_array.msg.status_list.size, 0u);
EXPECT_EQ(status_array.msg.status_list.data, nullptr);
// Initialize with valid arguments
status_array = rcl_action_get_zero_initialized_goal_status_array();
ASSERT_EQ(status_array.status_list.size, 0u);
ASSERT_EQ(status_array.msg.status_list.size, 0u);
ret = rcl_action_goal_status_array_init(&status_array, num_status, rcl_get_default_allocator());
EXPECT_EQ(ret, RCL_RET_OK);
EXPECT_EQ(status_array.status_list.size, num_status);
EXPECT_NE(status_array.status_list.data, nullptr);
EXPECT_EQ(status_array.msg.status_list.size, num_status);
EXPECT_NE(status_array.msg.status_list.data, nullptr);
// Finalize with invalid status array
ret = rcl_action_goal_status_array_fini(nullptr, rcl_get_default_allocator());
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT);
// Finalize with invalid allocator
ret = rcl_action_goal_status_array_fini(&status_array, invalid_allocator);
ret = rcl_action_goal_status_array_fini(nullptr);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT);
// Finalize with valid arguments
ret = rcl_action_goal_status_array_fini(&status_array, rcl_get_default_allocator());
ret = rcl_action_goal_status_array_fini(&status_array);
EXPECT_EQ(ret, RCL_RET_OK);
}
@ -133,40 +128,36 @@ TEST(TestActionTypes, test_init_fini_cancel_response)
rcl_allocator_t invalid_allocator = rcl_get_default_allocator();
invalid_allocator.allocate = nullptr;
rcl_action_cancel_response_t cancel_response = rcl_action_get_zero_initialized_cancel_response();
ASSERT_EQ(cancel_response.goals_canceling.size, 0u);
ASSERT_EQ(cancel_response.msg.goals_canceling.size, 0u);
ret = rcl_action_cancel_response_init(&cancel_response, num_goals_canceling, invalid_allocator);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT);
EXPECT_EQ(cancel_response.goals_canceling.size, 0u);
EXPECT_EQ(cancel_response.goals_canceling.data, nullptr);
EXPECT_EQ(cancel_response.msg.goals_canceling.size, 0u);
EXPECT_EQ(cancel_response.msg.goals_canceling.data, nullptr);
// Initialize with zero size
cancel_response = rcl_action_get_zero_initialized_cancel_response();
ASSERT_EQ(cancel_response.goals_canceling.size, 0u);
ASSERT_EQ(cancel_response.msg.goals_canceling.size, 0u);
ret = rcl_action_cancel_response_init(&cancel_response, 0, rcl_get_default_allocator());
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT);
EXPECT_EQ(cancel_response.goals_canceling.size, 0u);
EXPECT_EQ(cancel_response.goals_canceling.data, nullptr);
EXPECT_EQ(cancel_response.msg.goals_canceling.size, 0u);
EXPECT_EQ(cancel_response.msg.goals_canceling.data, nullptr);
// Initialize with valid arguments
cancel_response = rcl_action_get_zero_initialized_cancel_response();
ASSERT_EQ(cancel_response.goals_canceling.size, 0u);
ASSERT_EQ(cancel_response.msg.goals_canceling.size, 0u);
ret = rcl_action_cancel_response_init(
&cancel_response,
num_goals_canceling,
rcl_get_default_allocator());
EXPECT_EQ(ret, RCL_RET_OK);
EXPECT_EQ(cancel_response.goals_canceling.size, num_goals_canceling);
EXPECT_NE(cancel_response.goals_canceling.data, nullptr);
EXPECT_EQ(cancel_response.msg.goals_canceling.size, num_goals_canceling);
EXPECT_NE(cancel_response.msg.goals_canceling.data, nullptr);
// Finalize with invalid cancel response
ret = rcl_action_cancel_response_fini(nullptr, rcl_get_default_allocator());
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT);
// Finalize with invalid allocator
ret = rcl_action_cancel_response_fini(&cancel_response, invalid_allocator);
ret = rcl_action_cancel_response_fini(nullptr);
EXPECT_EQ(ret, RCL_RET_INVALID_ARGUMENT);
// Finalize with valid arguments
ret = rcl_action_cancel_response_fini(&cancel_response, rcl_get_default_allocator());
ret = rcl_action_cancel_response_fini(&cancel_response);
EXPECT_EQ(ret, RCL_RET_OK);
}