00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <cstring>
00031 #include <cstdlib>
00032
00033 #include "ros/ros.h"
00034 #include "ros/file_log.h"
00035 #include "rosgraph_msgs/Log.h"
00036
00037 #include "log4cxx/logger.h"
00038 #include "log4cxx/rollingfileappender.h"
00039 #include "log4cxx/patternlayout.h"
00040 #include "log4cxx/helpers/pool.h"
00041
00054 class Rosout
00055 {
00056 public:
00057 log4cxx::LoggerPtr logger_;
00058 ros::NodeHandle node_;
00059 ros::Subscriber rosout_sub_;
00060 ros::Publisher agg_pub_;
00061
00062 Rosout()
00063 {
00064 init();
00065 }
00066
00067 void init()
00068 {
00069
00070 std::string log_file_name = ros::file_log::getLogDirectory() + "/rosout.log";
00071
00072 logger_ = log4cxx::Logger::getRootLogger();
00073 log4cxx::LayoutPtr layout = new log4cxx::PatternLayout("");
00074 log4cxx::RollingFileAppenderPtr appender = new log4cxx::RollingFileAppender(layout, log_file_name, true);
00075 logger_->addAppender( appender );
00076 appender->setMaximumFileSize(100*1024*1024);
00077 appender->setMaxBackupIndex(10);
00078 log4cxx::helpers::Pool pool;
00079 appender->activateOptions(pool);
00080
00081 std::cout << "logging to " << log_file_name << std::endl;
00082
00083 LOG4CXX_INFO(logger_, "\n\n" << ros::Time::now() << " Node Startup\n");
00084
00085 agg_pub_ = node_.advertise<rosgraph_msgs::Log>("/rosout_agg", 0);
00086 std::cout << "re-publishing aggregated messages to /rosout_agg" << std::endl;
00087
00088 rosout_sub_ = node_.subscribe("/rosout", 0, &Rosout::rosoutCallback, this);
00089 std::cout << "subscribed to /rosout" << std::endl;
00090 }
00091
00092 void rosoutCallback(const rosgraph_msgs::Log::ConstPtr& msg)
00093 {
00094 agg_pub_.publish(msg);
00095
00096 std::stringstream ss;
00097 ss << msg->header.stamp << " ";
00098 switch (msg->level)
00099 {
00100 case rosgraph_msgs::Log::FATAL:
00101 ss << "FATAL ";
00102 break;
00103 case rosgraph_msgs::Log::ERROR:
00104 ss << "ERROR ";
00105 break;
00106 case rosgraph_msgs::Log::WARN:
00107 ss << "WARN ";
00108 break;
00109 case rosgraph_msgs::Log::DEBUG:
00110 ss << "DEBUG ";
00111 break;
00112 case rosgraph_msgs::Log::INFO:
00113 ss << "INFO ";
00114 break;
00115 default:
00116 ss << msg->level << " ";
00117 }
00118
00119 ss << "[" << msg->file << ":" << msg->line << "(" << msg->function << ") ";
00120
00121 ss << "[topics: ";
00122 std::vector<std::string>::const_iterator it = msg->topics.begin();
00123 std::vector<std::string>::const_iterator end = msg->topics.end();
00124 for ( ; it != end; ++it )
00125 {
00126 const std::string& topic = *it;
00127
00128 if ( it != msg->topics.begin() )
00129 {
00130 ss << ", ";
00131 }
00132
00133 ss << topic;
00134 }
00135 ss << "] ";
00136
00137 ss << msg->msg;
00138 LOG4CXX_INFO(logger_, ss.str());
00139 }
00140 };
00141
00142 int main(int argc, char **argv)
00143 {
00144 ros::init(argc, argv, "rosout", ros::init_options::NoRosout);
00145 ros::NodeHandle n;
00146 Rosout r;
00147
00148 ros::spin();
00149
00150 return 0;
00151 }
00152