Go to the documentation of this file.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
00036 #ifdef WIN32
00037 #ifdef ERROR
00038
00039
00040 #undef ERROR
00041 #endif
00042 #endif
00043 #include "rosgraph_msgs/Log.h"
00044
00045 #include "log4cxx/logger.h"
00046 #include "log4cxx/rollingfileappender.h"
00047 #include "log4cxx/patternlayout.h"
00048 #include "log4cxx/helpers/pool.h"
00049 #ifdef _MSC_VER
00050 #include "log4cxx/helpers/transcoder.h"
00051 #endif
00052
00065 class Rosout
00066 {
00067 public:
00068 log4cxx::LoggerPtr logger_;
00069 ros::NodeHandle node_;
00070 ros::Subscriber rosout_sub_;
00071 ros::Publisher agg_pub_;
00072
00073 Rosout()
00074 {
00075 init();
00076 }
00077
00078 void init()
00079 {
00080
00081 #ifdef _MSC_VER
00082 std::string log_file_name_str = ros::file_log::getLogDirectory() + "/rosout.log";
00083 LOG4CXX_DECODE_CHAR(log_file_name, log_file_name_str);
00084 std::string empty_str = "";
00085 LOG4CXX_DECODE_CHAR(log_empty, empty_str);
00086 #else
00087 std::string log_file_name = ros::file_log::getLogDirectory() + "/rosout.log";
00088 std::string log_empty = "";
00089 #endif
00090
00091 logger_ = log4cxx::Logger::getRootLogger();
00092 log4cxx::LayoutPtr layout = new log4cxx::PatternLayout(log_empty);
00093 log4cxx::RollingFileAppenderPtr appender = new log4cxx::RollingFileAppender(layout, log_file_name, true);
00094 logger_->addAppender( appender );
00095 appender->setMaximumFileSize(100*1024*1024);
00096 appender->setMaxBackupIndex(10);
00097 log4cxx::helpers::Pool pool;
00098 appender->activateOptions(pool);
00099
00100 std::cout << "logging to " << log_file_name.c_str() << std::endl;
00101
00102 LOG4CXX_INFO(logger_, "\n\n" << ros::Time::now() << " Node Startup\n");
00103
00104 agg_pub_ = node_.advertise<rosgraph_msgs::Log>("/rosout_agg", 0);
00105 std::cout << "re-publishing aggregated messages to /rosout_agg" << std::endl;
00106
00107 rosout_sub_ = node_.subscribe("/rosout", 0, &Rosout::rosoutCallback, this);
00108 std::cout << "subscribed to /rosout" << std::endl;
00109 }
00110
00111 void rosoutCallback(const rosgraph_msgs::Log::ConstPtr& msg)
00112 {
00113 agg_pub_.publish(msg);
00114
00115 std::stringstream ss;
00116 ss << msg->header.stamp << " ";
00117 switch (msg->level)
00118 {
00119 case rosgraph_msgs::Log::FATAL:
00120 ss << "FATAL ";
00121 break;
00122 case rosgraph_msgs::Log::ERROR:
00123 ss << "ERROR ";
00124 break;
00125 case rosgraph_msgs::Log::WARN:
00126 ss << "WARN ";
00127 break;
00128 case rosgraph_msgs::Log::DEBUG:
00129 ss << "DEBUG ";
00130 break;
00131 case rosgraph_msgs::Log::INFO:
00132 ss << "INFO ";
00133 break;
00134 default:
00135 ss << msg->level << " ";
00136 }
00137
00138 ss << "[" << msg->file << ":" << msg->line << "(" << msg->function << ") ";
00139
00140 ss << "[topics: ";
00141 std::vector<std::string>::const_iterator it = msg->topics.begin();
00142 std::vector<std::string>::const_iterator end = msg->topics.end();
00143 for ( ; it != end; ++it )
00144 {
00145 const std::string& topic = *it;
00146
00147 if ( it != msg->topics.begin() )
00148 {
00149 ss << ", ";
00150 }
00151
00152 ss << topic;
00153 }
00154 ss << "] ";
00155
00156 ss << msg->msg;
00157 LOG4CXX_INFO(logger_, ss.str());
00158 }
00159 };
00160
00161 int main(int argc, char **argv)
00162 {
00163 ros::init(argc, argv, "rosout", ros::init_options::NoRosout);
00164 ros::NodeHandle n;
00165 Rosout r;
00166
00167 ros::spin();
00168
00169 return 0;
00170 }
00171