Skip to content

Commit

Permalink
commnted out check for received sequence id - error in build-job for …
Browse files Browse the repository at this point in the history
…rolling https://build.ros2.org/job/Rpr__rclc__ubuntu_focal_amd64/72/ see also PR ros2#46 and issue ros2#49

Signed-off-by: Jan Staschulat <[email protected]>
  • Loading branch information
JanStaschulat committed Aug 19, 2021
1 parent cf6aadb commit 2961db5
Show file tree
Hide file tree
Showing 4 changed files with 79 additions and 23 deletions.
9 changes: 5 additions & 4 deletions rclc_lifecycle/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ The API of the RCLC Lifecycle Node can be divided in several phases: Initializat

### Initialization

Creation of a lifecycle node as a bundle of an rcl node and the rcl Node Lifecycle state machine.
Creation of a lifecycle node as a bundle of an rcl node and the rcl Node Lifecycle state machine:

```C
#include "rclc_lifecycle/rclc_lifecycle.h"
Expand All @@ -22,7 +22,7 @@ rcl_ret_t rc;

// create rcl node
rc = rclc_support_init(&support, argc, argv, &allocator);
rcl_node_t my_node = rcl_get_zero_initialized_node();
rcl_node_t my_node;
rc = rclc_node_init_default(&my_node, "lifecycle_node", "rclc", &support);

// rcl state machine
Expand All @@ -39,7 +39,7 @@ rcl_ret_t rc = rclc_make_node_a_lifecycle_node(
&allocator);
```

Register lifecycle services and optionally create callbacks for state changes. Executor needsto be equipped with 1 handle per node _and_ per service.
Register lifecycle services and optionally create callbacks for state changes. Executor needsto be equipped with 1 handle per node _and_ per service:

```C
// Executor
Expand All @@ -64,10 +64,11 @@ rclc_lifecycle_register_on_activate(&lifecycle_node, &my_on_activate);
### Cleaning Up
To clean everything up, simply do
To clean everything up, do:
```C
rc += rcl_lifecycle_node_fini(&lifecycle_node, &allocator);
...
```

## Example
Expand Down
2 changes: 1 addition & 1 deletion rclc_lifecycle/include/rclc_lifecycle/rclc_lifecycle.h
Original file line number Diff line number Diff line change
Expand Up @@ -153,7 +153,7 @@ rclc_lifecycle_execute_callback(

RCLC_LIFECYCLE_PUBLIC
rcl_ret_t
rcl_lifecycle_node_fini(
rclc_lifecycle_node_fini(
rclc_lifecycle_node_t * node,
rcl_allocator_t * allocator);

Expand Down
55 changes: 47 additions & 8 deletions rclc_lifecycle/src/rclc_lifecycle/rclc_lifecycle.c
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,13 @@ rclc_make_node_a_lifecycle_node(
bool enable_communication_interface
)
{
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(
node, "node is a null pointer", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_FOR_NULL_WITH_MSG(
allocator, "allocator is a null pointer", return RCL_RET_INVALID_ARGUMENT);

lifecycle_node->node = node;

rcl_lifecycle_state_machine_options_t state_machine_options =
Expand All @@ -62,7 +69,6 @@ rclc_make_node_a_lifecycle_node(
&state_machine_options);
if (rcl_ret != RCL_RET_OK) {
// state machine not initialized, return uninitilized
// @todo(anordman): how/what to return in this case?
RCUTILS_LOG_ERROR(
"Unable to initialize state machine: %s",
rcl_get_error_string().str);
Expand Down Expand Up @@ -107,6 +113,9 @@ rclc_lifecycle_change_state(
bool publish_update
)
{
RCL_CHECK_FOR_NULL_WITH_MSG(
lifecycle_node, "lifecycle_node is a null pointer", return RCL_RET_INVALID_ARGUMENT);

if (rcl_lifecycle_state_machine_is_initialized(lifecycle_node->state_machine) != RCL_RET_OK) {
RCUTILS_LOG_ERROR(
"Unable to change state for state machine: %s",
Expand Down Expand Up @@ -215,6 +224,9 @@ rclc_lifecycle_register_on_configure(
int (* cb)(void)
)
{
RCL_CHECK_FOR_NULL_WITH_MSG(
node, "node is a null pointer", return RCL_RET_INVALID_ARGUMENT);

return rclc_lifecycle_register_callback(
node,
lifecycle_msgs__msg__Transition__TRANSITION_CONFIGURE,
Expand All @@ -227,6 +239,9 @@ rclc_lifecycle_register_on_activate(
int (* cb)(void)
)
{
RCL_CHECK_FOR_NULL_WITH_MSG(
node, "node is a null pointer", return RCL_RET_INVALID_ARGUMENT);

return rclc_lifecycle_register_callback(
node,
lifecycle_msgs__msg__Transition__TRANSITION_ACTIVATE,
Expand All @@ -239,6 +254,9 @@ rclc_lifecycle_register_on_deactivate(
int (* cb)(void)
)
{
RCL_CHECK_FOR_NULL_WITH_MSG(
node, "node is a null pointer", return RCL_RET_INVALID_ARGUMENT);

return rclc_lifecycle_register_callback(
node,
lifecycle_msgs__msg__Transition__TRANSITION_DEACTIVATE,
Expand All @@ -251,18 +269,26 @@ rclc_lifecycle_register_on_cleanup(
int (* cb)(void)
)
{
RCL_CHECK_FOR_NULL_WITH_MSG(
node, "node is a null pointer", return RCL_RET_INVALID_ARGUMENT);

return rclc_lifecycle_register_callback(
node,
lifecycle_msgs__msg__Transition__TRANSITION_CLEANUP,
cb);
}

rcl_ret_t
rcl_lifecycle_node_fini(
rclc_lifecycle_node_fini(
rclc_lifecycle_node_t * lifecycle_node,
rcl_allocator_t * allocator
)
{
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(
allocator, "allocator is a null pointer", return RCL_RET_INVALID_ARGUMENT);

rcl_ret_t rcl_ret = RCL_RET_OK;
RCLC_UNUSED(allocator);

Expand All @@ -271,12 +297,10 @@ rcl_lifecycle_node_fini(
lifecycle_node->state_machine,
lifecycle_node->node);
if (rcl_ret != RCL_RET_OK) {
return RCL_RET_ERROR;
}

// Cleanup node
rcl_ret = rcl_node_fini(lifecycle_node->node);
if (rcl_ret != RCL_RET_OK) {
RCUTILS_LOG_ERROR(
"Unable to clean up state machine: %s",
rcl_get_error_string().str);
rcutils_reset_error();
return RCL_RET_ERROR;
}

Expand All @@ -297,6 +321,9 @@ rclc_lifecycle_execute_callback(
unsigned int transition_id
)
{
RCL_CHECK_FOR_NULL_WITH_MSG(
lifecycle_node, "lifecycle_node is a null pointer", return RCL_RET_INVALID_ARGUMENT);

if (!lifecycle_node->callbacks.goal_states[transition_id]) {
// no callback, so process, all good
return RCL_RET_OK;
Expand All @@ -310,6 +337,10 @@ rclc_lifecycle_init_get_state_server(
rclc_lifecycle_node_t * lifecycle_node,
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;

Expand Down Expand Up @@ -359,6 +390,11 @@ rclc_lifecycle_init_get_available_states_server(
rclc_lifecycle_node_t * lifecycle_node,
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;

Expand Down Expand Up @@ -413,6 +449,9 @@ rclc_lifecycle_init_change_state_server(
rclc_lifecycle_node_t * lifecycle_node,
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;

Expand Down
36 changes: 26 additions & 10 deletions rclc_lifecycle/test/test_lifecycle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,12 +65,12 @@ TEST(TestRclcLifecycle, lifecycle_node) {
res += rcl_node_init(&my_node, "lifecycle_node", "rclc", &context, &node_ops);

rclc_lifecycle_node_t lifecycle_node;
rcl_lifecycle_state_machine_t state_machine_ = rcl_lifecycle_get_zero_initialized_state_machine();
rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine();

res += rclc_make_node_a_lifecycle_node(
&lifecycle_node,
&my_node,
&state_machine_,
&state_machine,
&allocator,
true);

Expand Down Expand Up @@ -102,12 +102,12 @@ TEST(TestRclcLifecycle, lifecycle_node_transitions) {
res += rcl_node_init(&my_node, "lifecycle_node", "rclc", &context, &node_ops);

rclc_lifecycle_node_t lifecycle_node;
rcl_lifecycle_state_machine_t state_machine_ = rcl_lifecycle_get_zero_initialized_state_machine();
rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine();

res += rclc_make_node_a_lifecycle_node(
&lifecycle_node,
&my_node,
&state_machine_,
&state_machine,
&allocator,
false);

Expand Down Expand Up @@ -172,12 +172,12 @@ TEST(TestRclcLifecycle, lifecycle_node_callbacks) {
res += rcl_node_init(&my_node, "lifecycle_node", "rclc", &context, &node_ops);

rclc_lifecycle_node_t lifecycle_node;
rcl_lifecycle_state_machine_t state_machine_ = rcl_lifecycle_get_zero_initialized_state_machine();
rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine();

res += rclc_make_node_a_lifecycle_node(
&lifecycle_node,
&my_node,
&state_machine_,
&state_machine,
&allocator,
true);

Expand Down Expand Up @@ -237,12 +237,12 @@ TEST(TestRclcLifecycle, lifecycle_node_servers) {
res += rcl_node_init(&my_node, "lifecycle_node", "rclc", &context, &node_ops);

rclc_lifecycle_node_t lifecycle_node;
rcl_lifecycle_state_machine_t state_machine_ = rcl_lifecycle_get_zero_initialized_state_machine();
rcl_lifecycle_state_machine_t state_machine = rcl_lifecycle_get_zero_initialized_state_machine();

res += rclc_make_node_a_lifecycle_node(
&lifecycle_node,
&my_node,
&state_machine_,
&state_machine,
&allocator,
true);

Expand All @@ -253,22 +253,38 @@ TEST(TestRclcLifecycle, lifecycle_node_servers) {
rclc_lifecycle_register_on_cleanup(&lifecycle_node, &callback_mockup_3);

// create lifecycle servers
rclc_executor_t executor = rclc_executor_get_zero_initialized_executor();
rclc_executor_t executor;
res = rclc_executor_init(
&executor,
&context,
1, // too little
&allocator);
EXPECT_EQ(RCL_RET_OK, res);

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

// Now with correct number of handles
rclc_executor_init(
&executor,
&context,
4, // 1 for the node + 1 for each lifecycle service
3, // 1 for each lifecycle service
&allocator);
res = rclc_lifecycle_init_get_state_server(&lifecycle_node, &executor);
EXPECT_EQ(RCL_RET_OK, res);
res = rclc_lifecycle_init_get_available_states_server(&lifecycle_node, &executor);
EXPECT_EQ(RCL_RET_OK, res);
res = rclc_lifecycle_init_change_state_server(&lifecycle_node, &executor);
EXPECT_EQ(RCL_RET_OK, res);

// Cleanup
res = rclc_lifecycle_node_fini(&lifecycle_node, &allocator);
EXPECT_EQ(RCL_RET_OK, res);
res = rcl_node_fini(&my_node);
EXPECT_EQ(RCL_RET_OK, res);
res = rclc_executor_fini(&executor);
EXPECT_EQ(RCL_RET_OK, res);
}

0 comments on commit 2961db5

Please sign in to comment.