1414
1515
1616#include < gtest/gtest.h>
17+ #include < map>
1718#include < memory>
19+ #include < set>
1820#include < string>
21+ #include < vector>
1922#include < utility>
2023
2124#include " lifecycle_msgs/msg/state.hpp"
@@ -162,6 +165,38 @@ TEST_F(TestDefaultStateMachine, trigger_transition) {
162165
163166TEST_F (TestDefaultStateMachine, trigger_transition_with_error_code) {
164167 auto test_node = std::make_shared<EmptyLifecycleNode>(" testnode" );
168+ auto success = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
169+ auto reset_key = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
170+ auto ret = reset_key;
171+
172+ EXPECT_EQ (State::PRIMARY_STATE_UNCONFIGURED, test_node->get_current_state ().id ());
173+ test_node->trigger_transition (
174+ rclcpp_lifecycle::Transition (Transition::TRANSITION_CONFIGURE), ret);
175+ ASSERT_EQ (success, ret);
176+ ret = reset_key;
177+
178+ test_node->trigger_transition (
179+ rclcpp_lifecycle::Transition (Transition::TRANSITION_ACTIVATE), ret);
180+ ASSERT_EQ (success, ret);
181+ ret = reset_key;
182+
183+ test_node->trigger_transition (
184+ rclcpp_lifecycle::Transition (Transition::TRANSITION_DEACTIVATE), ret);
185+ ASSERT_EQ (success, ret);
186+ ret = reset_key;
187+
188+ test_node->trigger_transition (
189+ rclcpp_lifecycle::Transition (Transition::TRANSITION_CLEANUP), ret);
190+ ASSERT_EQ (success, ret);
191+ ret = reset_key;
192+
193+ test_node->trigger_transition (
194+ rclcpp_lifecycle::Transition (Transition::TRANSITION_UNCONFIGURED_SHUTDOWN), ret);
195+ ASSERT_EQ (success, ret);
196+ }
197+
198+ TEST_F (TestDefaultStateMachine, call_transitions_with_error_code) {
199+ auto test_node = std::make_shared<EmptyLifecycleNode>(" testnode" );
165200
166201 auto success = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS;
167202 auto reset_key = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::ERROR;
@@ -188,6 +223,25 @@ TEST_F(TestDefaultStateMachine, trigger_transition_with_error_code) {
188223 EXPECT_EQ (success, ret);
189224}
190225
226+ TEST_F (TestDefaultStateMachine, call_transitions_without_code) {
227+ auto test_node = std::make_shared<EmptyLifecycleNode>(" testnode" );
228+
229+ auto configured = test_node->configure ();
230+ EXPECT_EQ (configured.id (), State::PRIMARY_STATE_INACTIVE);
231+
232+ auto activated = test_node->activate ();
233+ EXPECT_EQ (activated.id (), State::PRIMARY_STATE_ACTIVE);
234+
235+ auto deactivated = test_node->deactivate ();
236+ EXPECT_EQ (deactivated.id (), State::PRIMARY_STATE_INACTIVE);
237+
238+ auto unconfigured = test_node->cleanup ();
239+ EXPECT_EQ (unconfigured.id (), State::PRIMARY_STATE_UNCONFIGURED);
240+
241+ auto finalized = test_node->shutdown ();
242+ EXPECT_EQ (finalized.id (), State::PRIMARY_STATE_FINALIZED);
243+ }
244+
191245TEST_F (TestDefaultStateMachine, good_mood) {
192246 auto test_node = std::make_shared<MoodyLifecycleNode<GoodMood>>(" testnode" );
193247
@@ -233,3 +287,259 @@ TEST_F(TestDefaultStateMachine, lifecycle_subscriber) {
233287
234288 SUCCEED ();
235289}
290+
291+ // Parameters are tested more thoroughly in rclcpp's test_node.cpp
292+ // These are provided for coverage of lifecycle node's API
293+ TEST_F (TestDefaultStateMachine, declare_parameters) {
294+ auto test_node = std::make_shared<EmptyLifecycleNode>(" testnode" );
295+
296+ auto list_result = test_node->list_parameters ({}, 0u );
297+ EXPECT_EQ (list_result.names .size (), 1u );
298+ EXPECT_STREQ (list_result.names [0 ].c_str (), " use_sim_time" );
299+
300+ const std::string bool_name = " test_boolean" ;
301+ const std::string int_name = " test_int" ;
302+
303+ // Default descriptor overload
304+ test_node->declare_parameter (bool_name, rclcpp::ParameterValue (false ));
305+
306+ // Explicit descriptor overload
307+ rcl_interfaces::msg::ParameterDescriptor int_descriptor;
308+ int_descriptor.name = int_name;
309+ int_descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
310+ int_descriptor.description = " Example integer parameter" ;
311+ test_node->declare_parameter (int_name, rclcpp::ParameterValue (42 ), int_descriptor);
312+
313+ std::map<std::string, std::string> str_parameters;
314+ str_parameters[" str_one" ] = " stringy_string" ;
315+ str_parameters[" str_two" ] = " stringy_string_string" ;
316+
317+ // Default descriptor overload
318+ test_node->declare_parameters (" test_string" , str_parameters);
319+
320+ std::map<std::string,
321+ std::pair<double , rcl_interfaces::msg::ParameterDescriptor>> double_parameters;
322+ rcl_interfaces::msg::ParameterDescriptor double_descriptor_one;
323+ double_descriptor_one.name = " double_one" ;
324+ double_descriptor_one.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE;
325+ double_parameters[" double_one" ] = std::make_pair (1.0 , double_descriptor_one);
326+
327+ rcl_interfaces::msg::ParameterDescriptor double_descriptor_two;
328+ double_descriptor_two.name = " double_two" ;
329+ double_descriptor_two.type = rcl_interfaces::msg::ParameterType::PARAMETER_DOUBLE;
330+ double_parameters[" double_two" ] = std::make_pair (2.0 , double_descriptor_two);
331+
332+ // Explicit descriptor overload
333+ test_node->declare_parameters (" test_double" , double_parameters);
334+
335+ list_result = test_node->list_parameters ({}, 0u );
336+ EXPECT_EQ (list_result.names .size (), 7u );
337+
338+ // The order of these names is not controlled by lifecycle_node, doing set equality
339+ std::set<std::string> expected_names = {
340+ " test_boolean" ,
341+ " test_double.double_one" ,
342+ " test_double.double_two" ,
343+ " test_int" ,
344+ " test_string.str_one" ,
345+ " test_string.str_two" ,
346+ " use_sim_time" ,
347+ };
348+ std::set<std::string> actual_names (list_result.names .begin (), list_result.names .end ());
349+
350+ EXPECT_EQ (expected_names, actual_names);
351+ }
352+
353+ TEST_F (TestDefaultStateMachine, check_parameters) {
354+ auto test_node = std::make_shared<EmptyLifecycleNode>(" testnode" );
355+
356+ auto list_result = test_node->list_parameters ({}, 0u );
357+ EXPECT_EQ (list_result.names .size (), 1u );
358+ EXPECT_STREQ (list_result.names [0 ].c_str (), " use_sim_time" );
359+
360+ const std::string bool_name = " test_boolean" ;
361+ const std::string int_name = " test_int" ;
362+ std::vector<std::string> parameter_names = {bool_name, int_name};
363+
364+ EXPECT_FALSE (test_node->has_parameter (bool_name));
365+ EXPECT_FALSE (test_node->has_parameter (int_name));
366+ EXPECT_THROW (
367+ test_node->get_parameters (parameter_names),
368+ rclcpp::exceptions::ParameterNotDeclaredException);
369+
370+ // Default descriptor overload
371+ test_node->declare_parameter (bool_name, rclcpp::ParameterValue (true ));
372+
373+ // Explicit descriptor overload
374+ rcl_interfaces::msg::ParameterDescriptor int_descriptor;
375+ int_descriptor.name = int_name;
376+ int_descriptor.type = rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER;
377+ int_descriptor.description = " Example integer parameter" ;
378+ test_node->declare_parameter (int_name, rclcpp::ParameterValue (42 ), int_descriptor);
379+
380+ // describe parameters
381+ auto descriptors = test_node->describe_parameters (parameter_names);
382+ EXPECT_EQ (descriptors.size (), parameter_names.size ());
383+
384+ EXPECT_THROW (
385+ test_node->describe_parameter (" not_a_real_parameter" ),
386+ rclcpp::exceptions::ParameterNotDeclaredException);
387+
388+ // describe parameter matches explicit descriptor
389+ auto descriptor = test_node->describe_parameter (int_name);
390+ EXPECT_STREQ (descriptor.name .c_str (), int_descriptor.name .c_str ());
391+ EXPECT_EQ (descriptor.type , int_descriptor.type );
392+ EXPECT_STREQ (descriptor.description .c_str (), int_descriptor.description .c_str ());
393+
394+ // bool parameter exists and value matches
395+ EXPECT_TRUE (test_node->has_parameter (bool_name));
396+ EXPECT_EQ (test_node->get_parameter (bool_name).as_bool (), true );
397+
398+ // int parameter exists and value matches
399+ EXPECT_TRUE (test_node->has_parameter (int_name));
400+ EXPECT_EQ (test_node->get_parameter (int_name).as_int (), 42 );
401+
402+ // Get multiple parameters at a time
403+ auto parameters = test_node->get_parameters (parameter_names);
404+ EXPECT_EQ (parameters.size (), parameter_names.size ());
405+ EXPECT_EQ (parameters[0 ].as_bool (), true );
406+ EXPECT_EQ (parameters[1 ].as_int (), 42 );
407+
408+ // Get multiple parameters at a time with map
409+ std::map<std::string, rclcpp::ParameterValue> parameter_map;
410+ EXPECT_TRUE (test_node->get_parameters ({}, parameter_map));
411+
412+ // int param, bool param, and use_sim_time
413+ EXPECT_EQ (parameter_map.size (), 3u );
414+
415+ // Check parameter types
416+ auto parameter_types = test_node->get_parameter_types (parameter_names);
417+ EXPECT_EQ (parameter_types.size (), parameter_names.size ());
418+ EXPECT_EQ (parameter_types[0 ], rcl_interfaces::msg::ParameterType::PARAMETER_BOOL);
419+ EXPECT_EQ (parameter_types[1 ], rcl_interfaces::msg::ParameterType::PARAMETER_INTEGER);
420+
421+ // Setting parameters
422+ size_t parameters_set = 0 ;
423+ auto callback = [¶meters_set](const std::vector<rclcpp::Parameter> & parameters) {
424+ parameters_set += parameters.size ();
425+ rcl_interfaces::msg::SetParametersResult result;
426+ result.successful = true ;
427+ return result;
428+ };
429+
430+ test_node->set_on_parameters_set_callback (callback);
431+ rclcpp::Parameter bool_parameter (bool_name, rclcpp::ParameterValue (false ));
432+ EXPECT_TRUE (test_node->set_parameter (bool_parameter).successful );
433+ EXPECT_EQ (parameters_set, 1u );
434+
435+ rclcpp::Parameter int_parameter (int_name, rclcpp::ParameterValue (7 ));
436+ test_node->set_parameters ({int_parameter});
437+ EXPECT_EQ (parameters_set, 2u );
438+
439+ // List parameters
440+ list_result = test_node->list_parameters ({}, 0u );
441+ EXPECT_EQ (list_result.names .size (), 3u );
442+ EXPECT_STREQ (list_result.names [0 ].c_str (), parameter_names[0 ].c_str ());
443+ EXPECT_STREQ (list_result.names [1 ].c_str (), parameter_names[1 ].c_str ());
444+ EXPECT_STREQ (list_result.names [2 ].c_str (), " use_sim_time" );
445+
446+ // Undeclare parameter
447+ test_node->undeclare_parameter (bool_name);
448+ EXPECT_FALSE (test_node->has_parameter (bool_name));
449+ rclcpp::Parameter parameter;
450+ EXPECT_FALSE (test_node->get_parameter (bool_name, parameter));
451+
452+ // Bool parameter has been undeclared, atomic setting should fail
453+ parameters = {
454+ rclcpp::Parameter (bool_name, rclcpp::ParameterValue (true )),
455+ rclcpp::Parameter (int_name, rclcpp::ParameterValue (0 ))};
456+ EXPECT_THROW (
457+ test_node->set_parameters_atomically (parameters),
458+ rclcpp::exceptions::ParameterNotDeclaredException);
459+
460+ // Since setting parameters failed, this should remain the same
461+ EXPECT_EQ (test_node->get_parameter (int_name).as_int (), 7 );
462+
463+ // Bool parameter no longer exists, using "or" value
464+ EXPECT_FALSE (
465+ test_node->get_parameter_or (
466+ bool_name, parameter, rclcpp::Parameter (bool_name, rclcpp::ParameterValue (true ))));
467+ EXPECT_TRUE (parameter.as_bool ());
468+ }
469+
470+ TEST_F (TestDefaultStateMachine, test_getters) {
471+ auto test_node = std::make_shared<EmptyLifecycleNode>(" testnode" );
472+ auto options = test_node->get_node_options ();
473+ EXPECT_EQ (0u , options.arguments ().size ());
474+ EXPECT_NE (nullptr , test_node->get_node_base_interface ());
475+ EXPECT_NE (nullptr , test_node->get_node_clock_interface ());
476+ EXPECT_NE (nullptr , test_node->get_node_graph_interface ());
477+ EXPECT_NE (nullptr , test_node->get_node_logging_interface ());
478+ EXPECT_NE (nullptr , test_node->get_node_time_source_interface ());
479+ EXPECT_NE (nullptr , test_node->get_node_timers_interface ());
480+ EXPECT_NE (nullptr , test_node->get_node_topics_interface ());
481+ EXPECT_NE (nullptr , test_node->get_node_services_interface ());
482+ EXPECT_NE (nullptr , test_node->get_node_parameters_interface ());
483+ EXPECT_NE (nullptr , test_node->get_node_waitables_interface ());
484+ EXPECT_NE (nullptr , test_node->get_graph_event ());
485+ EXPECT_NE (nullptr , test_node->get_clock ());
486+ EXPECT_LT (0u , test_node->now ().nanoseconds ());
487+ EXPECT_STREQ (" testnode" , test_node->get_logger ().get_name ());
488+ EXPECT_NE (nullptr , const_cast <const EmptyLifecycleNode *>(test_node.get ())->get_clock ());
489+ }
490+
491+ TEST_F (TestDefaultStateMachine, test_graph) {
492+ auto test_node = std::make_shared<EmptyLifecycleNode>(" testnode" );
493+ auto names = test_node->get_node_names ();
494+ EXPECT_EQ (names.size (), 1u );
495+ EXPECT_STREQ (names[0 ].c_str (), " /testnode" );
496+
497+ // parameter_events, rosout, /testnode/transition_event
498+ auto topic_names_and_types = test_node->get_topic_names_and_types ();
499+ EXPECT_EQ (topic_names_and_types.size (), 3u );
500+ EXPECT_STREQ (
501+ topic_names_and_types[" /testnode/transition_event" ][0 ].c_str (),
502+ " lifecycle_msgs/msg/TransitionEvent" );
503+
504+ auto service_names_and_types = test_node->get_service_names_and_types ();
505+ EXPECT_EQ (service_names_and_types.size (), 11u );
506+ // These are specific to lifecycle nodes, other services are provided by rclcpp::Node
507+ EXPECT_STREQ (
508+ service_names_and_types[" /testnode/change_state" ][0 ].c_str (),
509+ " lifecycle_msgs/srv/ChangeState" );
510+ EXPECT_STREQ (
511+ service_names_and_types[" /testnode/get_available_states" ][0 ].c_str (),
512+ " lifecycle_msgs/srv/GetAvailableStates" );
513+ EXPECT_STREQ (
514+ service_names_and_types[" /testnode/get_available_transitions" ][0 ].c_str (),
515+ " lifecycle_msgs/srv/GetAvailableTransitions" );
516+ EXPECT_STREQ (
517+ service_names_and_types[" /testnode/get_state" ][0 ].c_str (),
518+ " lifecycle_msgs/srv/GetState" );
519+ EXPECT_STREQ (
520+ service_names_and_types[" /testnode/get_transition_graph" ][0 ].c_str (),
521+ " lifecycle_msgs/srv/GetAvailableTransitions" );
522+
523+ EXPECT_EQ (1u , test_node->count_publishers (" /testnode/transition_event" ));
524+ EXPECT_EQ (0u , test_node->count_subscribers (" /testnode/transition_event" ));
525+
526+ auto publishers_info = test_node->get_publishers_info_by_topic (" /testnode/transition_event" );
527+ EXPECT_EQ (publishers_info.size (), 1u );
528+ auto subscriptions_info =
529+ test_node->get_subscriptions_info_by_topic (" /testnode/transition_event" );
530+ EXPECT_EQ (subscriptions_info.size (), 0u );
531+ }
532+
533+ TEST_F (TestDefaultStateMachine, test_callback_groups) {
534+ auto test_node = std::make_shared<EmptyLifecycleNode>(" testnode" );
535+ auto groups = test_node->get_callback_groups ();
536+ EXPECT_EQ (groups.size (), 1u );
537+
538+ auto group = test_node->create_callback_group (
539+ rclcpp::callback_group::CallbackGroupType::MutuallyExclusive);
540+ EXPECT_NE (nullptr , group);
541+
542+ groups = test_node->get_callback_groups ();
543+ EXPECT_EQ (groups.size (), 2u );
544+ EXPECT_EQ (groups[1 ].lock ().get (), group.get ());
545+ }
0 commit comments