From 0de31d04830f0b33a3adf4a87e179e0d0d76555b Mon Sep 17 00:00:00 2001 From: Karsten Knese Date: Wed, 27 May 2020 12:03:10 -0700 Subject: [PATCH] transition start and goal states can be null (#662) * transition start and goal states can be null Signed-off-by: Karsten Knese * correct tests Signed-off-by: Karsten Knese --- rcl_lifecycle/src/rcl_lifecycle.c | 10 ---------- rcl_lifecycle/test/test_rcl_lifecycle.cpp | 4 ++-- 2 files changed, 2 insertions(+), 12 deletions(-) diff --git a/rcl_lifecycle/src/rcl_lifecycle.c b/rcl_lifecycle/src/rcl_lifecycle.c index ce6c07628..80a8ff0f6 100644 --- a/rcl_lifecycle/src/rcl_lifecycle.c +++ b/rcl_lifecycle/src/rcl_lifecycle.c @@ -132,16 +132,6 @@ rcl_lifecycle_transition_init( return RCL_RET_ERROR; } - if (!start) { - RCL_SET_ERROR_MSG("start state pointer is null\n"); - return RCL_RET_ERROR; - } - - if (!goal) { - RCL_SET_ERROR_MSG("goal state pointer is null\n"); - return RCL_RET_ERROR; - } - transition->start = start; transition->goal = goal; diff --git a/rcl_lifecycle/test/test_rcl_lifecycle.cpp b/rcl_lifecycle/test/test_rcl_lifecycle.cpp index e429cd881..35a53f76e 100644 --- a/rcl_lifecycle/test/test_rcl_lifecycle.cpp +++ b/rcl_lifecycle/test/test_rcl_lifecycle.cpp @@ -133,12 +133,12 @@ TEST(TestRclLifecycle, lifecycle_transition) { ret = rcl_lifecycle_transition_init( &transition, expected_id, &expected_label[0], nullptr, nullptr, &allocator); - EXPECT_EQ(ret, RCL_RET_ERROR); + EXPECT_EQ(ret, RCL_RET_OK); rcutils_reset_error(); ret = rcl_lifecycle_transition_init( &transition, expected_id, &expected_label[0], start, nullptr, &allocator); - EXPECT_EQ(ret, RCL_RET_ERROR); + EXPECT_EQ(ret, RCL_RET_OK); rcutils_reset_error(); rcl_allocator_t bad_allocator = rcl_get_default_allocator();