add rclcpp lifecycle

* initial state machine implementation

(fix) correctly initialize default state machine

uncrustify

(dev) first high level api interface

src/default_state_machine.c

(fix) correctly initialize arrays in statemachine

(dev) deactivate/activate publisher demo

(dev) initial state machine implementation in rcl

* (dev) demo application for a managed lifecycle node

* add visibility control

* correct install of c-library

* fix compilation on windows

* refactoring of external/internal api

* (dev) generate static functions for c-callback

* (fix) correct typo

* (dev) cleanup for c-statemachine

(dev) cleanup for c-statemachine

* (dev) cpp callback map

* (dev) mv source file into project folders

* (dev) more helper functions for valid transition

* (dev) pimpl implementation for cpp lifecyclemanager

* (dev) register non-default callback functions

* (dev) cleanup lifecycle node to serve as base class

* (dev) new my_node child of lifecyclenode for demo purpose

update

stuff

(cleanup) remove unused comments

(fix) correct dllexport in windows

(fix) correctly install libraries

(fix) uncrustify

(dev) composition over inheritance

(dev) publish notification in state_machine transition

 (dev) lifecycle talker + listener demo for notification

(dev) custom transition message generation

(dev) publish transition message on state change

(dev) correctly malloc/free c data structures

(fix) use single thread executor

(dev) use services for get state

(fix) set freed pointer to NULL

(dev) add change state service

(dev) introduce services: get_state and change_state in LM

(dev) asynchronous caller script for service client

(fix) correct dllexport for pimpl

(dev) correct constness

(dev) concatenate function for topic

(fix) uncrustify

prepare new service api

(tmp) refactor stash

(fix) correctly concatenate topics

(fix) correctly initialize Service wo/ copy

(dev) call both service types

extract demo files

(fix) remove debug prints

(dev) change to lifecycle_msgs

(refactor) extract rcl_lifecycle package

(refactor) extract lifecycle demos

(fix) address review comments

(fix) address review comments

(fix) pass shared_ptr by value

(fix) make find_package(rmw) required

(fix) return to shared node handle pointer

(refactor) attach sm to lifecycle node and disable lc_manager

(dev) construct service from existing rcl_service_t

(refactor) extract method for adding a service to a node

(fix) stop mock msgs from being installed

service takes rcl_node_t*

correct typo

add_service has to be public

uncrustify

initial state machine implementation

(fix) correctly initialize default state machine

uncrustify

(dev) first high level api interface

src/default_state_machine.c

(fix) correctly initialize arrays in statemachine

(dev) deactivate/activate publisher demo

(dev) initial state machine implementation in rcl

(dev) demo application for a managed lifecycle node

add visibility control

correct install of c-library

fix compilation on windows

refactoring of external/internal api

(dev) generate static functions for c-callback

(fix) correct typo

(dev) cleanup for c-statemachine

(dev) cleanup for c-statemachine

(dev) cpp callback map

(dev) mv source file into project folders

(dev) more helper functions for valid transition

(dev) pimpl implementation for cpp lifecyclemanager

(dev) register non-default callback functions

(dev) cleanup lifecycle node to serve as base class

(dev) new my_node child of lifecyclenode for demo purpose

update

stuff

(cleanup) remove unused comments

(fix) correct dllexport in windows

(fix) correctly install libraries

(fix) uncrustify

(dev) composition over inheritance

(dev) publish notification in state_machine transition

 (dev) lifecycle talker + listener demo for notification

(dev) custom transition message generation

(dev) publish transition message on state change

(dev) correctly malloc/free c data structures

(fix) use single thread executor

(dev) use services for get state

(fix) set freed pointer to NULL

(dev) add change state service

(dev) introduce services: get_state and change_state in LM

(dev) asynchronous caller script for service client

(fix) correct dllexport for pimpl

(dev) correct constness

(dev) concatenate function for topic

(fix) uncrustify

prepare new service api

(tmp) refactor stash

* (dev) construct service from existing rcl_service_t

* service takes rcl_node_t*

* correct typo

* add_service has to be public

* uncrustify

* (fix) correctly concatenate topics

* (fix) correctly initialize Service wo/ copy

* (dev) call both service types

* extract demo files

* (fix) remove debug prints

* (dev) change to lifecycle_msgs

* (refactor) extract rcl_lifecycle package

* (refactor) extract lifecycle demos

* (fix) address review comments

(fix) address review comments

* (fix) make find_package(rmw) required

* (refactor) attach sm to lifecycle node and disable lc_manager

* (fix) adjust code to rcl_test refactor

* (dev) remove unused deps

* (rebase) merge commit

* (bugfix) correct rcl_ret_t error handling

* (fix) depedencies

* (refactor) change to lifecycle_msgs

* (fix) correct find_rcl

* (refactor) comply for new state machine

* visibility control and test api

* (rebase) change to new typesupport

* uncrustify'

* fix visibility control

* (fix) correct whitespace

* (fix) unused variable

* comparison signed and unsigned

* get_state returns complete state

* get_available_states service

* new service msgs

* get available states and transitions api

* (broken) state after rebase, does not compile demos

* fix the way lifecycle node impl is included

* fixed rebase compilation errors

* remove copy&paste comment

* remove empty line

* (test) register custom callbacks

* (dev) return codes

* style

* test for exception handling

* refacotr new state machine

* c++14

* change exception message for windows ci bug

change exception message for windows ci bug
This commit is contained in:
Karsten Knese 2016-12-14 09:29:27 -08:00 committed by GitHub
parent d241a730fe
commit 2c6d95946e
19 changed files with 2712 additions and 0 deletions

View file

@ -0,0 +1,102 @@
// Copyright 2015 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <gtest/gtest.h>
#include <memory>
#include <string>
#include <utility>
#include "lifecycle_msgs/msg/state.hpp"
#include "lifecycle_msgs/msg/transition.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
using lifecycle_msgs::msg::State;
using lifecycle_msgs::msg::Transition;
class TestCallbackExceptions : public ::testing::Test
{
protected:
static void SetUpTestCase()
{
rclcpp::init(0, nullptr);
}
};
class PositiveCallbackExceptionNode : public rclcpp_lifecycle::LifecycleNode
{
public:
explicit PositiveCallbackExceptionNode(std::string node_name)
: rclcpp_lifecycle::LifecycleNode(std::move(node_name))
{}
size_t number_of_callbacks = 0;
protected:
rcl_lifecycle_ret_t on_configure(const rclcpp_lifecycle::State &)
{
++number_of_callbacks;
throw std::runtime_error("custom exception raised in configure callback");
}
rcl_lifecycle_ret_t on_error(const rclcpp_lifecycle::State &)
{
++number_of_callbacks;
return RCL_LIFECYCLE_RET_OK;
}
};
TEST_F(TestCallbackExceptions, positive_on_error) {
auto test_node = std::make_shared<PositiveCallbackExceptionNode>("testnode");
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, test_node->get_current_state().id());
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_CONFIGURE)).id());
// check if all callbacks were successfully overwritten
EXPECT_EQ(static_cast<size_t>(2), test_node->number_of_callbacks);
}
class NegativeCallbackExceptionNode : public rclcpp_lifecycle::LifecycleNode
{
public:
explicit NegativeCallbackExceptionNode(std::string node_name)
: rclcpp_lifecycle::LifecycleNode(std::move(node_name))
{}
size_t number_of_callbacks = 0;
protected:
rcl_lifecycle_ret_t on_configure(const rclcpp_lifecycle::State &)
{
++number_of_callbacks;
throw std::runtime_error("custom exception raised in configure callback");
}
rcl_lifecycle_ret_t on_error(const rclcpp_lifecycle::State &)
{
++number_of_callbacks;
return RCL_LIFECYCLE_RET_FAILURE;
}
};
TEST_F(TestCallbackExceptions, negative_on_error) {
auto test_node = std::make_shared<NegativeCallbackExceptionNode>("testnode");
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, test_node->get_current_state().id());
EXPECT_EQ(State::PRIMARY_STATE_FINALIZED, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_CONFIGURE)).id());
// check if all callbacks were successfully overwritten
EXPECT_EQ(static_cast<size_t>(2), test_node->number_of_callbacks);
}

View file

@ -0,0 +1,174 @@
// Copyright 2015 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <gtest/gtest.h>
#include <memory>
#include <string>
#include <utility>
#include "lifecycle_msgs/msg/state.hpp"
#include "lifecycle_msgs/msg/transition.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
using lifecycle_msgs::msg::State;
using lifecycle_msgs::msg::Transition;
struct GoodMood
{
static constexpr rcl_lifecycle_ret_t cb_ret = RCL_LIFECYCLE_RET_OK;
};
struct BadMood
{
static constexpr rcl_lifecycle_ret_t cb_ret = RCL_LIFECYCLE_RET_FAILURE;
};
struct VeryBadMood
{
static constexpr rcl_lifecycle_ret_t cb_ret = RCL_LIFECYCLE_RET_ERROR;
};
class TestDefaultStateMachine : public ::testing::Test
{
protected:
static void SetUpTestCase()
{
rclcpp::init(0, nullptr);
}
};
class EmptyLifecycleNode : public rclcpp_lifecycle::LifecycleNode
{
public:
explicit EmptyLifecycleNode(std::string node_name)
: rclcpp_lifecycle::LifecycleNode(std::move(node_name))
{}
};
template<class Mood = GoodMood>
class MoodyLifecycleNode : public rclcpp_lifecycle::LifecycleNode
{
public:
explicit MoodyLifecycleNode(std::string node_name)
: rclcpp_lifecycle::LifecycleNode(std::move(node_name))
{}
size_t number_of_callbacks = 0;
protected:
rcl_lifecycle_ret_t on_configure(const rclcpp_lifecycle::State &)
{
EXPECT_EQ(State::TRANSITION_STATE_CONFIGURING, get_current_state().id());
++number_of_callbacks;
return Mood::cb_ret;
}
rcl_lifecycle_ret_t on_activate(const rclcpp_lifecycle::State &)
{
EXPECT_EQ(State::TRANSITION_STATE_ACTIVATING, get_current_state().id());
++number_of_callbacks;
return Mood::cb_ret;
}
rcl_lifecycle_ret_t on_deactivate(const rclcpp_lifecycle::State &)
{
EXPECT_EQ(State::TRANSITION_STATE_DEACTIVATING, get_current_state().id());
++number_of_callbacks;
return Mood::cb_ret;
}
rcl_lifecycle_ret_t on_cleanup(const rclcpp_lifecycle::State &)
{
EXPECT_EQ(State::TRANSITION_STATE_CLEANINGUP, get_current_state().id());
++number_of_callbacks;
return Mood::cb_ret;
}
rcl_lifecycle_ret_t on_shutdown(const rclcpp_lifecycle::State &)
{
EXPECT_EQ(State::TRANSITION_STATE_SHUTTINGDOWN, get_current_state().id());
++number_of_callbacks;
return Mood::cb_ret;
}
rcl_lifecycle_ret_t on_error(const rclcpp_lifecycle::State &);
};
template<>
rcl_lifecycle_ret_t MoodyLifecycleNode<GoodMood>::on_error(const rclcpp_lifecycle::State &)
{
EXPECT_EQ(State::TRANSITION_STATE_ERRORPROCESSING, get_current_state().id());
ADD_FAILURE();
return RCL_LIFECYCLE_RET_ERROR;
}
template<>
rcl_lifecycle_ret_t MoodyLifecycleNode<BadMood>::on_error(const rclcpp_lifecycle::State &)
{
EXPECT_EQ(State::TRANSITION_STATE_ERRORPROCESSING, get_current_state().id());
++number_of_callbacks;
return RCL_LIFECYCLE_RET_OK;
}
TEST_F(TestDefaultStateMachine, empty_initializer) {
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, test_node->get_current_state().id());
}
TEST_F(TestDefaultStateMachine, trigger_transition) {
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, test_node->get_current_state().id());
EXPECT_EQ(State::PRIMARY_STATE_INACTIVE, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_CONFIGURE)).id());
EXPECT_EQ(State::PRIMARY_STATE_ACTIVE, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_ACTIVATE)).id());
EXPECT_EQ(State::PRIMARY_STATE_INACTIVE, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_DEACTIVATE)).id());
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_CLEANUP)).id());
EXPECT_EQ(State::PRIMARY_STATE_FINALIZED, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_SHUTDOWN)).id());
}
TEST_F(TestDefaultStateMachine, good_mood) {
auto test_node = std::make_shared<MoodyLifecycleNode<GoodMood>>("testnode");
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, test_node->get_current_state().id());
EXPECT_EQ(State::PRIMARY_STATE_INACTIVE, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_CONFIGURE)).id());
EXPECT_EQ(State::PRIMARY_STATE_ACTIVE, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_ACTIVATE)).id());
EXPECT_EQ(State::PRIMARY_STATE_INACTIVE, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_DEACTIVATE)).id());
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_CLEANUP)).id());
EXPECT_EQ(State::PRIMARY_STATE_FINALIZED, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_SHUTDOWN)).id());
// check if all callbacks were successfully overwritten
EXPECT_EQ(static_cast<size_t>(5), test_node->number_of_callbacks);
}
TEST_F(TestDefaultStateMachine, bad_mood) {
auto test_node = std::make_shared<MoodyLifecycleNode<BadMood>>("testnode");
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, test_node->get_current_state().id());
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_CONFIGURE)).id());
// check if all callbacks were successfully overwritten
EXPECT_EQ(static_cast<size_t>(1), test_node->number_of_callbacks);
}

View file

@ -0,0 +1,155 @@
// Copyright 2015 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <gtest/gtest.h>
#include <memory>
#include <string>
#include <utility>
#include "lifecycle_msgs/msg/state.hpp"
#include "lifecycle_msgs/msg/transition.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
using lifecycle_msgs::msg::State;
using lifecycle_msgs::msg::Transition;
class TestRegisterCustomCallbacks : public ::testing::Test
{
protected:
static void SetUpTestCase()
{
rclcpp::init(0, nullptr);
}
};
class CustomLifecycleNode : public rclcpp_lifecycle::LifecycleNode
{
public:
explicit CustomLifecycleNode(std::string node_name)
: rclcpp_lifecycle::LifecycleNode(std::move(node_name))
{}
size_t number_of_callbacks = 0;
protected:
rcl_lifecycle_ret_t on_configure(const rclcpp_lifecycle::State &)
{
ADD_FAILURE();
++number_of_callbacks;
return RCL_LIFECYCLE_RET_OK;
}
rcl_lifecycle_ret_t on_activate(const rclcpp_lifecycle::State &)
{
ADD_FAILURE();
++number_of_callbacks;
return RCL_LIFECYCLE_RET_OK;
}
rcl_lifecycle_ret_t on_deactivate(const rclcpp_lifecycle::State &)
{
ADD_FAILURE();
++number_of_callbacks;
return RCL_LIFECYCLE_RET_OK;
}
rcl_lifecycle_ret_t on_cleanup(const rclcpp_lifecycle::State &)
{
ADD_FAILURE();
++number_of_callbacks;
return RCL_LIFECYCLE_RET_OK;
}
rcl_lifecycle_ret_t on_shutdown(const rclcpp_lifecycle::State &)
{
ADD_FAILURE();
++number_of_callbacks;
return RCL_LIFECYCLE_RET_OK;
}
// Custom callbacks
public:
rcl_lifecycle_ret_t on_custom_configure(const rclcpp_lifecycle::State & previous_state)
{
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, previous_state.id());
EXPECT_EQ(State::TRANSITION_STATE_CONFIGURING, get_current_state().id());
++number_of_callbacks;
return RCL_LIFECYCLE_RET_OK;
}
rcl_lifecycle_ret_t on_custom_activate(const rclcpp_lifecycle::State & previous_state)
{
EXPECT_EQ(State::PRIMARY_STATE_INACTIVE, previous_state.id());
EXPECT_EQ(State::TRANSITION_STATE_ACTIVATING, get_current_state().id());
++number_of_callbacks;
return RCL_LIFECYCLE_RET_OK;
}
rcl_lifecycle_ret_t on_custom_deactivate(const rclcpp_lifecycle::State & previous_state)
{
EXPECT_EQ(State::PRIMARY_STATE_ACTIVE, previous_state.id());
EXPECT_EQ(State::TRANSITION_STATE_DEACTIVATING, get_current_state().id());
++number_of_callbacks;
return RCL_LIFECYCLE_RET_OK;
}
rcl_lifecycle_ret_t on_custom_cleanup(const rclcpp_lifecycle::State & previous_state)
{
EXPECT_EQ(State::PRIMARY_STATE_INACTIVE, previous_state.id());
EXPECT_EQ(State::TRANSITION_STATE_CLEANINGUP, get_current_state().id());
++number_of_callbacks;
return RCL_LIFECYCLE_RET_OK;
}
rcl_lifecycle_ret_t on_custom_shutdown(const rclcpp_lifecycle::State &)
{
EXPECT_EQ(State::TRANSITION_STATE_SHUTTINGDOWN, get_current_state().id());
++number_of_callbacks;
return RCL_LIFECYCLE_RET_OK;
}
};
TEST_F(TestRegisterCustomCallbacks, custom_callbacks) {
auto test_node = std::make_shared<CustomLifecycleNode>("testnode");
test_node->register_on_configure(
std::bind(&CustomLifecycleNode::on_custom_configure, test_node, std::placeholders::_1));
test_node->register_on_cleanup(std::bind(&CustomLifecycleNode::on_custom_cleanup, test_node,
std::placeholders::_1));
test_node->register_on_shutdown(std::bind(&CustomLifecycleNode::on_custom_shutdown, test_node,
std::placeholders::_1));
test_node->register_on_activate(std::bind(&CustomLifecycleNode::on_custom_activate, test_node,
std::placeholders::_1));
test_node->register_on_deactivate(std::bind(&CustomLifecycleNode::on_custom_deactivate,
test_node, std::placeholders::_1));
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, test_node->get_current_state().id());
EXPECT_EQ(State::PRIMARY_STATE_INACTIVE, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_CONFIGURE)).id());
EXPECT_EQ(State::PRIMARY_STATE_ACTIVE, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_ACTIVATE)).id());
EXPECT_EQ(State::PRIMARY_STATE_INACTIVE, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_DEACTIVATE)).id());
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_CLEANUP)).id());
EXPECT_EQ(State::PRIMARY_STATE_FINALIZED, test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_SHUTDOWN)).id());
// check if all callbacks were successfully overwritten
EXPECT_EQ(static_cast<size_t>(5), test_node->number_of_callbacks);
}

View file

@ -0,0 +1,73 @@
// Copyright 2015 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <gtest/gtest.h>
#include <memory>
#include <string>
#include <utility>
#include <vector>
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
class TestStateMachineInfo : public ::testing::Test
{
protected:
static void SetUpTestCase()
{
rclcpp::init(0, nullptr);
}
};
TEST_F(TestStateMachineInfo, available_states) {
auto test_node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("testnode");
std::vector<rclcpp_lifecycle::State> available_states =
test_node->get_available_states();
EXPECT_EQ((unsigned int)11, available_states.size());
// Primary States
EXPECT_EQ((unsigned int)0, available_states[0].id()); // unknown
EXPECT_EQ((unsigned int)1, available_states[1].id()); // unconfigured
EXPECT_EQ((unsigned int)2, available_states[2].id()); // inactive
EXPECT_EQ((unsigned int)3, available_states[3].id()); // active
EXPECT_EQ((unsigned int)4, available_states[4].id()); // finalized
// Transition States
EXPECT_EQ((unsigned int)10, available_states[5].id()); // configuring
EXPECT_EQ((unsigned int)11, available_states[6].id()); // cleaningup
EXPECT_EQ((unsigned int)12, available_states[7].id()); // shuttingdown
EXPECT_EQ((unsigned int)13, available_states[8].id()); // activating
EXPECT_EQ((unsigned int)14, available_states[9].id()); // deactivating
EXPECT_EQ((unsigned int)15, available_states[10].id()); // errorprocessing
}
TEST_F(TestStateMachineInfo, available_transitions) {
auto test_node = std::make_shared<rclcpp_lifecycle::LifecycleNode>("testnode");
std::vector<rclcpp_lifecycle::Transition> available_transitions =
test_node->get_available_transitions();
EXPECT_EQ((unsigned int)25, available_transitions.size());
for (rclcpp_lifecycle::Transition & transition : available_transitions) {
EXPECT_FALSE(transition.label().empty());
EXPECT_TRUE(transition.start_state().id() <= (unsigned int)4 ||
(transition.start_state().id() >= (unsigned int)10 &&
(transition.start_state().id() <= (unsigned int)15)));
EXPECT_FALSE(transition.start_state().label().empty());
EXPECT_TRUE(transition.goal_state().id() <= (unsigned int)4 ||
(transition.goal_state().id() >= (unsigned int)10 &&
(transition.goal_state().id() <= (unsigned int)15)));
EXPECT_FALSE(transition.goal_state().label().empty());
}
}