From dac6635612083c0bb04cdbef172d4bce90002e69 Mon Sep 17 00:00:00 2001 From: Yong Li <30503431+yli-cpr@users.noreply.github.com> Date: Fri, 18 May 2018 18:27:13 -0400 Subject: [PATCH] Allow disabling rosout file logging (to rosout.log) (#1381) See issue #1380. --- tools/rosout/rosout.cpp | 43 ++++++++++++++++++++++++++--------------- 1 file changed, 27 insertions(+), 16 deletions(-) diff --git a/tools/rosout/rosout.cpp b/tools/rosout/rosout.cpp index e1f15712b6..60cf870271 100644 --- a/tools/rosout/rosout.cpp +++ b/tools/rosout/rosout.cpp @@ -82,29 +82,35 @@ class Rosout void init() { - handle_ = fopen(log_file_name_.c_str(), "w"); + bool disable_file_logging = false; + node_.getParamCached("/rosout/disable_file_logging", disable_file_logging); - if (handle_ == 0) + if (!disable_file_logging) { - std::cerr << "Error opening rosout log file '" << log_file_name_.c_str() << "': " << strerror(errno); - } - else - { - std::cout << "logging to " << log_file_name_.c_str() << std::endl; + handle_ = fopen(log_file_name_.c_str(), "w"); - std::stringstream ss; - ss << "\n\n" << ros::Time::now() << " Node Startup\n"; - int written = fprintf(handle_, "%s", ss.str().c_str()); - if (written < 0) + if (handle_ == 0) { - std::cerr << "Error writting to rosout log file '" << log_file_name_.c_str() << "': " << strerror(ferror(handle_)) << std::endl; + std::cerr << "Error opening rosout log file '" << log_file_name_.c_str() << "': " << strerror(errno); } - else if (written > 0) + else { - current_file_size_ += written; - if (fflush(handle_)) + std::cout << "logging to " << log_file_name_.c_str() << std::endl; + + std::stringstream ss; + ss << "\n\n" << ros::Time::now() << " Node Startup\n"; + int written = fprintf(handle_, "%s", ss.str().c_str()); + if (written < 0) + { + std::cerr << "Error writting to rosout log file '" << log_file_name_.c_str() << "': " << strerror(ferror(handle_)) << std::endl; + } + else if (written > 0) { - std::cerr << "Error flushing rosout log file '" << log_file_name_.c_str() << "': " << strerror(ferror(handle_)); + current_file_size_ += written; + if (fflush(handle_)) + { + std::cerr << "Error flushing rosout log file '" << log_file_name_.c_str() << "': " << strerror(ferror(handle_)); + } } } } @@ -120,6 +126,11 @@ class Rosout { agg_pub_.publish(msg); + if (!handle_) + { + return; + } + std::stringstream ss; ss << msg->header.stamp << " "; switch (msg->level)