Skip to content
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
14 changes: 4 additions & 10 deletions .github/workflows/ci.yml
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
name: CI RCLC
name: CI RCLC Rolling

on:
push:
Expand All @@ -17,14 +17,8 @@ jobs:
matrix:
# os: [ ubuntu-20.04, windows-latest, macOS-latest ]
os: [ ubuntu-20.04 ]
ros_distribution: [ foxy, rolling, dashing ]
ros_distribution: [ rolling ]
include:
- docker_image: ubuntu:bionic
ros_distribution: dashing

- docker_image: ubuntu:focal
ros_distribution: foxy

- docker_image: ubuntu:focal
ros_distribution: rolling
container:
Expand All @@ -42,5 +36,5 @@ jobs:
- uses : ros-tooling/[email protected]
with:
package-name: "rclc rclc_examples rclc_lifecycle"
vcs-repo-file-url: ""
target-ros2-distro: ${{ matrix.ros_distribution }}
vcs-repo-file-url: dependencies.repos
target-ros2-distro: ${{ matrix.ros_distribution }}
4 changes: 4 additions & 0 deletions dependencies.repos
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
- git:
local-name: rcl
uri: https://github.com/ros2/rcl.git
version: master
3 changes: 2 additions & 1 deletion rclc_examples/src/example_lifecycle_node.c
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,8 @@ int main(int argc, const char * argv[])
&lifecycle_node,
&my_node,
&state_machine_,
&allocator);
&allocator,
true);
if (rc != RCL_RET_OK) {
printf("Error in creating lifecycle node.\n");
return -1;
Expand Down
3 changes: 2 additions & 1 deletion rclc_lifecycle/include/rclc_lifecycle/rclc_lifecycle.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,8 @@ rclc_make_node_a_lifecycle_node(
rclc_lifecycle_node_t * lifecycle_node,
rcl_node_t * node,
rcl_lifecycle_state_machine_t * state_machine,
rcl_allocator_t * allocator);
rcl_allocator_t * allocator,
bool enable_communication_interface);

RCLC_LIFECYCLE_PUBLIC
rcl_ret_t
Expand Down
15 changes: 10 additions & 5 deletions rclc_lifecycle/src/rclc_lifecycle/rclc_lifecycle.c
Original file line number Diff line number Diff line change
Expand Up @@ -35,9 +35,15 @@ rclc_make_node_a_lifecycle_node(
rclc_lifecycle_node_t * lifecycle_node,
rcl_node_t * node,
rcl_lifecycle_state_machine_t * state_machine,
rcl_allocator_t * allocator
rcl_allocator_t * allocator,
bool enable_communication_interface
)
{
rcl_lifecycle_state_machine_options_t state_machine_options =
rcl_lifecycle_get_default_state_machine_options();
state_machine_options.enable_com_interface = enable_communication_interface;
state_machine_options.allocator = *allocator;

rcl_ret_t rcl_ret = rcl_lifecycle_state_machine_init(
state_machine,
node,
Expand All @@ -47,8 +53,7 @@ rclc_make_node_a_lifecycle_node(
ROSIDL_GET_SRV_TYPE_SUPPORT(lifecycle_msgs, srv, GetAvailableStates),
ROSIDL_GET_SRV_TYPE_SUPPORT(lifecycle_msgs, srv, GetAvailableTransitions),
ROSIDL_GET_SRV_TYPE_SUPPORT(lifecycle_msgs, srv, GetAvailableTransitions),
true,
allocator);
&state_machine_options);
if (rcl_ret != RCL_RET_OK) {
// state machine not initialized, return uninitilized
// @todo(anordman): how/what to return in this case?
Expand Down Expand Up @@ -228,12 +233,12 @@ rcl_lifecycle_node_fini(
)
{
rcl_ret_t rcl_ret = RCL_RET_OK;
RCLC_UNUSED(allocator);

// Cleanup statemachine
rcl_ret = rcl_lifecycle_state_machine_fini(
lifecycle_node->state_machine,
lifecycle_node->node,
allocator);
lifecycle_node->node);
if (rcl_ret != RCL_RET_OK) {
return RCL_RET_ERROR;
}
Expand Down
9 changes: 6 additions & 3 deletions rclc_lifecycle/test/test_lifecycle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,8 @@ TEST(TestRclcLifecycle, lifecycle_node) {
&lifecycle_node,
&my_node,
&state_machine_,
&allocator);
&allocator,
true);

EXPECT_EQ(RCL_RET_OK, res);

Expand Down Expand Up @@ -107,7 +108,8 @@ TEST(TestRclcLifecycle, lifecycle_node_transitions) {
&lifecycle_node,
&my_node,
&state_machine_,
&allocator);
&allocator,
false);

// configure
res = rclc_lifecycle_change_state(
Expand Down Expand Up @@ -176,7 +178,8 @@ TEST(TestRclcLifecycle, lifecycle_node_callbacks) {
&lifecycle_node,
&my_node,
&state_machine_,
&allocator);
&allocator,
true);

// register callbacks
rclc_lifecycle_register_on_configure(&lifecycle_node, &callback_mockup_0);
Expand Down