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

Swap to using logger object for logging macros #200

Merged
merged 3 commits into from
Dec 5, 2017
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
16 changes: 8 additions & 8 deletions composition/src/api_composition.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ int main(int argc, char * argv[])
if (
!ament_index_cpp::get_resource("node_plugin", request->package_name, content, &base_path))
{
RCLCPP_ERROR(node->get_name(), "Could not find requested resource in ament index")
RCLCPP_ERROR(node->get_logger(), "Could not find requested resource in ament index")
response->success = false;
return;
}
Expand All @@ -98,7 +98,7 @@ int main(int argc, char * argv[])
for (auto line : lines) {
std::vector<std::string> parts = split(line, ';');
if (parts.size() != 2) {
RCLCPP_ERROR(node->get_name(), "Invalid resource entry")
RCLCPP_ERROR(node->get_logger(), "Invalid resource entry")
response->success = false;
return;
}
Expand All @@ -114,23 +114,23 @@ int main(int argc, char * argv[])
if (!fs::path(library_path).is_absolute()) {
library_path = base_path + "/" + library_path;
}
RCLCPP_INFO(node->get_name(), "Load library %s", library_path.c_str())
RCLCPP_INFO(node->get_logger(), "Load library %s", library_path.c_str())
class_loader::ClassLoader * loader;
try {
loader = new class_loader::ClassLoader(library_path);
} catch (const std::exception & ex) {
RCLCPP_ERROR(node->get_name(), "Failed to load library: %s", ex.what())
RCLCPP_ERROR(node->get_logger(), "Failed to load library: %s", ex.what())
response->success = false;
return;
} catch (...) {
RCLCPP_ERROR(node->get_name(), "Failed to load library")
RCLCPP_ERROR(node->get_logger(), "Failed to load library")
response->success = false;
return;
}
auto classes = loader->getAvailableClasses<rclcpp::Node>();
for (auto clazz : classes) {
if (clazz == class_name) {
RCLCPP_INFO(node->get_name(), "Instantiate class %s", clazz.c_str())
RCLCPP_INFO(node->get_logger(), "Instantiate class %s", clazz.c_str())
auto node = loader->createInstance<rclcpp::Node>(clazz);
exec.add_node(node);
nodes.push_back(node);
Expand All @@ -143,14 +143,14 @@ int main(int argc, char * argv[])
// no matching class found in loader
delete loader;
RCLCPP_ERROR(
node->get_name(), "Failed to find class with the requested plugin name '%s' in "
node->get_logger(), "Failed to find class with the requested plugin name '%s' in "
"the loaded library",
request->plugin_name.c_str())
response->success = false;
return;
}
RCLCPP_ERROR(
node->get_name(), "Failed to find plugin name '%s' in prefix '%s'",
node->get_logger(), "Failed to find plugin name '%s' in prefix '%s'",
request->plugin_name.c_str(), base_path.c_str())
response->success = false;
});
Expand Down
12 changes: 6 additions & 6 deletions composition/src/api_composition_cli.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,31 +51,31 @@ int main(int argc, char * argv[])
while (!client->wait_for_service(1s)) {
if (!rclcpp::ok()) {
RCLCPP_ERROR(
node->get_name(),
node->get_logger(),
"Interrupted while waiting for the service. Exiting.")
return 0;
}
RCLCPP_INFO(node->get_name(), "Service not available, waiting again...")
RCLCPP_INFO(node->get_logger(), "Service not available, waiting again...")
}

auto request = std::make_shared<composition::srv::LoadNode::Request>();
request->package_name = argv[1];
request->plugin_name = argv[2];

RCLCPP_INFO(node->get_name(), "Sending request...")
RCLCPP_INFO(node->get_logger(), "Sending request...")
auto result = client->async_send_request(request);
RCLCPP_INFO(node->get_name(), "Waiting for response...")
RCLCPP_INFO(node->get_logger(), "Waiting for response...")
if (rclcpp::spin_until_future_complete(node, result) !=
rclcpp::executor::FutureReturnCode::SUCCESS)
{
RCLCPP_ERROR(node->get_name(), "Interrupted while waiting for response. Exiting.")
RCLCPP_ERROR(node->get_logger(), "Interrupted while waiting for response. Exiting.")
if (!rclcpp::ok()) {
return 0;
}
return 1;
}
RCLCPP_INFO(
node->get_name(), "Result of load_node: success = %s",
node->get_logger(), "Result of load_node: success = %s",
result.get()->success ? "true" : "false")

rclcpp::shutdown();
Expand Down
6 changes: 3 additions & 3 deletions composition/src/client_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,11 +41,11 @@ void Client::on_timer()
if (!client_->wait_for_service(1s)) {
if (!rclcpp::ok()) {
RCLCPP_ERROR(
this->get_name(),
this->get_logger(),
"Interrupted while waiting for the service. Exiting.")
return;
}
RCLCPP_INFO(this->get_name(), "Service not available after waiting")
RCLCPP_INFO(this->get_logger(), "Service not available after waiting")
return;
}

Expand All @@ -66,7 +66,7 @@ void Client::on_timer()
using ServiceResponseFuture =
rclcpp::Client<example_interfaces::srv::AddTwoInts>::SharedFuture;
auto response_received_callback = [this](ServiceResponseFuture future) {
RCLCPP_INFO(this->get_name(), "Got result: [%" PRId64 "]", future.get()->sum)
RCLCPP_INFO(this->get_logger(), "Got result: [%" PRId64 "]", future.get()->sum)
};
auto future_result = client_->async_send_request(request, response_received_callback);
}
Expand Down
5 changes: 3 additions & 2 deletions composition/src/dlopen_composition.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@ int main(int argc, char * argv[])
fprintf(stderr, "Requires at least one argument to be passed with the library to load\n");
return 1;
}
rclcpp::Logger logger = rclcpp::get_logger(DLOPEN_COMPOSITION_LOGGER_NAME);
rclcpp::init(argc, argv);
rclcpp::executors::SingleThreadedExecutor exec;
std::vector<class_loader::ClassLoader *> loaders;
Expand All @@ -37,11 +38,11 @@ int main(int argc, char * argv[])
libraries.push_back(argv[i]);
}
for (auto library : libraries) {
RCLCPP_INFO(DLOPEN_COMPOSITION_LOGGER_NAME, "Load library %s", library.c_str())
RCLCPP_INFO(logger, "Load library %s", library.c_str())
auto loader = new class_loader::ClassLoader(library);
auto classes = loader->getAvailableClasses<rclcpp::Node>();
for (auto clazz : classes) {
RCLCPP_INFO(DLOPEN_COMPOSITION_LOGGER_NAME, "Instantiate class %s", clazz.c_str())
RCLCPP_INFO(logger, "Instantiate class %s", clazz.c_str())
auto node = loader->createInstance<rclcpp::Node>(clazz);
exec.add_node(node);
nodes.push_back(node);
Expand Down
6 changes: 3 additions & 3 deletions image_tools/src/showimage.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,9 +56,9 @@ encoding2mat_type(const std::string & encoding)
/// Convert the ROS Image message to an OpenCV matrix and display it to the user.
// \param[in] msg The image message to show.
void show_image(
const sensor_msgs::msg::Image::SharedPtr msg, bool show_camera, std::string logger_name)
const sensor_msgs::msg::Image::SharedPtr msg, bool show_camera, rclcpp::Logger logger)
{
RCLCPP_INFO(logger_name, "Received image #%s", msg->header.frame_id.c_str())
RCLCPP_INFO(logger, "Received image #%s", msg->header.frame_id.c_str())

if (show_camera) {
// Convert to an OpenCV matrix by assigning the data.
Expand Down Expand Up @@ -136,7 +136,7 @@ int main(int argc, char * argv[])

auto callback = [show_camera, &node](const sensor_msgs::msg::Image::SharedPtr msg)
{
show_image(msg, show_camera, node->get_name());
show_image(msg, show_camera, node->get_logger());
};

printf("Subscribing to topic '%s'\n", topic.c_str());
Expand Down
4 changes: 2 additions & 2 deletions lifecycle/src/lifecycle_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -51,12 +51,12 @@ class LifecycleListener : public rclcpp::Node

void data_callback(const std_msgs::msg::String::SharedPtr msg)
{
RCUTILS_LOG_INFO_NAMED(get_name(), "data_callback: %s", msg->data.c_str())
RCLCPP_INFO(get_logger(), "data_callback: %s", msg->data.c_str())
}

void notification_callback(const lifecycle_msgs::msg::TransitionEvent::SharedPtr msg)
{
RCUTILS_LOG_INFO_NAMED(get_name(), "notify callback: Transition from state %s to %s",
RCLCPP_INFO(get_logger(), "notify callback: Transition from state %s to %s",
msg->start_state.label.c_str(), msg->goal_state.label.c_str())
}

Expand Down
30 changes: 17 additions & 13 deletions lifecycle/src/lifecycle_service_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,9 @@ class LifecycleServiceClient : public rclcpp::Node
auto request = std::make_shared<lifecycle_msgs::srv::GetState::Request>();

if (!client_get_state_->wait_for_service(time_out)) {
RCUTILS_LOG_ERROR("Service %s is not available.",
RCLCPP_ERROR(
get_logger(),
"Service %s is not available.",
client_get_state_->get_service_name().c_str())
return lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN;
}
Expand All @@ -111,19 +113,19 @@ class LifecycleServiceClient : public rclcpp::Node
auto future_status = wait_for_result(future_result, time_out);

if (future_status != std::future_status::ready) {
RCUTILS_LOG_ERROR_NAMED(
get_name(), "Server time out while getting current state for node %s", lifecycle_node)
RCLCPP_ERROR(
get_logger(), "Server time out while getting current state for node %s", lifecycle_node)
return lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN;
}

// We have an succesful answer. So let's print the current state.
if (future_result.get()) {
RCUTILS_LOG_INFO_NAMED(get_name(), "Node %s has current state %s.",
RCLCPP_INFO(get_logger(), "Node %s has current state %s.",
lifecycle_node, future_result.get()->current_state.label.c_str())
return future_result.get()->current_state.id;
} else {
RCUTILS_LOG_ERROR_NAMED(
get_name(), "Failed to get current state for node %s", lifecycle_node)
RCLCPP_ERROR(
get_logger(), "Failed to get current state for node %s", lifecycle_node)
return lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN;
}
}
Expand Down Expand Up @@ -151,7 +153,9 @@ class LifecycleServiceClient : public rclcpp::Node
request->transition.id = transition;

if (!client_change_state_->wait_for_service(time_out)) {
RCUTILS_LOG_ERROR("Service %s is not available.",
RCLCPP_ERROR(
get_logger(),
"Service %s is not available.",
client_change_state_->get_service_name().c_str())
return false;
}
Expand All @@ -164,19 +168,19 @@ class LifecycleServiceClient : public rclcpp::Node
auto future_status = wait_for_result(future_result, time_out);

if (future_status != std::future_status::ready) {
RCUTILS_LOG_ERROR_NAMED(
get_name(), "Server time out while getting current state for node %s", lifecycle_node)
RCLCPP_ERROR(
get_logger(), "Server time out while getting current state for node %s", lifecycle_node)
return false;
}

// We have an answer, let's print our success.
if (future_result.get()->success) {
RCUTILS_LOG_INFO_NAMED(
get_name(), "Transition %d successfully triggered.", static_cast<int>(transition))
RCLCPP_INFO(
get_logger(), "Transition %d successfully triggered.", static_cast<int>(transition))
return true;
} else {
RCUTILS_LOG_WARN_NAMED(
get_name(), "Failed to trigger transition %u", static_cast<unsigned int>(transition));
RCLCPP_WARN(
get_logger(), "Failed to trigger transition %u", static_cast<unsigned int>(transition));
return false;
}
}
Expand Down
10 changes: 5 additions & 5 deletions lifecycle/src/lifecycle_talker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,11 +78,11 @@ class LifecycleTalker : public rclcpp_lifecycle::LifecycleNode

// Print the current state for demo purposes
if (!pub_->is_activated()) {
RCUTILS_LOG_INFO_NAMED(
get_name(), "Lifecycle publisher is currently inactive. Messages are not published.")
RCLCPP_INFO(
get_logger(), "Lifecycle publisher is currently inactive. Messages are not published.")
} else {
RCUTILS_LOG_INFO_NAMED(
get_name(), "Lifecycle publisher is active. Publishing: [%s]", msg_->data.c_str())
RCLCPP_INFO(
get_logger(), "Lifecycle publisher is active. Publishing: [%s]", msg_->data.c_str())
}

// We independently from the current state call publish on the lifecycle
Expand Down Expand Up @@ -119,7 +119,7 @@ class LifecycleTalker : public rclcpp_lifecycle::LifecycleNode
timer_ = this->create_wall_timer(
1s, std::bind(&LifecycleTalker::publish, this));

RCUTILS_LOG_INFO_NAMED(get_name(), "on_configure() is called.")
RCLCPP_INFO(get_logger(), "on_configure() is called.")

// We return a success and hence invoke the transition to the next
// step: "inactive".
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ class LoggerUsage : public rclcpp::Node
std::function<bool()> debug_function_to_evaluate_;
};

bool is_divisor_of_twelve(size_t val, std::string logger_name);
bool is_divisor_of_twelve(size_t val, rclcpp::Logger logger);
} // namespace logging_demo

#endif // LOGGING_DEMO__LOGGER_USAGE_COMPONENT_HPP_
7 changes: 4 additions & 3 deletions logging_demo/src/logger_config_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ LoggerConfig::handle_logger_config_request(
{
const char * severity_string = request->level.c_str();
RCLCPP_INFO(
this->get_name(), "Incoming request: logger '%s', severity '%s'",
this->get_logger(), "Incoming request: logger '%s', severity '%s'",
request->logger_name.c_str(), severity_string);
std::flush(std::cout);
int severity;
Expand All @@ -59,15 +59,16 @@ LoggerConfig::handle_logger_config_request(
severity = RCUTILS_LOG_SEVERITY_UNSET;
} else {
RCLCPP_ERROR(
this->get_name(), "Unknown severity '%s'", severity_string);
this->get_logger(), "Unknown severity '%s'", severity_string);
response->success = false;
return;
}

// TODO(dhood): allow configuration through rclcpp
auto ret = rcutils_logging_set_logger_level(request->logger_name.c_str(), severity);
if (ret != RCUTILS_RET_OK) {
RCLCPP_ERROR(get_name(), "Error setting severity: %s", rcutils_get_error_string_safe());
RCLCPP_ERROR(
this->get_logger(), "Error setting severity: %s", rcutils_get_error_string_safe());
rcutils_reset_error();
response->success = false;
}
Expand Down
23 changes: 12 additions & 11 deletions logging_demo/src/logger_usage_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,18 +33,18 @@ LoggerUsage::LoggerUsage()
{
pub_ = create_publisher<std_msgs::msg::String>("logging_demo_count");
timer_ = create_wall_timer(500ms, std::bind(&LoggerUsage::on_timer, this));
debug_function_to_evaluate_ = std::bind(is_divisor_of_twelve, std::cref(count_), get_name());
debug_function_to_evaluate_ = std::bind(is_divisor_of_twelve, std::cref(count_), get_logger());

// After 10 iterations the severity will be set to DEBUG.
auto on_one_shot_timer =
[this]() -> void {
one_shot_timer_->cancel();
RCLCPP_INFO(get_name(), "Setting logger level to DEBUG")
RCLCPP_INFO(get_logger(), "Setting severity threshold to DEBUG")
// TODO(dhood): allow configuration through rclcpp
auto ret = rcutils_logging_set_logger_level(
get_name(), RCUTILS_LOG_SEVERITY_DEBUG);
get_logger().get_name(), RCUTILS_LOG_SEVERITY_DEBUG);
if (ret != RCUTILS_RET_OK) {
RCLCPP_ERROR(get_name(), "Error setting severity: %s", rcutils_get_error_string_safe());
RCLCPP_ERROR(get_logger(), "Error setting severity: %s", rcutils_get_error_string_safe());
rcutils_reset_error();
}
};
Expand All @@ -54,38 +54,39 @@ LoggerUsage::LoggerUsage()
void LoggerUsage::on_timer()
{
// This message will be logged only the first time this line is reached.
RCLCPP_INFO_ONCE(get_name(), "Timer callback called (this will only log once)")
RCLCPP_INFO_ONCE(get_logger(), "Timer callback called (this will only log once)")

auto msg = std::make_shared<std_msgs::msg::String>();
msg->data = "Current count: " + std::to_string(count_);

// This message will be logged each time it is reached.
RCLCPP_INFO(get_name(), "Publishing: '%s'", msg->data.c_str())
RCLCPP_INFO(get_logger(), "Publishing: '%s'", msg->data.c_str())
pub_->publish(msg);

// This message will be logged when the function evaluates to true.
// The function will only be evaluated when DEBUG severity is enabled.
// This is useful if calculation of debug output is computationally expensive.
RCLCPP_DEBUG_FUNCTION(
get_name(), &debug_function_to_evaluate_, "Count divides into 12 (function evaluated to true)")
get_logger(), &debug_function_to_evaluate_,
"Count divides into 12 (function evaluated to true)")

// This message will be logged when the expression evaluates to true.
// The expression will only be evaluated when DEBUG severity is enabled.
RCLCPP_DEBUG_EXPRESSION(
get_name(), (count_ % 2) == 0, "Count is even (expression evaluated to true)")
get_logger(), (count_ % 2) == 0, "Count is even (expression evaluated to true)")
if (count_++ >= 15) {
RCLCPP_WARN(get_name(), "Reseting count to 0")
RCLCPP_WARN(get_logger(), "Reseting count to 0")
count_ = 0;
}
}

bool is_divisor_of_twelve(size_t val, std::string logger_name)
bool is_divisor_of_twelve(size_t val, rclcpp::Logger logger)
{
// This method is called from within a RCLCPP_DEBUG_FUNCTION() call.
// Therefore it will only be called when DEBUG log messages are enabled.

if (val == 0) {
RCLCPP_ERROR(logger_name, "Modulo divisor cannot be 0")
RCLCPP_ERROR(logger, "Modulo divisor cannot be 0")
return false;
}
return (12 % val) == 0;
Expand Down