Increasing test coverage of rclcpp_lifecycle (#1045)

Signed-off-by: Stephen Brawner <brawner@gmail.com>
This commit is contained in:
brawner 2020-04-30 10:29:45 -07:00 committed by GitHub
parent ef6434026f
commit f69b18203f
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
5 changed files with 735 additions and 1 deletions

View file

@ -59,6 +59,14 @@ if(BUILD_TESTING)
) )
target_link_libraries(test_lifecycle_node ${PROJECT_NAME}) target_link_libraries(test_lifecycle_node ${PROJECT_NAME})
endif() endif()
ament_add_gtest(test_lifecycle_service_client test/test_lifecycle_service_client.cpp)
if(TARGET test_lifecycle_service_client)
ament_target_dependencies(test_lifecycle_service_client
"rcl_lifecycle"
"rclcpp"
)
target_link_libraries(test_lifecycle_service_client ${PROJECT_NAME})
endif()
ament_add_gtest(test_state_machine_info test/test_state_machine_info.cpp) ament_add_gtest(test_state_machine_info test/test_state_machine_info.cpp)
if(TARGET test_state_machine_info) if(TARGET test_state_machine_info)
ament_target_dependencies(test_state_machine_info ament_target_dependencies(test_state_machine_info

View file

@ -14,8 +14,11 @@
#include <gtest/gtest.h> #include <gtest/gtest.h>
#include <map>
#include <memory> #include <memory>
#include <set>
#include <string> #include <string>
#include <vector>
#include <utility> #include <utility>
#include "lifecycle_msgs/msg/state.hpp" #include "lifecycle_msgs/msg/state.hpp"
@ -162,6 +165,38 @@ TEST_F(TestDefaultStateMachine, trigger_transition) {
TEST_F(TestDefaultStateMachine, trigger_transition_with_error_code) { TEST_F(TestDefaultStateMachine, trigger_transition_with_error_code) {
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode"); auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
auto success = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
auto reset_key = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
auto ret = reset_key;
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, test_node->get_current_state().id());
test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_CONFIGURE), ret);
ASSERT_EQ(success, ret);
ret = reset_key;
test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_ACTIVATE), ret);
ASSERT_EQ(success, ret);
ret = reset_key;
test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_DEACTIVATE), ret);
ASSERT_EQ(success, ret);
ret = reset_key;
test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_CLEANUP), ret);
ASSERT_EQ(success, ret);
ret = reset_key;
test_node->trigger_transition(
rclcpp_lifecycle::Transition(Transition::TRANSITION_UNCONFIGURED_SHUTDOWN), ret);
ASSERT_EQ(success, ret);
}
TEST_F(TestDefaultStateMachine, call_transitions_with_error_code) {
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
auto success = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS; auto success = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
auto reset_key = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR; auto reset_key = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
@ -188,6 +223,25 @@ TEST_F(TestDefaultStateMachine, trigger_transition_with_error_code) {
EXPECT_EQ(success, ret); EXPECT_EQ(success, ret);
} }
TEST_F(TestDefaultStateMachine, call_transitions_without_code) {
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
auto configured = test_node->configure();
EXPECT_EQ(configured.id(), State::PRIMARY_STATE_INACTIVE);
auto activated = test_node->activate();
EXPECT_EQ(activated.id(), State::PRIMARY_STATE_ACTIVE);
auto deactivated = test_node->deactivate();
EXPECT_EQ(deactivated.id(), State::PRIMARY_STATE_INACTIVE);
auto unconfigured = test_node->cleanup();
EXPECT_EQ(unconfigured.id(), State::PRIMARY_STATE_UNCONFIGURED);
auto finalized = test_node->shutdown();
EXPECT_EQ(finalized.id(), State::PRIMARY_STATE_FINALIZED);
}
TEST_F(TestDefaultStateMachine, good_mood) { TEST_F(TestDefaultStateMachine, good_mood) {
auto test_node = std::make_shared<MoodyLifecycleNode<GoodMood>>("testnode"); auto test_node = std::make_shared<MoodyLifecycleNode<GoodMood>>("testnode");
@ -233,3 +287,259 @@ TEST_F(TestDefaultStateMachine, lifecycle_subscriber) {
SUCCEED(); SUCCEED();
} }
// Parameters are tested more thoroughly in rclcpp's test_node.cpp
// These are provided for coverage of lifecycle node's API
TEST_F(TestDefaultStateMachine, declare_parameters) {
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
auto list_result = test_node->list_parameters({}, 0u);
EXPECT_EQ(list_result.names.size(), 1u);
EXPECT_STREQ(list_result.names[0].c_str(), "use_sim_time");
const std::string bool_name = "test_boolean";
const std::string int_name = "test_int";
// Default descriptor overload
test_node->declare_parameter(bool_name, rclcpp::ParameterValue(false));
// Explicit descriptor overload
rcl_interfaces::msg::ParameterDescriptor int_descriptor;
int_descriptor.name = int_name;
int_descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
int_descriptor.description = "Example integer parameter";
test_node->declare_parameter(int_name, rclcpp::ParameterValue(42), int_descriptor);
std::map<std::string, std::string> str_parameters;
str_parameters["str_one"] = "stringy_string";
str_parameters["str_two"] = "stringy_string_string";
// Default descriptor overload
test_node->declare_parameters("test_string", str_parameters);
std::map<std::string,
std::pair<double, rcl_interfaces::msg::ParameterDescriptor>> double_parameters;
rcl_interfaces::msg::ParameterDescriptor double_descriptor_one;
double_descriptor_one.name = "double_one";
double_descriptor_one.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE;
double_parameters["double_one"] = std::make_pair(1.0, double_descriptor_one);
rcl_interfaces::msg::ParameterDescriptor double_descriptor_two;
double_descriptor_two.name = "double_two";
double_descriptor_two.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE;
double_parameters["double_two"] = std::make_pair(2.0, double_descriptor_two);
// Explicit descriptor overload
test_node->declare_parameters("test_double", double_parameters);
list_result = test_node->list_parameters({}, 0u);
EXPECT_EQ(list_result.names.size(), 7u);
// The order of these names is not controlled by lifecycle_node, doing set equality
std::set<std::string> expected_names = {
"test_boolean",
"test_double.double_one",
"test_double.double_two",
"test_int",
"test_string.str_one",
"test_string.str_two",
"use_sim_time",
};
std::set<std::string> actual_names(list_result.names.begin(), list_result.names.end());
EXPECT_EQ(expected_names, actual_names);
}
TEST_F(TestDefaultStateMachine, check_parameters) {
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
auto list_result = test_node->list_parameters({}, 0u);
EXPECT_EQ(list_result.names.size(), 1u);
EXPECT_STREQ(list_result.names[0].c_str(), "use_sim_time");
const std::string bool_name = "test_boolean";
const std::string int_name = "test_int";
std::vector<std::string> parameter_names = {bool_name, int_name};
EXPECT_FALSE(test_node->has_parameter(bool_name));
EXPECT_FALSE(test_node->has_parameter(int_name));
EXPECT_THROW(
test_node->get_parameters(parameter_names),
rclcpp::exceptions::ParameterNotDeclaredException);
// Default descriptor overload
test_node->declare_parameter(bool_name, rclcpp::ParameterValue(true));
// Explicit descriptor overload
rcl_interfaces::msg::ParameterDescriptor int_descriptor;
int_descriptor.name = int_name;
int_descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
int_descriptor.description = "Example integer parameter";
test_node->declare_parameter(int_name, rclcpp::ParameterValue(42), int_descriptor);
// describe parameters
auto descriptors = test_node->describe_parameters(parameter_names);
EXPECT_EQ(descriptors.size(), parameter_names.size());
EXPECT_THROW(
test_node->describe_parameter("not_a_real_parameter"),
rclcpp::exceptions::ParameterNotDeclaredException);
// describe parameter matches explicit descriptor
auto descriptor = test_node->describe_parameter(int_name);
EXPECT_STREQ(descriptor.name.c_str(), int_descriptor.name.c_str());
EXPECT_EQ(descriptor.type, int_descriptor.type);
EXPECT_STREQ(descriptor.description.c_str(), int_descriptor.description.c_str());
// bool parameter exists and value matches
EXPECT_TRUE(test_node->has_parameter(bool_name));
EXPECT_EQ(test_node->get_parameter(bool_name).as_bool(), true);
// int parameter exists and value matches
EXPECT_TRUE(test_node->has_parameter(int_name));
EXPECT_EQ(test_node->get_parameter(int_name).as_int(), 42);
// Get multiple parameters at a time
auto parameters = test_node->get_parameters(parameter_names);
EXPECT_EQ(parameters.size(), parameter_names.size());
EXPECT_EQ(parameters[0].as_bool(), true);
EXPECT_EQ(parameters[1].as_int(), 42);
// Get multiple parameters at a time with map
std::map<std::string, rclcpp::ParameterValue> parameter_map;
EXPECT_TRUE(test_node->get_parameters({}, parameter_map));
// int param, bool param, and use_sim_time
EXPECT_EQ(parameter_map.size(), 3u);
// Check parameter types
auto parameter_types = test_node->get_parameter_types(parameter_names);
EXPECT_EQ(parameter_types.size(), parameter_names.size());
EXPECT_EQ(parameter_types[0], rcl_interfaces::msg::ParameterType::PARAMETER_BOOL);
EXPECT_EQ(parameter_types[1], rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER);
// Setting parameters
size_t parameters_set = 0;
auto callback = [&parameters_set](const std::vector<rclcpp::Parameter> & parameters) {
parameters_set += parameters.size();
rcl_interfaces::msg::SetParametersResult result;
result.successful = true;
return result;
};
test_node->set_on_parameters_set_callback(callback);
rclcpp::Parameter bool_parameter(bool_name, rclcpp::ParameterValue(false));
EXPECT_TRUE(test_node->set_parameter(bool_parameter).successful);
EXPECT_EQ(parameters_set, 1u);
rclcpp::Parameter int_parameter(int_name, rclcpp::ParameterValue(7));
test_node->set_parameters({int_parameter});
EXPECT_EQ(parameters_set, 2u);
// List parameters
list_result = test_node->list_parameters({}, 0u);
EXPECT_EQ(list_result.names.size(), 3u);
EXPECT_STREQ(list_result.names[0].c_str(), parameter_names[0].c_str());
EXPECT_STREQ(list_result.names[1].c_str(), parameter_names[1].c_str());
EXPECT_STREQ(list_result.names[2].c_str(), "use_sim_time");
// Undeclare parameter
test_node->undeclare_parameter(bool_name);
EXPECT_FALSE(test_node->has_parameter(bool_name));
rclcpp::Parameter parameter;
EXPECT_FALSE(test_node->get_parameter(bool_name, parameter));
// Bool parameter has been undeclared, atomic setting should fail
parameters = {
rclcpp::Parameter(bool_name, rclcpp::ParameterValue(true)),
rclcpp::Parameter(int_name, rclcpp::ParameterValue(0))};
EXPECT_THROW(
test_node->set_parameters_atomically(parameters),
rclcpp::exceptions::ParameterNotDeclaredException);
// Since setting parameters failed, this should remain the same
EXPECT_EQ(test_node->get_parameter(int_name).as_int(), 7);
// Bool parameter no longer exists, using "or" value
EXPECT_FALSE(
test_node->get_parameter_or(
bool_name, parameter, rclcpp::Parameter(bool_name, rclcpp::ParameterValue(true))));
EXPECT_TRUE(parameter.as_bool());
}
TEST_F(TestDefaultStateMachine, test_getters) {
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
auto options = test_node->get_node_options();
EXPECT_EQ(0u, options.arguments().size());
EXPECT_NE(nullptr, test_node->get_node_base_interface());
EXPECT_NE(nullptr, test_node->get_node_clock_interface());
EXPECT_NE(nullptr, test_node->get_node_graph_interface());
EXPECT_NE(nullptr, test_node->get_node_logging_interface());
EXPECT_NE(nullptr, test_node->get_node_time_source_interface());
EXPECT_NE(nullptr, test_node->get_node_timers_interface());
EXPECT_NE(nullptr, test_node->get_node_topics_interface());
EXPECT_NE(nullptr, test_node->get_node_services_interface());
EXPECT_NE(nullptr, test_node->get_node_parameters_interface());
EXPECT_NE(nullptr, test_node->get_node_waitables_interface());
EXPECT_NE(nullptr, test_node->get_graph_event());
EXPECT_NE(nullptr, test_node->get_clock());
EXPECT_LT(0u, test_node->now().nanoseconds());
EXPECT_STREQ("testnode", test_node->get_logger().get_name());
EXPECT_NE(nullptr, const_cast<const EmptyLifecycleNode *>(test_node.get())->get_clock());
}
TEST_F(TestDefaultStateMachine, test_graph) {
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
auto names = test_node->get_node_names();
EXPECT_EQ(names.size(), 1u);
EXPECT_STREQ(names[0].c_str(), "/testnode");
// parameter_events, rosout, /testnode/transition_event
auto topic_names_and_types = test_node->get_topic_names_and_types();
EXPECT_EQ(topic_names_and_types.size(), 3u);
EXPECT_STREQ(
topic_names_and_types["/testnode/transition_event"][0].c_str(),
"lifecycle_msgs/msg/TransitionEvent");
auto service_names_and_types = test_node->get_service_names_and_types();
EXPECT_EQ(service_names_and_types.size(), 11u);
// These are specific to lifecycle nodes, other services are provided by rclcpp::Node
EXPECT_STREQ(
service_names_and_types["/testnode/change_state"][0].c_str(),
"lifecycle_msgs/srv/ChangeState");
EXPECT_STREQ(
service_names_and_types["/testnode/get_available_states"][0].c_str(),
"lifecycle_msgs/srv/GetAvailableStates");
EXPECT_STREQ(
service_names_and_types["/testnode/get_available_transitions"][0].c_str(),
"lifecycle_msgs/srv/GetAvailableTransitions");
EXPECT_STREQ(
service_names_and_types["/testnode/get_state"][0].c_str(),
"lifecycle_msgs/srv/GetState");
EXPECT_STREQ(
service_names_and_types["/testnode/get_transition_graph"][0].c_str(),
"lifecycle_msgs/srv/GetAvailableTransitions");
EXPECT_EQ(1u, test_node->count_publishers("/testnode/transition_event"));
EXPECT_EQ(0u, test_node->count_subscribers("/testnode/transition_event"));
auto publishers_info = test_node->get_publishers_info_by_topic("/testnode/transition_event");
EXPECT_EQ(publishers_info.size(), 1u);
auto subscriptions_info =
test_node->get_subscriptions_info_by_topic("/testnode/transition_event");
EXPECT_EQ(subscriptions_info.size(), 0u);
}
TEST_F(TestDefaultStateMachine, test_callback_groups) {
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
auto groups = test_node->get_callback_groups();
EXPECT_EQ(groups.size(), 1u);
auto group = test_node->create_callback_group(
rclcpp::callback_group::CallbackGroupType::MutuallyExclusive);
EXPECT_NE(nullptr, group);
groups = test_node->get_callback_groups();
EXPECT_EQ(groups.size(), 2u);
EXPECT_EQ(groups[1].lock().get(), group.get());
}

View file

@ -0,0 +1,346 @@
// Copyright 2020 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.
/**
* Service client test was adopted from:
* https://github.com/ros2/demos/blob/master/lifecycle/src/lifecycle_service_client.cpp
*/
#include <gtest/gtest.h>
#include <chrono>
#include <memory>
#include <string>
#include <thread>
#include <vector>
#include "lifecycle_msgs/msg/state.hpp"
#include "lifecycle_msgs/msg/transition.hpp"
#include "lifecycle_msgs/msg/transition_description.hpp"
#include "lifecycle_msgs/srv/change_state.hpp"
#include "lifecycle_msgs/srv/get_available_states.hpp"
#include "lifecycle_msgs/srv/get_available_transitions.hpp"
#include "lifecycle_msgs/srv/get_state.hpp"
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
using namespace std::chrono_literals;
constexpr char const * lifecycle_node_name = "lc_talker";
constexpr char const * node_get_state_topic = "/lc_talker/get_state";
constexpr char const * node_change_state_topic = "/lc_talker/change_state";
constexpr char const * node_get_available_states_topic = "/lc_talker/get_available_states";
constexpr char const * node_get_available_transitions_topic =
"/lc_talker/get_available_transitions";
constexpr char const * node_get_transition_graph_topic =
"/lc_talker/get_transition_graph";
const lifecycle_msgs::msg::State unknown_state = lifecycle_msgs::msg::State();
class EmptyLifecycleNode : public rclcpp_lifecycle::LifecycleNode
{
public:
EmptyLifecycleNode()
: rclcpp_lifecycle::LifecycleNode(lifecycle_node_name)
{}
};
class LifecycleServiceClient : public rclcpp::Node
{
public:
explicit LifecycleServiceClient(std::string node_name)
: Node(node_name)
{
client_get_available_states_ = this->create_client<lifecycle_msgs::srv::GetAvailableStates>(
node_get_available_states_topic);
client_get_available_transitions_ =
this->create_client<lifecycle_msgs::srv::GetAvailableTransitions>(
node_get_available_transitions_topic);
client_get_transition_graph_ =
this->create_client<lifecycle_msgs::srv::GetAvailableTransitions>(
node_get_transition_graph_topic);
client_get_state_ = this->create_client<lifecycle_msgs::srv::GetState>(
node_get_state_topic);
client_change_state_ = this->create_client<lifecycle_msgs::srv::ChangeState>(
node_change_state_topic);
}
lifecycle_msgs::msg::State
get_state(std::chrono::seconds time_out = 1s)
{
auto request = std::make_shared<lifecycle_msgs::srv::GetState::Request>();
if (!client_get_state_->wait_for_service(time_out)) {
return unknown_state;
}
auto future_result = client_get_state_->async_send_request(request);
auto future_status = future_result.wait_for(time_out);
if (future_status != std::future_status::ready) {
return unknown_state;
}
if (future_result.get()) {
return future_result.get()->current_state;
} else {
return unknown_state;
}
}
bool
change_state(std::uint8_t transition, std::chrono::seconds time_out = 1s)
{
auto request = std::make_shared<lifecycle_msgs::srv::ChangeState::Request>();
request->transition.id = transition;
if (!client_change_state_->wait_for_service(time_out)) {
return false;
}
auto future_result = client_change_state_->async_send_request(request);
auto future_status = future_result.wait_for(time_out);
if (future_status != std::future_status::ready) {
return false;
}
return future_result.get()->success;
}
std::vector<lifecycle_msgs::msg::State>
get_available_states(std::chrono::seconds time_out = 1s)
{
auto request = std::make_shared<lifecycle_msgs::srv::GetAvailableStates::Request>();
if (!client_get_available_states_->wait_for_service(time_out)) {
return std::vector<lifecycle_msgs::msg::State>();
}
auto future_result = client_get_available_states_->async_send_request(request);
auto future_status = future_result.wait_for(time_out);
if (future_status != std::future_status::ready) {
return std::vector<lifecycle_msgs::msg::State>();
}
if (future_result.get()) {
return future_result.get()->available_states;
}
return std::vector<lifecycle_msgs::msg::State>();
}
std::vector<lifecycle_msgs::msg::TransitionDescription>
get_available_transitions(std::chrono::seconds time_out = 1s)
{
auto request = std::make_shared<lifecycle_msgs::srv::GetAvailableTransitions::Request>();
if (!client_get_available_transitions_->wait_for_service(time_out)) {
return std::vector<lifecycle_msgs::msg::TransitionDescription>();
}
auto future_result = client_get_available_transitions_->async_send_request(request);
auto future_status = future_result.wait_for(time_out);
if (future_status != std::future_status::ready) {
return std::vector<lifecycle_msgs::msg::TransitionDescription>();
}
if (future_result.get()) {
return future_result.get()->available_transitions;
}
return std::vector<lifecycle_msgs::msg::TransitionDescription>();
}
std::vector<lifecycle_msgs::msg::TransitionDescription>
get_transition_graph(std::chrono::seconds time_out = 1s)
{
auto request = std::make_shared<lifecycle_msgs::srv::GetAvailableTransitions::Request>();
if (!client_get_transition_graph_->wait_for_service(time_out)) {
return std::vector<lifecycle_msgs::msg::TransitionDescription>();
}
auto future_result = client_get_transition_graph_->async_send_request(request);
auto future_status = future_result.wait_for(time_out);
if (future_status != std::future_status::ready) {
return std::vector<lifecycle_msgs::msg::TransitionDescription>();
}
if (future_result.get()) {
return future_result.get()->available_transitions;
}
return std::vector<lifecycle_msgs::msg::TransitionDescription>();
}
private:
std::shared_ptr<rclcpp::Client<lifecycle_msgs::srv::GetAvailableStates>>
client_get_available_states_;
std::shared_ptr<rclcpp::Client<lifecycle_msgs::srv::GetAvailableTransitions>>
client_get_available_transitions_;
std::shared_ptr<rclcpp::Client<lifecycle_msgs::srv::GetAvailableTransitions>>
client_get_transition_graph_;
std::shared_ptr<rclcpp::Client<lifecycle_msgs::srv::GetState>> client_get_state_;
std::shared_ptr<rclcpp::Client<lifecycle_msgs::srv::ChangeState>> client_change_state_;
};
class TestLifecycleServiceClient : public ::testing::Test
{
protected:
EmptyLifecycleNode * lifecycle_node() {return lifecycle_node_.get();}
LifecycleServiceClient * lifecycle_client() {return lifecycle_client_.get();}
private:
void SetUp() override
{
rclcpp::init(0, nullptr);
lifecycle_node_ = std::make_shared<EmptyLifecycleNode>();
lifecycle_client_ = std::make_shared<LifecycleServiceClient>("client");
spinner_ = std::thread(&TestLifecycleServiceClient::spin, this);
}
void TearDown() override
{
rclcpp::shutdown();
spinner_.join();
}
void spin()
{
while (rclcpp::ok()) {
rclcpp::spin_some(lifecycle_node_->get_node_base_interface());
rclcpp::spin_some(lifecycle_client_);
std::this_thread::sleep_for(std::chrono::milliseconds(10));
}
}
std::shared_ptr<EmptyLifecycleNode> lifecycle_node_;
std::shared_ptr<LifecycleServiceClient> lifecycle_client_;
std::thread spinner_;
};
TEST_F(TestLifecycleServiceClient, construct_destruct) {
EXPECT_NE(nullptr, lifecycle_client());
EXPECT_NE(nullptr, lifecycle_node());
}
TEST_F(TestLifecycleServiceClient, available_states) {
auto states = lifecycle_client()->get_available_states();
EXPECT_EQ(states.size(), 11u);
EXPECT_EQ(states[0].id, lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN);
EXPECT_EQ(states[1].id, lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED);
EXPECT_EQ(states[2].id, lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
EXPECT_EQ(states[3].id, lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE);
EXPECT_EQ(states[4].id, lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED);
EXPECT_EQ(states[5].id, lifecycle_msgs::msg::State::TRANSITION_STATE_CONFIGURING);
EXPECT_EQ(states[6].id, lifecycle_msgs::msg::State::TRANSITION_STATE_CLEANINGUP);
EXPECT_EQ(states[7].id, lifecycle_msgs::msg::State::TRANSITION_STATE_SHUTTINGDOWN);
EXPECT_EQ(states[8].id, lifecycle_msgs::msg::State::TRANSITION_STATE_ACTIVATING);
EXPECT_EQ(states[9].id, lifecycle_msgs::msg::State::TRANSITION_STATE_DEACTIVATING);
EXPECT_EQ(states[10].id, lifecycle_msgs::msg::State::TRANSITION_STATE_ERRORPROCESSING);
}
TEST_F(TestLifecycleServiceClient, transition_graph) {
auto transitions = lifecycle_client()->get_transition_graph();
EXPECT_EQ(transitions.size(), 25u);
}
TEST_F(TestLifecycleServiceClient, available_transitions) {
auto transitions = lifecycle_client()->get_available_transitions();
EXPECT_EQ(transitions.size(), 2u);
EXPECT_EQ(transitions[0].transition.id, lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE);
EXPECT_EQ(
transitions[1].transition.id,
lifecycle_msgs::msg::Transition::TRANSITION_UNCONFIGURED_SHUTDOWN);
}
TEST_F(TestLifecycleServiceClient, lifecycle_transitions) {
EXPECT_EQ(
lifecycle_client()->get_state().id, lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED);
auto transitions = lifecycle_client()->get_available_transitions();
EXPECT_EQ(transitions.size(), 2u);
EXPECT_EQ(transitions[0].transition.id, lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE);
EXPECT_EQ(
transitions[1].transition.id,
lifecycle_msgs::msg::Transition::TRANSITION_UNCONFIGURED_SHUTDOWN);
EXPECT_TRUE(
lifecycle_client()->change_state(
lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE));
EXPECT_EQ(
lifecycle_client()->get_state().id,
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
transitions = lifecycle_client()->get_available_transitions();
EXPECT_EQ(transitions.size(), 3u);
EXPECT_EQ(transitions[0].transition.id, lifecycle_msgs::msg::Transition::TRANSITION_CLEANUP);
EXPECT_EQ(transitions[1].transition.id, lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE);
EXPECT_EQ(
transitions[2].transition.id,
lifecycle_msgs::msg::Transition::TRANSITION_INACTIVE_SHUTDOWN);
EXPECT_TRUE(
lifecycle_client()->change_state(
lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE));
EXPECT_EQ(lifecycle_client()->get_state().id, lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE);
transitions = lifecycle_client()->get_available_transitions();
EXPECT_EQ(transitions.size(), 2u);
EXPECT_EQ(transitions[0].transition.id, lifecycle_msgs::msg::Transition::TRANSITION_DEACTIVATE);
EXPECT_EQ(
transitions[1].transition.id,
lifecycle_msgs::msg::Transition::TRANSITION_ACTIVE_SHUTDOWN);
EXPECT_TRUE(
lifecycle_client()->change_state(
lifecycle_msgs::msg::Transition::
TRANSITION_DEACTIVATE));
EXPECT_EQ(
lifecycle_client()->get_state().id,
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE);
transitions = lifecycle_client()->get_available_transitions();
EXPECT_EQ(transitions.size(), 3u);
EXPECT_EQ(transitions[0].transition.id, lifecycle_msgs::msg::Transition::TRANSITION_CLEANUP);
EXPECT_EQ(transitions[1].transition.id, lifecycle_msgs::msg::Transition::TRANSITION_ACTIVATE);
EXPECT_EQ(
transitions[2].transition.id,
lifecycle_msgs::msg::Transition::TRANSITION_INACTIVE_SHUTDOWN);
EXPECT_TRUE(
lifecycle_client()->change_state(
lifecycle_msgs::msg::Transition::TRANSITION_CLEANUP));
EXPECT_EQ(
lifecycle_client()->get_state().id, lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED);
transitions = lifecycle_client()->get_available_transitions();
EXPECT_EQ(transitions.size(), 2u);
EXPECT_EQ(transitions[0].transition.id, lifecycle_msgs::msg::Transition::TRANSITION_CONFIGURE);
EXPECT_EQ(
transitions[1].transition.id,
lifecycle_msgs::msg::Transition::TRANSITION_UNCONFIGURED_SHUTDOWN);
EXPECT_TRUE(
lifecycle_client()->change_state(
lifecycle_msgs::msg::Transition::
TRANSITION_UNCONFIGURED_SHUTDOWN));
EXPECT_EQ(
lifecycle_client()->get_state().id,
lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED);
transitions = lifecycle_client()->get_available_transitions();
EXPECT_EQ(transitions.size(), 0u);
}

View file

@ -28,6 +28,17 @@ protected:
} }
}; };
class StateDerived : public rclcpp_lifecycle::State
{
public:
StateDerived(uint8_t id, const std::string & label)
: State(id, label) {}
void expose_reset()
{
reset();
}
};
TEST_F(TestStateWrapper, wrapper) { TEST_F(TestStateWrapper, wrapper) {
{ {
rclcpp_lifecycle::State state(1, "my_state"); rclcpp_lifecycle::State state(1, "my_state");
@ -95,6 +106,10 @@ TEST_F(TestStateWrapper, copy_constructor) {
TEST_F(TestStateWrapper, assignment_operator) { TEST_F(TestStateWrapper, assignment_operator) {
auto a = std::make_shared<rclcpp_lifecycle::State>(1, "one"); auto a = std::make_shared<rclcpp_lifecycle::State>(1, "one");
*a = *a;
EXPECT_EQ(1, a->id());
EXPECT_STREQ("one", a->label().c_str());
auto b = std::make_shared<rclcpp_lifecycle::State>(2, "two"); auto b = std::make_shared<rclcpp_lifecycle::State>(2, "two");
*b = *a; *b = *a;
@ -166,3 +181,16 @@ TEST_F(TestStateWrapper, assignment_operator4) {
delete lc_state1; delete lc_state1;
} }
TEST_F(TestStateWrapper, exceptions) {
EXPECT_THROW((void)rclcpp_lifecycle::State(0, ""), std::runtime_error);
const rcl_lifecycle_state_t * null_handle = nullptr;
EXPECT_THROW((void)rclcpp_lifecycle::State(null_handle), std::runtime_error);
auto reset_state = std::make_shared<StateDerived>(1, "one");
reset_state->expose_reset();
EXPECT_THROW(reset_state->id(), std::runtime_error);
EXPECT_THROW(reset_state->label(), std::runtime_error);
}

View file

@ -28,6 +28,19 @@ protected:
} }
}; };
class TransitionDerived : public rclcpp_lifecycle::Transition
{
public:
TransitionDerived(
uint8_t id, const std::string & label,
rclcpp_lifecycle::State && start, rclcpp_lifecycle::State && goal)
: Transition(id, label, std::move(start), std::move(goal)) {}
void expose_reset()
{
reset();
}
};
TEST_F(TestTransitionWrapper, empty_transition) { TEST_F(TestTransitionWrapper, empty_transition) {
auto a = std::make_shared<rclcpp_lifecycle::Transition>(1, "my_transition"); auto a = std::make_shared<rclcpp_lifecycle::Transition>(1, "my_transition");
EXPECT_NO_THROW(a.reset()); EXPECT_NO_THROW(a.reset());
@ -75,7 +88,15 @@ TEST_F(TestTransitionWrapper, copy_constructor) {
} }
TEST_F(TestTransitionWrapper, assignment_operator) { TEST_F(TestTransitionWrapper, assignment_operator) {
auto a = std::make_shared<rclcpp_lifecycle::Transition>(1, "one"); rclcpp_lifecycle::State start_state(1, "start_state");
rclcpp_lifecycle::State goal_state(2, "goal_state");
auto a = std::make_shared<rclcpp_lifecycle::Transition>(
1, "one", std::move(start_state),
std::move(goal_state));
*a = *a;
EXPECT_EQ(1, a->id());
EXPECT_STREQ("one", a->label().c_str());
auto b = std::make_shared<rclcpp_lifecycle::Transition>(2, "two"); auto b = std::make_shared<rclcpp_lifecycle::Transition>(2, "two");
*b = *a; *b = *a;
@ -83,4 +104,25 @@ TEST_F(TestTransitionWrapper, assignment_operator) {
EXPECT_EQ(1, b->id()); EXPECT_EQ(1, b->id());
EXPECT_STREQ("one", b->label().c_str()); EXPECT_STREQ("one", b->label().c_str());
EXPECT_STREQ("start_state", b->start_state().label().c_str());
EXPECT_STREQ("goal_state", b->goal_state().label().c_str());
EXPECT_EQ(1, b->start_state().id());
EXPECT_EQ(2, b->goal_state().id());
}
TEST_F(TestTransitionWrapper, exceptions) {
rcl_lifecycle_transition_t * null_handle = nullptr;
EXPECT_THROW((void)rclcpp_lifecycle::Transition(null_handle), std::runtime_error);
rclcpp_lifecycle::State start_state(1, "start_state");
rclcpp_lifecycle::State goal_state(2, "goal_state");
auto a = std::make_shared<TransitionDerived>(
1, "one", std::move(start_state),
std::move(goal_state));
a->expose_reset();
EXPECT_THROW(a->start_state(), std::runtime_error);
EXPECT_THROW(a->goal_state(), std::runtime_error);
EXPECT_THROW(a->id(), std::runtime_error);
EXPECT_THROW(a->label(), std::runtime_error);
} }