Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Allow disabling rosout file logging (to rosout.log) (#1381) #1413

Merged
merged 1 commit into from May 28, 2018
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
43 changes: 27 additions & 16 deletions tools/rosout/rosout.cpp
Expand Up @@ -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_));
}
}
}
}
Expand All @@ -120,6 +126,11 @@ class Rosout
{
agg_pub_.publish(msg);

if (!handle_)
{
return;
}

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