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

Create service context in main #224

Merged
merged 2 commits into from
Dec 14, 2021
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
8 changes: 5 additions & 3 deletions rclc_examples/src/example_lifecycle_node.c
Original file line number Diff line number Diff line change
Expand Up @@ -108,9 +108,11 @@ int main(int argc, const char * argv[])

// Register lifecycle services
printf("registering lifecycle services...\n");
RCCHECK(rclc_lifecycle_init_get_state_server(&lifecycle_node, &executor));
RCCHECK(rclc_lifecycle_init_get_available_states_server(&lifecycle_node, &executor));
RCCHECK(rclc_lifecycle_init_change_state_server(&lifecycle_node, &executor));
rclc_lifecycle_service_context_t context;
context.lifecycle_node = &lifecycle_node;
RCCHECK(rclc_lifecycle_init_get_state_server(&context, &executor));
RCCHECK(rclc_lifecycle_init_get_available_states_server(&context, &executor));
RCCHECK(rclc_lifecycle_init_change_state_server(&context, &executor));

// Register lifecycle service callbacks
printf("registering callbacks...\n");
Expand Down
6 changes: 3 additions & 3 deletions rclc_lifecycle/include/rclc_lifecycle/rclc_lifecycle.h
Original file line number Diff line number Diff line change
Expand Up @@ -62,19 +62,19 @@ typedef struct rclc_lifecycle_service_context_t
RCLC_LIFECYCLE_PUBLIC
rcl_ret_t
rclc_lifecycle_init_get_state_server(
rclc_lifecycle_node_t * lifecycle_node,
rclc_lifecycle_service_context_t * context,
rclc_executor_t * executor);

RCLC_LIFECYCLE_PUBLIC
rcl_ret_t
rclc_lifecycle_init_get_available_states_server(
rclc_lifecycle_node_t * lifecycle_node,
rclc_lifecycle_service_context_t * context,
rclc_executor_t * executor);

RCLC_LIFECYCLE_PUBLIC
rcl_ret_t
rclc_lifecycle_init_change_state_server(
rclc_lifecycle_node_t * lifecycle_node,
rclc_lifecycle_service_context_t * context,
rclc_executor_t * executor);

RCLC_LIFECYCLE_PUBLIC
Expand Down
46 changes: 17 additions & 29 deletions rclc_lifecycle/src/rclc_lifecycle/rclc_lifecycle.c
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,7 @@ rclc_make_node_a_lifecycle_node(
allocator, "allocator is a null pointer", return RCL_RET_INVALID_ARGUMENT);

lifecycle_node->node = node;
lifecycle_node->publish_transitions = enable_communication_interface;

rcl_lifecycle_state_machine_options_t state_machine_options =
rcl_lifecycle_get_default_state_machine_options();
Expand Down Expand Up @@ -334,23 +335,21 @@ rclc_lifecycle_execute_callback(

rcl_ret_t
rclc_lifecycle_init_get_state_server(
rclc_lifecycle_node_t * lifecycle_node,
rclc_lifecycle_service_context_t * context,
rclc_executor_t * executor)
{
RCL_CHECK_FOR_NULL_WITH_MSG(
lifecycle_node, "lifecycle_node is a null pointer", return RCL_RET_INVALID_ARGUMENT);
context, "context is a null pointer", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_FOR_NULL_WITH_MSG(
executor, "executor is a null pointer", return RCL_RET_INVALID_ARGUMENT);
rclc_lifecycle_service_context_t context;
context.lifecycle_node = lifecycle_node;

rcl_ret_t rc = rclc_executor_add_service_with_context(
executor,
&lifecycle_node->state_machine->com_interface.srv_get_state,
&lifecycle_node->gs_req,
&lifecycle_node->gs_res,
&context->lifecycle_node->state_machine->com_interface.srv_get_state,
&context->lifecycle_node->gs_req,
&context->lifecycle_node->gs_res,
rclc_lifecycle_get_state_callback,
&context);
context);
if (rc != RCL_RET_OK) {
PRINT_RCLC_ERROR(main, rclc_executor_add_service_with_context);
return RCL_RET_ERROR;
Expand Down Expand Up @@ -387,24 +386,19 @@ rclc_lifecycle_get_state_callback(

rcl_ret_t
rclc_lifecycle_init_get_available_states_server(
rclc_lifecycle_node_t * lifecycle_node,
rclc_lifecycle_service_context_t * context,
rclc_executor_t * executor)
{
RCL_CHECK_FOR_NULL_WITH_MSG(
lifecycle_node, "lifecycle_node is a null pointer", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_FOR_NULL_WITH_MSG(
executor, "executor is a null pointer", return RCL_RET_INVALID_ARGUMENT);

rclc_lifecycle_service_context_t context;
context.lifecycle_node = lifecycle_node;

rcl_ret_t rc = rclc_executor_add_service_with_context(
executor,
&lifecycle_node->state_machine->com_interface.srv_get_available_states,
&lifecycle_node->gas_req,
&lifecycle_node->gas_res,
&context->lifecycle_node->state_machine->com_interface.srv_get_available_states,
&context->lifecycle_node->gas_req,
&context->lifecycle_node->gas_res,
rclc_lifecycle_get_available_states_callback,
&context);
context);
if (rc != RCL_RET_OK) {
PRINT_RCLC_ERROR(main, rclc_executor_add_service_with_context);
return RCL_RET_ERROR;
Expand Down Expand Up @@ -446,22 +440,16 @@ rclc_lifecycle_get_available_states_callback(

rcl_ret_t
rclc_lifecycle_init_change_state_server(
rclc_lifecycle_node_t * lifecycle_node,
rclc_lifecycle_service_context_t * context,
rclc_executor_t * executor)
{
RCL_CHECK_FOR_NULL_WITH_MSG(
lifecycle_node, "lifecycle_node is a null pointer", return RCL_RET_INVALID_ARGUMENT);

rclc_lifecycle_service_context_t context;
context.lifecycle_node = lifecycle_node;

rcl_ret_t rc = rclc_executor_add_service_with_context(
executor,
&lifecycle_node->state_machine->com_interface.srv_change_state,
&lifecycle_node->cs_req,
&lifecycle_node->cs_res,
&context->lifecycle_node->state_machine->com_interface.srv_change_state,
&context->lifecycle_node->cs_req,
&context->lifecycle_node->cs_res,
rclc_lifecycle_change_state_callback,
&context);
context);
if (rc != RCL_RET_OK) {
PRINT_RCLC_ERROR(main, rclc_executor_add_service_with_context);
return RCL_RET_ERROR;
Expand Down
13 changes: 8 additions & 5 deletions rclc_lifecycle/test/test_lifecycle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -252,6 +252,9 @@ TEST(TestRclcLifecycle, lifecycle_node_servers) {
rclc_lifecycle_register_on_deactivate(&lifecycle_node, &callback_mockup_2);
rclc_lifecycle_register_on_cleanup(&lifecycle_node, &callback_mockup_3);

rclc_lifecycle_service_context_t lcontext;
lcontext.lifecycle_node = &lifecycle_node;

// create lifecycle servers
rclc_executor_t executor;
res = rclc_executor_init(
Expand All @@ -262,9 +265,9 @@ TEST(TestRclcLifecycle, lifecycle_node_servers) {
EXPECT_EQ(RCL_RET_OK, res);

// Too little executor handles
res = rclc_lifecycle_init_get_state_server(&lifecycle_node, &executor);
res = rclc_lifecycle_init_get_state_server(&lcontext, &executor);
EXPECT_EQ(RCL_RET_OK, res);
res = rclc_lifecycle_init_get_available_states_server(&lifecycle_node, &executor);
res = rclc_lifecycle_init_get_available_states_server(&lcontext, &executor);
EXPECT_EQ(RCL_RET_ERROR, res);

// Now with correct number of handles
Expand All @@ -273,11 +276,11 @@ TEST(TestRclcLifecycle, lifecycle_node_servers) {
&context,
3, // 1 for each lifecycle service
&allocator);
res = rclc_lifecycle_init_get_state_server(&lifecycle_node, &executor);
res = rclc_lifecycle_init_get_state_server(&lcontext, &executor);
EXPECT_EQ(RCL_RET_OK, res);
res = rclc_lifecycle_init_get_available_states_server(&lifecycle_node, &executor);
res = rclc_lifecycle_init_get_available_states_server(&lcontext, &executor);
EXPECT_EQ(RCL_RET_OK, res);
res = rclc_lifecycle_init_change_state_server(&lifecycle_node, &executor);
res = rclc_lifecycle_init_change_state_server(&lcontext, &executor);
EXPECT_EQ(RCL_RET_OK, res);

// Cleanup
Expand Down