ros_log_sink.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #include "cartographer_ros/ros_log_sink.h"
00018 
00019 #include <chrono>
00020 #include <cstring>
00021 #include <string>
00022 #include <thread>
00023 
00024 #include "glog/log_severity.h"
00025 #include "ros/console.h"
00026 
00027 namespace cartographer_ros {
00028 
00029 namespace {
00030 
00031 const char* GetBasename(const char* filepath) {
00032   const char* base = std::strrchr(filepath, '/');
00033   return base ? (base + 1) : filepath;
00034 }
00035 
00036 }  // namespace
00037 
00038 ScopedRosLogSink::ScopedRosLogSink() : will_die_(false) { AddLogSink(this); }
00039 ScopedRosLogSink::~ScopedRosLogSink() { RemoveLogSink(this); }
00040 
00041 void ScopedRosLogSink::send(const ::google::LogSeverity severity,
00042                             const char* const filename,
00043                             const char* const base_filename, const int line,
00044                             const struct std::tm* const tm_time,
00045                             const char* const message,
00046                             const size_t message_len) {
00047   const std::string message_string = ::google::LogSink::ToString(
00048       severity, GetBasename(filename), line, tm_time, message, message_len);
00049   switch (severity) {
00050     case ::google::GLOG_INFO:
00051       ROS_INFO_STREAM(message_string);
00052       break;
00053 
00054     case ::google::GLOG_WARNING:
00055       ROS_WARN_STREAM(message_string);
00056       break;
00057 
00058     case ::google::GLOG_ERROR:
00059       ROS_ERROR_STREAM(message_string);
00060       break;
00061 
00062     case ::google::GLOG_FATAL:
00063       ROS_FATAL_STREAM(message_string);
00064       will_die_ = true;
00065       break;
00066   }
00067 }
00068 
00069 void ScopedRosLogSink::WaitTillSent() {
00070   if (will_die_) {
00071     // Give ROS some time to actually publish our message.
00072     std::this_thread::sleep_for(std::chrono::milliseconds(1000));
00073   }
00074 }
00075 
00076 }  // namespace cartographer_ros


cartographer_ros
Author(s): The Cartographer Authors
autogenerated on Wed Jul 10 2019 04:10:28