Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

add logger level service to lifecycle node. #2277

Merged
merged 2 commits into from
Aug 26, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions rclcpp_lifecycle/src/lifecycle_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -144,6 +144,10 @@ LifecycleNode::LifecycleNode(
&LifecycleNodeInterface::on_deactivate, this,
std::placeholders::_1));
register_on_error(std::bind(&LifecycleNodeInterface::on_error, this, std::placeholders::_1));

if (options.enable_logger_service()) {
node_logging_->create_logger_services(node_services_);
}
}

LifecycleNode::~LifecycleNode()
Expand Down
33 changes: 33 additions & 0 deletions rclcpp_lifecycle/test/test_lifecycle_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@
#include "lifecycle_msgs/msg/transition.hpp"

#include "rcl_lifecycle/rcl_lifecycle.h"
#include "rcl_interfaces/srv/get_logger_levels.hpp"
#include "rcl_interfaces/srv/set_logger_levels.hpp"

#include "rclcpp/rclcpp.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
Expand All @@ -34,6 +36,8 @@
using lifecycle_msgs::msg::State;
using lifecycle_msgs::msg::Transition;

using namespace std::chrono_literals;

static const std::chrono::nanoseconds DEFAULT_EVENT_TIMEOUT = std::chrono::seconds(3);
static const std::chrono::nanoseconds DEFAULT_EVENT_SLEEP_PERIOD = std::chrono::milliseconds(100);

Expand Down Expand Up @@ -249,6 +253,35 @@ TEST_F(TestDefaultStateMachine, empty_initializer_rcl_errors) {
}
}

TEST_F(TestDefaultStateMachine, check_logger_services_exist) {
// Logger level services are disabled
{
rclcpp::NodeOptions options = rclcpp::NodeOptions();
options.enable_logger_service(false);
auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>(
"test_logger_service", "/test", options);
auto get_client = node->create_client<rcl_interfaces::srv::GetLoggerLevels>(
"/test/test_logger_service/get_logger_levels");
ASSERT_FALSE(get_client->wait_for_service(2s));
auto set_client = node->create_client<rcl_interfaces::srv::SetLoggerLevels>(
"/test/test_logger_service/set_logger_levels");
ASSERT_FALSE(set_client->wait_for_service(2s));
}
// Logger level services are enabled
{
rclcpp::NodeOptions options = rclcpp::NodeOptions();
options.enable_logger_service(true);
auto node = std::make_shared<rclcpp_lifecycle::LifecycleNode>(
"test_logger_service", "/test", options);
auto get_client = node->create_client<rcl_interfaces::srv::GetLoggerLevels>(
"/test/test_logger_service/get_logger_levels");
ASSERT_TRUE(get_client->wait_for_service(2s));
auto set_client = node->create_client<rcl_interfaces::srv::SetLoggerLevels>(
"/test/test_logger_service/set_logger_levels");
ASSERT_TRUE(set_client->wait_for_service(2s));
}
}

TEST_F(TestDefaultStateMachine, trigger_transition) {
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");

Expand Down