Skip to content

Commit

Permalink
Swap logging_demo to using logger object
Browse files Browse the repository at this point in the history
  • Loading branch information
dhood committed Dec 4, 2017
1 parent 58fe8a5 commit 5eda3de
Show file tree
Hide file tree
Showing 3 changed files with 17 additions and 15 deletions.
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

0 comments on commit 5eda3de

Please sign in to comment.