forked from ros2/rclcpp
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathlogger.cpp
More file actions
83 lines (74 loc) · 2.3 KB
/
logger.cpp
File metadata and controls
83 lines (74 loc) · 2.3 KB
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
// 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 <string>
#include "rcl_logging_interface/rcl_logging_interface.h"
#include "rclcpp/exceptions.hpp"
#include "rclcpp/logger.hpp"
#include "rclcpp/logging.hpp"
namespace rclcpp
{
Logger
get_logger(const std::string & name)
{
#if RCLCPP_LOGGING_ENABLED
return rclcpp::Logger(name);
#else
(void)name;
return rclcpp::Logger();
#endif
}
Logger
get_node_logger(const rcl_node_t * node)
{
const char * logger_name = rcl_node_get_logger_name(node);
if (nullptr == logger_name) {
auto logger = rclcpp::get_logger("rclcpp");
RCLCPP_ERROR(
logger, "failed to get logger name from node at address %p",
static_cast<void *>(const_cast<rcl_node_t *>(node)));
return logger;
}
return rclcpp::get_logger(logger_name);
}
rcpputils::fs::path
get_logging_directory()
{
char * log_dir = NULL;
auto allocator = rcutils_get_default_allocator();
rcl_logging_ret_t ret = rcl_logging_get_logging_directory(allocator, &log_dir);
if (RCL_LOGGING_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret);
}
std::string path{log_dir};
allocator.deallocate(log_dir, allocator.state);
return path;
}
void
Logger::set_level(Level level)
{
rcutils_ret_t rcutils_ret = rcutils_logging_set_logger_level(
get_name(),
static_cast<RCUTILS_LOG_SEVERITY>(level));
if (rcutils_ret != RCUTILS_RET_OK) {
if (rcutils_ret == RCUTILS_RET_INVALID_ARGUMENT) {
exceptions::throw_from_rcl_error(
RCL_RET_INVALID_ARGUMENT, "Invalid parameter",
rcutils_get_error_state(), rcutils_reset_error);
}
exceptions::throw_from_rcl_error(
RCL_RET_ERROR, "Couldn't set logger level",
rcutils_get_error_state(), rcutils_reset_error);
}
}
} // namespace rclcpp