|
25 | 25 | #include "lifecycle_msgs/msg/transition.hpp" |
26 | 26 |
|
27 | 27 | #include "rcl_lifecycle/rcl_lifecycle.h" |
| 28 | +#include "rcl_interfaces/srv/get_logger_levels.hpp" |
| 29 | +#include "rcl_interfaces/srv/set_logger_levels.hpp" |
28 | 30 |
|
29 | 31 | #include "rclcpp/rclcpp.hpp" |
30 | 32 | #include "rclcpp_lifecycle/lifecycle_node.hpp" |
|
34 | 36 | using lifecycle_msgs::msg::State; |
35 | 37 | using lifecycle_msgs::msg::Transition; |
36 | 38 |
|
| 39 | +using namespace std::chrono_literals; |
| 40 | + |
37 | 41 | static const std::chrono::nanoseconds DEFAULT_EVENT_TIMEOUT = std::chrono::seconds(3); |
38 | 42 | static const std::chrono::nanoseconds DEFAULT_EVENT_SLEEP_PERIOD = std::chrono::milliseconds(100); |
39 | 43 |
|
@@ -249,6 +253,35 @@ TEST_F(TestDefaultStateMachine, empty_initializer_rcl_errors) { |
249 | 253 | } |
250 | 254 | } |
251 | 255 |
|
| 256 | +TEST_F(TestDefaultStateMachine, check_logger_services_exist) { |
| 257 | + // Logger level services are disabled |
| 258 | + { |
| 259 | + rclcpp::NodeOptions options = rclcpp::NodeOptions(); |
| 260 | + options.enable_logger_service(false); |
| 261 | + auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>( |
| 262 | + "test_logger_service", "/test", options); |
| 263 | + auto get_client = node->create_client<rcl_interfaces::srv::GetLoggerLevels>( |
| 264 | + "/test/test_logger_service/get_logger_levels"); |
| 265 | + ASSERT_FALSE(get_client->wait_for_service(2s)); |
| 266 | + auto set_client = node->create_client<rcl_interfaces::srv::SetLoggerLevels>( |
| 267 | + "/test/test_logger_service/set_logger_levels"); |
| 268 | + ASSERT_FALSE(set_client->wait_for_service(2s)); |
| 269 | + } |
| 270 | + // Logger level services are enabled |
| 271 | + { |
| 272 | + rclcpp::NodeOptions options = rclcpp::NodeOptions(); |
| 273 | + options.enable_logger_service(true); |
| 274 | + auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>( |
| 275 | + "test_logger_service", "/test", options); |
| 276 | + auto get_client = node->create_client<rcl_interfaces::srv::GetLoggerLevels>( |
| 277 | + "/test/test_logger_service/get_logger_levels"); |
| 278 | + ASSERT_TRUE(get_client->wait_for_service(2s)); |
| 279 | + auto set_client = node->create_client<rcl_interfaces::srv::SetLoggerLevels>( |
| 280 | + "/test/test_logger_service/set_logger_levels"); |
| 281 | + ASSERT_TRUE(set_client->wait_for_service(2s)); |
| 282 | + } |
| 283 | +} |
| 284 | + |
252 | 285 | TEST_F(TestDefaultStateMachine, trigger_transition) { |
253 | 286 | auto test_node = std::make_shared<EmptyLifecycleNode>("testnode"); |
254 | 287 |
|
|
0 commit comments