ros_log_sink.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2016 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
18 
19 #include <chrono>
20 #include <cstring>
21 #include <string>
22 #include <thread>
23 
24 #include "glog/log_severity.h"
25 #include "ros/console.h"
26 
27 namespace cartographer_ros {
28 
29 namespace {
30 
31 const char* GetBasename(const char* filepath) {
32  const char* base = std::strrchr(filepath, '/');
33  return base ? (base + 1) : filepath;
34 }
35 
36 } // namespace
37 
38 ScopedRosLogSink::ScopedRosLogSink() : will_die_(false) { AddLogSink(this); }
39 ScopedRosLogSink::~ScopedRosLogSink() { RemoveLogSink(this); }
40 
41 void ScopedRosLogSink::send(const ::google::LogSeverity severity,
42  const char* const filename,
43  const char* const base_filename, const int line,
44  const struct std::tm* const tm_time,
45  const char* const message,
46  const size_t message_len) {
47  const std::string message_string = ::google::LogSink::ToString(
48  severity, GetBasename(filename), line, tm_time, message, message_len);
49  switch (severity) {
50  case ::google::GLOG_INFO:
51  ROS_INFO_STREAM(message_string);
52  break;
53 
54  case ::google::GLOG_WARNING:
55  ROS_WARN_STREAM(message_string);
56  break;
57 
58  case ::google::GLOG_ERROR:
59  ROS_ERROR_STREAM(message_string);
60  break;
61 
62  case ::google::GLOG_FATAL:
63  ROS_FATAL_STREAM(message_string);
64  will_die_ = true;
65  break;
66  }
67 }
68 
70  if (will_die_) {
71  // Give ROS some time to actually publish our message.
72  std::this_thread::sleep_for(std::chrono::milliseconds(1000));
73  }
74 }
75 
76 } // namespace cartographer_ros
#define ROS_FATAL_STREAM(args)
void send(::google::LogSeverity severity, const char *filename, const char *base_filename, int line, const struct std::tm *tm_time, const char *message, size_t message_len) override
Definition: ros_log_sink.cc:41
#define ROS_WARN_STREAM(args)
#define ROS_INFO_STREAM(args)
#define ROS_ERROR_STREAM(args)


cartographer_ros
Author(s):
autogenerated on Mon Jun 10 2019 12:59:40