Skip to content

Commit

Permalink
Allow disabling rosout file logging (to rosout.log)
Browse files Browse the repository at this point in the history
See issue #1380.
  • Loading branch information
yli-cpr committed May 2, 2018
1 parent 4c8b8f2 commit bfa7dfd
Showing 1 changed file with 28 additions and 18 deletions.
46 changes: 28 additions & 18 deletions tools/rosout/rosout.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
* POSSIBILITY OF SUCH DAMAGE.
*/

#include <boost/algorithm/string.hpp>
#include <cstring>
#include <cstdlib>

Expand Down Expand Up @@ -70,7 +71,7 @@ class Rosout

Rosout() :
log_file_name_(ros::file_log::getLogDirectory() + "/rosout.log"),
handle_(NULL),
handle_(0),
max_file_size_(100*1024*1024),
current_file_size_(0),
max_backup_index_(10),
Expand All @@ -82,29 +83,33 @@ class Rosout

void init()
{
handle_ = fopen(log_file_name_.c_str(), "w");

if (handle_ == 0)
{
std::cerr << "Error opening rosout log file '" << log_file_name_.c_str() << "': " << strerror(errno);
}
else
std::string disable_file_logging(getenv("ROSOUT_DISABLE_FILE_LOGGING"));
if (disable_file_logging.empty() || !boost::iequals(disable_file_logging, "true"))
{
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_)
{
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 flushing rosout log file '" << log_file_name_.c_str() << "': " << strerror(ferror(handle_));
std::cerr << "Error writting to rosout log file '" << log_file_name_.c_str() << "': " << strerror(ferror(handle_)) << std::endl;
}
else if (written > 0)
{
current_file_size_ += written;
if (fflush(handle_))
{
std::cerr << "Error flushing rosout log file '" << log_file_name_.c_str() << "': " << strerror(ferror(handle_));
}
}
}
}
Expand All @@ -120,6 +125,11 @@ class Rosout
{
agg_pub_.publish(msg);

if (!handle_)
{
return;
}

std::stringstream ss;
ss << msg->header.stamp << " ";
switch (msg->level)
Expand Down

0 comments on commit bfa7dfd

Please sign in to comment.