forked from ros2/demos
-
Notifications
You must be signed in to change notification settings - Fork 0
/
logger_usage_component.cpp
105 lines (88 loc) · 3.71 KB
/
logger_usage_component.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
// Copyright 2017 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include "logging_demo/logger_usage_component.hpp"
#include <cinttypes>
#include <iostream>
#include <memory>
#include <string>
#include <utility>
#include "rclcpp/rclcpp.hpp"
#include "rcutils/error_handling.h"
#include "std_msgs/msg/string.hpp"
using namespace std::chrono_literals;
namespace logging_demo
{
LoggerUsage::LoggerUsage(rclcpp::NodeOptions options)
: Node("logger_usage_demo", options), count_(0)
{
pub_ = create_publisher<std_msgs::msg::String>("logging_demo_count", 10);
timer_ = create_wall_timer(500ms, [this]() {return this->on_timer();});
debug_function_to_evaluate_ = [this]() {
return is_divisor_of_twelve(std::cref(this->count_), this->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_logger(), "Setting severity threshold to DEBUG");
// TODO(dhood): allow configuration through rclcpp
auto ret = rcutils_logging_set_logger_level(
get_logger().get_name(), RCUTILS_LOG_SEVERITY_DEBUG);
if (ret != RCUTILS_RET_OK) {
RCLCPP_ERROR(get_logger(), "Error setting severity: %s", rcutils_get_error_string().str);
rcutils_reset_error();
}
};
one_shot_timer_ = create_wall_timer(5500ms, on_one_shot_timer);
}
void LoggerUsage::on_timer()
{
// This message will be logged only the first time this line is reached.
RCLCPP_INFO_ONCE(get_logger(), "Timer callback called (this will only log once)");
auto msg = std::make_unique<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_logger(), "Publishing: '%s'", msg->data.c_str());
pub_->publish(std::move(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_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_logger(), (count_ % 2) == 0, "Count is even (expression evaluated to true)");
if (count_++ >= 15) {
RCLCPP_WARN(get_logger(), "Reseting count to 0");
count_ = 0;
}
}
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, "Modulo divisor cannot be 0");
return false;
}
return (12 % val) == 0;
}
} // namespace logging_demo
#include "rclcpp_components/register_node_macro.hpp"
// Register the component with class_loader.
// This acts as a sort of entry point, allowing the component to be discoverable when its library
// is being loaded into a running process.
RCLCPP_COMPONENTS_REGISTER_NODE(logging_demo::LoggerUsage)