rosout.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <cstring>
31 #include <cstdlib>
32 #include <cctype>
33 
34 #include "ros/ros.h"
35 #include "ros/file_log.h"
36 
37 #ifdef WIN32
38  #ifdef ERROR
39  // ach, windows.h polluting everything again,
40  // clashes with autogenerated rosgraph_msgs/Log.h
41  #undef ERROR
42  #endif
43 #endif
44 #include "rosgraph_msgs/Log.h"
45 
58 class Rosout
59 {
60 public:
61  std::string log_file_name_;
62  FILE* handle_;
71 
72  Rosout() :
73  log_file_name_(ros::file_log::getLogDirectory() + "/rosout.log"),
74  handle_(NULL),
75  max_file_size_(100*1024*1024),
76  current_file_size_(0),
77  max_backup_index_(10),
78  current_backup_index_(0),
79  omit_topics_(false)
80  {
81  init();
82  }
83 
84  void init()
85  {
86  const char* disable_file_logging_env = getenv("ROSOUT_DISABLE_FILE_LOGGING");
87  std::string disable_file_logging(disable_file_logging_env ? disable_file_logging_env : "");
88  std::transform(
89  disable_file_logging.begin(),
90  disable_file_logging.end(),
91  disable_file_logging.begin(),
92  [](char c){ return std::tolower(c); });
93  if (disable_file_logging.empty() || // Not set or set to empty string.
94  disable_file_logging == "0" ||
95  disable_file_logging == "false" ||
96  disable_file_logging == "off" ||
97  disable_file_logging == "no")
98  {
99  handle_ = fopen(log_file_name_.c_str(), "w");
100 
101  if (handle_ == 0)
102  {
103  std::cerr << "Error opening rosout log file '" << log_file_name_.c_str() << "': " << strerror(errno);
104  }
105  else
106  {
107  std::cout << "logging to " << log_file_name_.c_str() << std::endl;
108 
109  std::stringstream ss;
110  ss << "\n\n" << ros::Time::now() << " Node Startup\n";
111  int written = fprintf(handle_, "%s", ss.str().c_str());
112  if (written < 0)
113  {
114  std::cerr << "Error writing to rosout log file '" << log_file_name_.c_str() << "': " << strerror(ferror(handle_)) << std::endl;
115  }
116  else if (written > 0)
117  {
118  current_file_size_ += written;
119  if (fflush(handle_))
120  {
121  std::cerr << "Error flushing rosout log file '" << log_file_name_.c_str() << "': " << strerror(ferror(handle_));
122  }
123  }
124  }
125  }
126 
127  agg_pub_ = node_.advertise<rosgraph_msgs::Log>("/rosout_agg", 0);
128  std::cout << "re-publishing aggregated messages to /rosout_agg" << std::endl;
129 
130  rosout_sub_ = node_.subscribe("/rosout", 0, &Rosout::rosoutCallback, this);
131  std::cout << "subscribed to /rosout" << std::endl;
132  }
133 
134  void rosoutCallback(const rosgraph_msgs::Log::ConstPtr& msg)
135  {
136  agg_pub_.publish(msg);
137 
138  if (!handle_)
139  {
140  return;
141  }
142 
143  std::stringstream ss;
144  ss << msg->header.stamp << " ";
145  switch (msg->level)
146  {
147  case rosgraph_msgs::Log::FATAL:
148  ss << "FATAL ";
149  break;
150  case rosgraph_msgs::Log::ERROR:
151  ss << "ERROR ";
152  break;
153  case rosgraph_msgs::Log::WARN:
154  ss << "WARN ";
155  break;
156  case rosgraph_msgs::Log::DEBUG:
157  ss << "DEBUG ";
158  break;
159  case rosgraph_msgs::Log::INFO:
160  ss << "INFO ";
161  break;
162  default:
163  ss << msg->level << " ";
164  }
165 
166  ss << msg->name << " ";
167  ss << "[" << msg->file << ":" << msg->line << "(" << msg->function << ")] ";
168 
169  // check parameter server for omit_topics flag and set class member
170  node_.getParamCached("/rosout/omit_topics", omit_topics_);
171 
172  if (!omit_topics_)
173  {
174  ss << "[topics: ";
175  std::vector<std::string>::const_iterator it = msg->topics.begin();
176  std::vector<std::string>::const_iterator end = msg->topics.end();
177  for ( ; it != end; ++it )
178  {
179  const std::string& topic = *it;
180 
181  if ( it != msg->topics.begin() )
182  {
183  ss << ", ";
184  }
185 
186  ss << topic;
187  }
188  ss << "] ";
189  }
190 
191  ss << msg->msg;
192  ss << "\n";
193  int written = fprintf(handle_, "%s", ss.str().c_str());
194  if (written < 0)
195  {
196  std::cerr << "Error writing to rosout log file '" << log_file_name_.c_str() << "': " << strerror(ferror(handle_)) << std::endl;
197  }
198  else if (written > 0)
199  {
200  current_file_size_ += written;
201  if (fflush(handle_))
202  {
203  std::cerr << "Error flushing rosout log file '" << log_file_name_.c_str() << "': " << strerror(errno);
204  }
205 
206  // check for rolling
207  if (current_file_size_ > max_file_size_)
208  {
209  std::cout << "rosout log file " << log_file_name_.c_str() << " reached max size, rotating log files" << std::endl;
210  if (fclose(handle_))
211  {
212  std::cerr << "Error closing rosout log file '" << log_file_name_.c_str() << "': " << strerror(errno) << std::endl;
213  }
214  if (current_backup_index_ == max_backup_index_)
215  {
216  std::stringstream backup_file_name;
217  backup_file_name << log_file_name_ << "." << max_backup_index_;
218  int rc = remove(backup_file_name.str().c_str());
219  if (rc != 0)
220  {
221  std::cerr << "Error deleting oldest rosout log file '" << backup_file_name.str().c_str() << "': " << strerror(errno) << std::endl;
222  }
223  }
224  std::size_t i = std::min(max_backup_index_, current_backup_index_ + 1);
225  while (i > 0)
226  {
227  std::stringstream current_file_name;
228  current_file_name << log_file_name_;
229  if (i > 1)
230  {
231  current_file_name << "." << (i - 1);
232  }
233  std::stringstream rotated_file_name;
234  rotated_file_name << log_file_name_ << "." << i;
235  int rc = rename(current_file_name.str().c_str(), rotated_file_name.str().c_str());
236  if (rc != 0)
237  {
238  std::cerr << "Error rotating rosout log file '" << current_file_name.str().c_str() << "' to '" << rotated_file_name.str().c_str() << "': " << strerror(errno) << std::endl;
239  }
240  --i;
241  }
242  if (current_backup_index_ < max_backup_index_)
243  {
245  }
246  handle_ = fopen(log_file_name_.c_str(), "w");
247  if (handle_ == 0)
248  {
249  std::cerr << "Error opening rosout log file '" << log_file_name_.c_str() << "': " << strerror(errno);
250  }
251  current_file_size_ = 0;
252  }
253  }
254  }
255 };
256 
257 int main(int argc, char **argv)
258 {
259  ros::init(argc, argv, "rosout", ros::init_options::NoRosout);
260  ros::NodeHandle n;
261  Rosout r;
262 
263  ros::spin();
264 
265  return 0;
266 }
267 
bool omit_topics_
Definition: rosout.cpp:70
FILE * handle_
Definition: rosout.cpp:62
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
size_t max_file_size_
Definition: rosout.cpp:63
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void init()
Definition: rosout.cpp:84
std::string log_file_name_
Definition: rosout.cpp:61
size_t current_backup_index_
Definition: rosout.cpp:66
void publish(const boost::shared_ptr< M > &message) const
size_t current_file_size_
Definition: rosout.cpp:64
ros::NodeHandle node_
Definition: rosout.cpp:67
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void spin()
size_t max_backup_index_
Definition: rosout.cpp:65
ROSCPP_DECL const std::string & getLogDirectory()
bool getParamCached(const std::string &key, std::string &s) const
Rosout()
Definition: rosout.cpp:72
static Time now()
ros::Publisher agg_pub_
Definition: rosout.cpp:69
void rosoutCallback(const rosgraph_msgs::Log::ConstPtr &msg)
Definition: rosout.cpp:134
int main(int argc, char **argv)
Definition: rosout.cpp:257
ros::Subscriber rosout_sub_
Definition: rosout.cpp:68


rosout
Author(s): Josh Faust, Dirk Thomas
autogenerated on Mon Feb 28 2022 23:33:40