Skip to content
Open
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
1 change: 1 addition & 0 deletions rclc_examples/src/example_lifecycle_node.c
Original file line number Diff line number Diff line change
Expand Up @@ -87,6 +87,7 @@ int main(int argc, const char * argv[])
rc = rclc_make_node_a_lifecycle_node(
&lifecycle_node,
&my_node,
&support.clock,
&state_machine_,
&allocator,
true);
Expand Down
1 change: 1 addition & 0 deletions rclc_lifecycle/include/rclc_lifecycle/rclc_lifecycle.h
Original file line number Diff line number Diff line change
Expand Up @@ -108,6 +108,7 @@ rcl_ret_t
rclc_make_node_a_lifecycle_node(
rclc_lifecycle_node_t * lifecycle_node,
rcl_node_t * node,
rcl_clock_t * clock,
rcl_lifecycle_state_machine_t * state_machine,
rcl_allocator_t * allocator,
bool enable_communication_interface);
Expand Down
4 changes: 4 additions & 0 deletions rclc_lifecycle/src/rclc_lifecycle/rclc_lifecycle.c
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ rcl_ret_t
rclc_make_node_a_lifecycle_node(
rclc_lifecycle_node_t * lifecycle_node,
rcl_node_t * node,
rcl_clock_t * clock,
rcl_lifecycle_state_machine_t * state_machine,
rcl_allocator_t * allocator,
bool enable_communication_interface
Expand All @@ -47,6 +48,8 @@ rclc_make_node_a_lifecycle_node(
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(
clock, "clock 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);

Expand All @@ -61,6 +64,7 @@ rclc_make_node_a_lifecycle_node(
rcl_ret_t rcl_ret = rcl_lifecycle_state_machine_init(
state_machine,
node,
clock,
ROSIDL_GET_MSG_TYPE_SUPPORT(lifecycle_msgs, msg, TransitionEvent),
ROSIDL_GET_SRV_TYPE_SUPPORT(lifecycle_msgs, srv, ChangeState),
ROSIDL_GET_SRV_TYPE_SUPPORT(lifecycle_msgs, srv, GetState),
Expand Down
24 changes: 24 additions & 0 deletions rclc_lifecycle/test/test_lifecycle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,12 +64,16 @@ TEST(TestRclcLifecycle, lifecycle_node) {
rcl_node_options_t node_ops = rcl_node_get_default_options();
res += rcl_node_init(&my_node, "lifecycle_node", "rclc", &context, &node_ops);

rcl_clock_t my_clock;
res += rcl_clock_init(RCL_SYSTEM_TIME, &my_clock, &allocator);

rclc_lifecycle_node_t lifecycle_node;
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,
&my_clock,
&state_machine,
&allocator,
true);
Expand All @@ -81,6 +85,8 @@ TEST(TestRclcLifecycle, lifecycle_node) {
rcl_lifecycle_state_machine_is_initialized(lifecycle_node.state_machine));

// clean up
res = rcl_clock_fini(&my_clock);
EXPECT_EQ(RCL_RET_OK, res);
res = rcl_node_fini(&my_node);
EXPECT_EQ(RCL_RET_OK, res);
res = rcl_node_options_fini(&node_ops);
Expand All @@ -101,12 +107,16 @@ TEST(TestRclcLifecycle, lifecycle_node_transitions) {
rcl_node_options_t node_ops = rcl_node_get_default_options();
res += rcl_node_init(&my_node, "lifecycle_node", "rclc", &context, &node_ops);

rcl_clock_t my_clock;
res += rcl_clock_init(RCL_ROS_TIME, &my_clock, &allocator);

rclc_lifecycle_node_t lifecycle_node;
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,
&my_clock,
&state_machine,
&allocator,
false);
Expand Down Expand Up @@ -151,6 +161,8 @@ TEST(TestRclcLifecycle, lifecycle_node_transitions) {
lifecycle_msgs__msg__State__PRIMARY_STATE_UNCONFIGURED,
lifecycle_node.state_machine->current_state->id);

res = rcl_clock_fini(&my_clock);
EXPECT_EQ(RCL_RET_OK, res);
res = rcl_node_fini(&my_node);
EXPECT_EQ(RCL_RET_OK, res);
res = rcl_node_options_fini(&node_ops);
Expand All @@ -171,12 +183,16 @@ TEST(TestRclcLifecycle, lifecycle_node_callbacks) {
rcl_node_options_t node_ops = rcl_node_get_default_options();
res += rcl_node_init(&my_node, "lifecycle_node", "rclc", &context, &node_ops);

rcl_clock_t my_clock;
res += rcl_clock_init(RCL_ROS_TIME, &my_clock, &allocator);

rclc_lifecycle_node_t lifecycle_node;
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,
&my_clock,
&state_machine,
&allocator,
true);
Expand Down Expand Up @@ -216,6 +232,8 @@ TEST(TestRclcLifecycle, lifecycle_node_callbacks) {
EXPECT_EQ(RCL_RET_OK, res);
EXPECT_EQ(15, callback_mockup_counter);

res = rcl_clock_fini(&my_clock);
EXPECT_EQ(RCL_RET_OK, res);
res = rcl_node_fini(&my_node);
EXPECT_EQ(RCL_RET_OK, res);
res = rcl_node_options_fini(&node_ops);
Expand All @@ -236,12 +254,16 @@ TEST(TestRclcLifecycle, lifecycle_node_servers) {
rcl_node_options_t node_ops = rcl_node_get_default_options();
res += rcl_node_init(&my_node, "lifecycle_node", "rclc", &context, &node_ops);

rcl_clock_t my_clock;
res += rcl_clock_init(RCL_ROS_TIME, &my_clock, &allocator);

rclc_lifecycle_node_t lifecycle_node;
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,
&my_clock,
&state_machine,
&allocator,
true);
Expand Down Expand Up @@ -286,6 +308,8 @@ TEST(TestRclcLifecycle, lifecycle_node_servers) {
// Cleanup
res = rclc_lifecycle_node_fini(&lifecycle_node, &allocator);
EXPECT_EQ(RCL_RET_OK, res);
res = rcl_clock_fini(&my_clock);
EXPECT_EQ(RCL_RET_OK, res);
res = rcl_node_fini(&my_node);
EXPECT_EQ(RCL_RET_OK, res);
res = rclc_executor_fini(&executor);
Expand Down