Increasing test coverage of rclcpp_lifecycle (#1045)
Signed-off-by: Stephen Brawner <brawner@gmail.com>
This commit is contained in:
parent
ef6434026f
commit
f69b18203f
5 changed files with 735 additions and 1 deletions
|
@ -14,8 +14,11 @@
|
|||
|
||||
|
||||
#include <gtest/gtest.h>
|
||||
#include <map>
|
||||
#include <memory>
|
||||
#include <set>
|
||||
#include <string>
|
||||
#include <vector>
|
||||
#include <utility>
|
||||
|
||||
#include "lifecycle_msgs/msg/state.hpp"
|
||||
|
@ -162,6 +165,38 @@ TEST_F(TestDefaultStateMachine, trigger_transition) {
|
|||
|
||||
TEST_F(TestDefaultStateMachine, trigger_transition_with_error_code) {
|
||||
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 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);
|
||||
}
|
||||
|
||||
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) {
|
||||
auto test_node = std::make_shared<MoodyLifecycleNode<GoodMood>>("testnode");
|
||||
|
||||
|
@ -233,3 +287,259 @@ TEST_F(TestDefaultStateMachine, lifecycle_subscriber) {
|
|||
|
||||
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 = [¶meters_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());
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue