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 
33 #include "ros/ros.h"
34 #include "ros/file_log.h"
35 
36 #ifdef WIN32
37  #ifdef ERROR
38  // ach, windows.h polluting everything again,
39  // clashes with autogenerated rosgraph_msgs/Log.h
40  #undef ERROR
41  #endif
42 #endif
43 #include "rosgraph_msgs/Log.h"
44 
57 class Rosout
58 {
59 public:
60  std::string log_file_name_;
61  FILE* handle_;
69 
71  {
72  init();
73  }
74 
75  void init()
76  {
77  max_file_size_ = 100*1024*1024;
78  current_file_size_ = 0;
79  max_backup_index_ = 10;
80  current_backup_index_ = 0;
81 
82  log_file_name_ = ros::file_log::getLogDirectory() + "/rosout.log";
83  handle_ = fopen(log_file_name_.c_str(), "w");
84 
85  if (handle_ == 0)
86  {
87  std::cerr << "Error opening rosout log file '" << log_file_name_.c_str() << "': " << strerror(errno);
88  }
89  else
90  {
91  std::cout << "logging to " << log_file_name_.c_str() << std::endl;
92 
93  std::stringstream ss;
94  ss << "\n\n" << ros::Time::now() << " Node Startup\n";
95  int written = fprintf(handle_, "%s", ss.str().c_str());
96  if (written < 0)
97  {
98  std::cerr << "Error writting to rosout log file '" << log_file_name_.c_str() << "': " << strerror(ferror(handle_)) << std::endl;
99  }
100  else if (written > 0)
101  {
102  current_file_size_ += written;
103  if (fflush(handle_))
104  {
105  std::cerr << "Error flushing rosout log file '" << log_file_name_.c_str() << "': " << strerror(ferror(handle_));
106  }
107  }
108  }
109 
110  agg_pub_ = node_.advertise<rosgraph_msgs::Log>("/rosout_agg", 0);
111  std::cout << "re-publishing aggregated messages to /rosout_agg" << std::endl;
112 
113  rosout_sub_ = node_.subscribe("/rosout", 0, &Rosout::rosoutCallback, this);
114  std::cout << "subscribed to /rosout" << std::endl;
115  }
116 
117  void rosoutCallback(const rosgraph_msgs::Log::ConstPtr& msg)
118  {
119  agg_pub_.publish(msg);
120 
121  std::stringstream ss;
122  ss << msg->header.stamp << " ";
123  switch (msg->level)
124  {
125  case rosgraph_msgs::Log::FATAL:
126  ss << "FATAL ";
127  break;
128  case rosgraph_msgs::Log::ERROR:
129  ss << "ERROR ";
130  break;
131  case rosgraph_msgs::Log::WARN:
132  ss << "WARN ";
133  break;
134  case rosgraph_msgs::Log::DEBUG:
135  ss << "DEBUG ";
136  break;
137  case rosgraph_msgs::Log::INFO:
138  ss << "INFO ";
139  break;
140  default:
141  ss << msg->level << " ";
142  }
143 
144  ss << "[" << msg->file << ":" << msg->line << "(" << msg->function << ") ";
145 
146  ss << "[topics: ";
147  std::vector<std::string>::const_iterator it = msg->topics.begin();
148  std::vector<std::string>::const_iterator end = msg->topics.end();
149  for ( ; it != end; ++it )
150  {
151  const std::string& topic = *it;
152 
153  if ( it != msg->topics.begin() )
154  {
155  ss << ", ";
156  }
157 
158  ss << topic;
159  }
160  ss << "] ";
161 
162  ss << msg->msg;
163  ss << "\n";
164  int written = fprintf(handle_, "%s", ss.str().c_str());
165  if (written < 0)
166  {
167  std::cerr << "Error writting to rosout log file '" << log_file_name_.c_str() << "': " << strerror(ferror(handle_)) << std::endl;
168  }
169  else if (written > 0)
170  {
171  current_file_size_ += written;
172  if (fflush(handle_))
173  {
174  std::cerr << "Error flushing rosout log file '" << log_file_name_.c_str() << "': " << strerror(errno);
175  }
176 
177  // check for rolling
178  if (current_file_size_ > max_file_size_)
179  {
180  if (fclose(handle_))
181  {
182  std::cerr << "Error closing rosout log file '" << log_file_name_.c_str() << "': " << strerror(errno) << std::endl;
183  }
184  current_backup_index_++;
185  if (current_backup_index_ <= max_backup_index_)
186  {
187  std::stringstream backup_file_name;
188  backup_file_name << log_file_name_ << "." << current_backup_index_;
189  int rc = rename(log_file_name_.c_str(), backup_file_name.str().c_str());
190  if (rc != 0)
191  {
192  rc = remove(backup_file_name.str().c_str());
193  if (rc == 0)
194  {
195  rc = rename(log_file_name_.c_str(), backup_file_name.str().c_str());
196  if (rc)
197  {
198  std::cerr << "Error rotating rosout log file '" << log_file_name_.c_str() << "' to '" << backup_file_name.str().c_str() << "': " << strerror(errno);
199  }
200  }
201  }
202  if (rc)
203  {
204  std::cerr << "Error rotating rosout log file '" << log_file_name_.c_str() << "'' to '" << backup_file_name.str().c_str() << "'" << std::endl;
205  }
206  else
207  {
208  std::cout << "rosout log file " << log_file_name_.c_str() << " reached max size, back up data to " << backup_file_name.str().c_str() << std::endl;
209  }
210  if (current_backup_index_ == max_backup_index_)
211  {
212  current_backup_index_ = 0;
213  }
214  }
215  handle_ = fopen(log_file_name_.c_str(), "w");
216  if (handle_ == 0)
217  {
218  std::cerr << "Error opening rosout log file '" << log_file_name_.c_str() << "': " << strerror(errno);
219  }
220  current_file_size_ = 0;
221  }
222  }
223  }
224 };
225 
226 int main(int argc, char **argv)
227 {
228  ros::init(argc, argv, "rosout", ros::init_options::NoRosout);
229  ros::NodeHandle n;
230  Rosout r;
231 
232  ros::spin();
233 
234  return 0;
235 }
236 
FILE * handle_
Definition: rosout.cpp:61
void publish(const boost::shared_ptr< M > &message) const
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:62
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void init()
Definition: rosout.cpp:75
std::string log_file_name_
Definition: rosout.cpp:60
size_t current_backup_index_
Definition: rosout.cpp:65
size_t current_file_size_
Definition: rosout.cpp:63
ros::NodeHandle node_
Definition: rosout.cpp:66
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:64
ROSCPP_DECL const std::string & getLogDirectory()
Rosout()
Definition: rosout.cpp:70
static Time now()
ros::Publisher agg_pub_
Definition: rosout.cpp:68
void rosoutCallback(const rosgraph_msgs::Log::ConstPtr &msg)
Definition: rosout.cpp:117
int main(int argc, char **argv)
Definition: rosout.cpp:226
ros::Subscriber rosout_sub_
Definition: rosout.cpp:67


rosout
Author(s): Josh Faust, Dirk Thomas
autogenerated on Mon Nov 2 2020 03:52:35