Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added remapping resolution for action names #1170

Open
wants to merge 6 commits into
base: rolling
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 4 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
36 changes: 30 additions & 6 deletions rcl_action/src/rcl_action/action_client.c
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,7 @@ _rcl_action_client_fini_impl(
{
ret = RCL_RET_ERROR;
}
allocator.deallocate(action_client->impl->action_name, allocator.state);
allocator.deallocate(action_client->impl->remapped_action_name, allocator.state);
allocator.deallocate(action_client->impl, allocator.state);
action_client->impl = NULL;
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Action client finalized");
Expand All @@ -109,7 +109,8 @@ _rcl_action_client_fini_impl(
// \internal Initializes an action client specific service client.
#define CLIENT_INIT(Type) \
char * Type ## _service_name = NULL; \
ret = rcl_action_get_ ## Type ## _service_name(action_name, allocator, &Type ## _service_name); \
ret = rcl_action_get_ ## Type ## _service_name( \
resolved_action_name, allocator, &Type ## _service_name); \
if (RCL_RET_OK != ret) { \
rcl_reset_error(); \
RCL_SET_ERROR_MSG("failed to get " #Type " service name"); \
Expand Down Expand Up @@ -145,7 +146,8 @@ _rcl_action_client_fini_impl(
// \internal Initializes an action client specific topic subscription.
#define SUBSCRIPTION_INIT(Type) \
char * Type ## _topic_name = NULL; \
ret = rcl_action_get_ ## Type ## _topic_name(action_name, allocator, &Type ## _topic_name); \
ret = rcl_action_get_ ## Type ## _topic_name( \
resolved_action_name, allocator, &Type ## _topic_name); \
if (RCL_RET_OK != ret) { \
rcl_reset_error(); \
RCL_SET_ERROR_MSG("failed to get " #Type " topic name"); \
Expand Down Expand Up @@ -212,9 +214,22 @@ rcl_action_client_init(

// Avoid uninitialized pointers should initialization fail
*action_client->impl = _rcl_action_get_zero_initialized_client_impl();

// Remap/Expand the action name
char * resolved_action_name = NULL;
ret = rcl_node_resolve_name(node, action_name, allocator, false, false, &resolved_action_name);
JustusBraun marked this conversation as resolved.
Show resolved Hide resolved
if (RCL_RET_OK != ret) {
if (RCL_RET_TOPIC_NAME_INVALID == ret || RCL_RET_UNKNOWN_SUBSTITUTION == ret) {
ret = RCL_RET_ACTION_NAME_INVALID;
} else if (RCL_RET_BAD_ALLOC != ret) {
ret = RCL_RET_ERROR;
}
goto fail;
JustusBraun marked this conversation as resolved.
Show resolved Hide resolved
}

JustusBraun marked this conversation as resolved.
Show resolved Hide resolved
// Copy action client name and options.
action_client->impl->action_name = rcutils_strdup(action_name, allocator);
if (NULL == action_client->impl->action_name) {
action_client->impl->remapped_action_name = rcutils_strdup(resolved_action_name, allocator);
JustusBraun marked this conversation as resolved.
Show resolved Hide resolved
if (NULL == action_client->impl->remapped_action_name) {
JustusBraun marked this conversation as resolved.
Show resolved Hide resolved
RCL_SET_ERROR_MSG("failed to duplicate action name");
ret = RCL_RET_BAD_ALLOC;
goto fail;
Expand All @@ -230,6 +245,10 @@ rcl_action_client_init(
SUBSCRIPTION_INIT(feedback);
SUBSCRIPTION_INIT(status);

// The resolved action name is no longer needed
allocator.deallocate(resolved_action_name, allocator.state);
resolved_action_name = NULL;

JustusBraun marked this conversation as resolved.
Show resolved Hide resolved
if (RCL_RET_OK != rcl_node_type_cache_register_type(
node, type_support->get_type_hash_func(type_support),
type_support->get_type_description_func(type_support),
Expand All @@ -244,6 +263,11 @@ rcl_action_client_init(
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Action client initialized");
return ret;
fail:
// Deallocate the resolved action name
if (NULL != resolved_action_name) {
allocator.deallocate(resolved_action_name, allocator.state);
}

fini_ret = _rcl_action_client_fini_impl(action_client, node, allocator);
if (RCL_RET_OK != fini_ret) {
RCL_SET_ERROR_MSG("failed to cleanup action client");
Expand Down Expand Up @@ -471,7 +495,7 @@ rcl_action_client_get_action_name(const rcl_action_client_t * action_client)
if (!rcl_action_client_is_valid(action_client)) {
return NULL;
}
return action_client->impl->action_name;
return action_client->impl->remapped_action_name;
}

const rcl_action_client_options_t *
Expand Down
2 changes: 1 addition & 1 deletion rcl_action/src/rcl_action/action_client_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ typedef struct rcl_action_client_impl_s
rcl_subscription_t feedback_subscription;
rcl_subscription_t status_subscription;
rcl_action_client_options_t options;
char * action_name;
char * remapped_action_name;
// Wait set records
size_t wait_set_goal_client_index;
size_t wait_set_cancel_client_index;
Expand Down
40 changes: 31 additions & 9 deletions rcl_action/src/rcl_action/action_server.c
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,8 @@ rcl_action_get_zero_initialized_server(void)

#define SERVICE_INIT(Type) \
char * Type ## _service_name = NULL; \
ret = rcl_action_get_ ## Type ## _service_name(action_name, allocator, &Type ## _service_name); \
ret = rcl_action_get_ ## Type ## _service_name( \
resolved_action_name, allocator, &Type ## _service_name); \
if (RCL_RET_OK != ret) { \
if (RCL_RET_BAD_ALLOC == ret) { \
ret = RCL_RET_BAD_ALLOC; \
Expand Down Expand Up @@ -80,7 +81,8 @@ rcl_action_get_zero_initialized_server(void)

#define PUBLISHER_INIT(Type) \
char * Type ## _topic_name = NULL; \
ret = rcl_action_get_ ## Type ## _topic_name(action_name, allocator, &Type ## _topic_name); \
ret = rcl_action_get_ ## Type ## _topic_name( \
resolved_action_name, allocator, &Type ## _topic_name); \
if (RCL_RET_OK != ret) { \
if (RCL_RET_BAD_ALLOC == ret) { \
ret = RCL_RET_BAD_ALLOC; \
Expand Down Expand Up @@ -155,14 +157,26 @@ rcl_action_server_init(
action_server->impl->expire_timer = rcl_get_zero_initialized_timer();
action_server->impl->feedback_publisher = rcl_get_zero_initialized_publisher();
action_server->impl->status_publisher = rcl_get_zero_initialized_publisher();
action_server->impl->action_name = NULL;
action_server->impl->remapped_action_name = NULL;
action_server->impl->options = *options; // copy options
action_server->impl->goal_handles = NULL;
action_server->impl->num_goal_handles = 0u;
action_server->impl->clock = NULL;
action_server->impl->type_hash = rosidl_get_zero_initialized_type_hash();

rcl_ret_t ret = RCL_RET_OK;
// Resolve action name
char * resolved_action_name = NULL;
ret = rcl_node_resolve_name(node, action_name, allocator, false, false, &resolved_action_name);
if (RCL_RET_OK != ret) {
if (RCL_RET_TOPIC_NAME_INVALID == ret || RCL_RET_UNKNOWN_SUBSTITUTION == ret) {
ret = RCL_RET_ACTION_NAME_INVALID;
} else if (RCL_RET_BAD_ALLOC != ret) {
ret = RCL_RET_ERROR;
}
JustusBraun marked this conversation as resolved.
Show resolved Hide resolved
goto fail;
}

// Initialize services
SERVICE_INIT(goal);
SERVICE_INIT(cancel);
Expand All @@ -189,12 +203,16 @@ rcl_action_server_init(
}

// Copy action name
action_server->impl->action_name = rcutils_strdup(action_name, allocator);
if (NULL == action_server->impl->action_name) {
action_server->impl->remapped_action_name = rcutils_strdup(resolved_action_name, allocator);
if (NULL == action_server->impl->remapped_action_name) {
ret = RCL_RET_BAD_ALLOC;
goto fail;
}

// The resolved_action_name is no longer needed
allocator.deallocate(resolved_action_name, allocator.state);
resolved_action_name = NULL;

// Store type hash
if (RCL_RET_OK != rcl_node_type_cache_register_type(
node, type_support->get_type_hash_func(type_support),
Expand All @@ -210,6 +228,10 @@ rcl_action_server_init(
return ret;
fail:
{
// Deallocate the resolved action name
if (NULL != resolved_action_name) {
allocator.deallocate(resolved_action_name, allocator.state);
}
// Finalize any services/publishers that were initialized and deallocate action_server->impl
rcl_ret_t ret_throwaway = rcl_action_server_fini(action_server, node);
// Since there is already a failure, it is likely that finalize will error on one or more of
Expand Down Expand Up @@ -254,9 +276,9 @@ rcl_action_server_fini(rcl_action_server_t * action_server, rcl_node_t * node)
action_server->impl->clock = NULL;
// Deallocate action name
rcl_allocator_t allocator = action_server->impl->options.allocator;
if (action_server->impl->action_name) {
allocator.deallocate(action_server->impl->action_name, allocator.state);
action_server->impl->action_name = NULL;
if (action_server->impl->remapped_action_name) {
allocator.deallocate(action_server->impl->remapped_action_name, allocator.state);
action_server->impl->remapped_action_name = NULL;
}
// Deallocate goal handles storage, but don't fini them.
for (size_t i = 0; i < action_server->impl->num_goal_handles; ++i) {
Expand Down Expand Up @@ -860,7 +882,7 @@ rcl_action_server_get_action_name(const rcl_action_server_t * action_server)
if (!rcl_action_server_is_valid(action_server)) {
return NULL; // error already set
}
return action_server->impl->action_name;
return action_server->impl->remapped_action_name;
}

const rcl_action_server_options_t *
Expand Down
2 changes: 1 addition & 1 deletion rcl_action/src/rcl_action/action_server_impl.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ typedef struct rcl_action_server_impl_s
rcl_publisher_t feedback_publisher;
rcl_publisher_t status_publisher;
rcl_timer_t expire_timer;
char * action_name;
char * remapped_action_name;
rcl_action_server_options_t options;
// Array of goal handles
rcl_action_goal_handle_t ** goal_handles;
Expand Down
2 changes: 1 addition & 1 deletion rcl_action/test/rcl_action/test_action_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -240,7 +240,7 @@ class TestActionClientFixture : public TestActionClientBaseFixture
TestActionClientBaseFixture::TearDown();
}

const char * const action_name = "test_action_client_name";
const char * const action_name = "/test_action_client_name";
rcl_action_client_options_t action_client_options;
rcl_action_client_t invalid_action_client;
rcl_action_client_t action_client;
Expand Down
2 changes: 1 addition & 1 deletion rcl_action/test/rcl_action/test_action_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -777,7 +777,7 @@ TEST_F(TestActionServer, test_action_server_get_action_name)
// Get action_name for a valid action server
action_name = rcl_action_server_get_action_name(&this->action_server);
ASSERT_NE(action_name, nullptr) << rcl_get_error_string().str;
EXPECT_STREQ(action_name, "test_action_server_name");
EXPECT_STREQ(action_name, "/test_action_server_name");
}

TEST_F(TestActionServer, test_action_server_get_options)
Expand Down