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
00031 #include <QFileDialog>
00032 #include <QDir>
00033 #include <QDirIterator>
00034
00035 #include <fstream>
00036 #include <ros/time.h>
00037 #include <rosbag/bag.h>
00038 #include <swri_console/rosout_log_loader.h>
00039 #include <time.h>
00040 #include <string>
00041
00042 namespace swri_console
00043 {
00044 const int MIN_MSG_SIZE=10;
00045
00046 void RosoutLogLoader::loadRosLogDirectory(const QString& logdirectory_name)
00047 {
00048 QDirIterator it(logdirectory_name, QStringList() << "*.log", QDir::Files);
00049 while (it.hasNext())
00050 {
00051 QString filename = it.next();
00052 printf("Loading log file %s ...\n", filename.toStdString().c_str());
00053 loadRosLog(filename);
00054 }
00055 }
00056
00057 void RosoutLogLoader::loadRosLog(const QString& logfile_name)
00058 {
00059 std::string std_string_logfile = logfile_name.toStdString();
00060 std::ifstream logfile(std_string_logfile.c_str());
00061 int seq = 0;
00062 for( std::string line; getline( logfile, line ); )
00063 {
00064 rosgraph_msgs::Log log;
00065 unsigned found = std_string_logfile.find_last_of("/\\");
00066 log.name = std_string_logfile.substr(found+1);
00067 int result = parseLine(line, seq, &log);
00068 if (result == 0)
00069 {
00070 rosgraph_msgs::LogConstPtr log_ptr(new rosgraph_msgs::Log(log));
00071 emit logReceived(log_ptr);
00072 }
00073 seq++;
00074 }
00075 emit finishedReading();
00076 }
00077
00078 int RosoutLogLoader::parseLine(std::string line, int seq, rosgraph_msgs::Log* log)
00079 {
00080
00081 char log_msg_fmt0[] = "%d.%d %s [%[^:]:%u(%[^)]) [topics: %[^]]] %[^\n]s";
00082 int secs = 0;
00083 int nsecs = 0;
00084 char level[16];
00085 char file[1024];
00086 unsigned int line_num = 1;
00087 char function[128];
00088 char topics[1024];
00089 char msg[1024*32];
00090 ros::Time stamp;
00091
00093 int num_parsed = sscanf(line.c_str(),log_msg_fmt0,&secs, &nsecs, level, file, &line_num, function, topics, msg);
00094 if (num_parsed == 8 )
00095 {
00096
00097 log->file = file;
00098 log->function = function;
00099 log->header.seq = seq;
00100 stamp.sec = secs;
00101 stamp.nsec = nsecs;
00102 log->header.stamp = stamp;
00103 log->level = level_string_to_level_type(std::string(level));
00104 log->line = line_num;
00105 log->msg = msg;
00106 }
00107 else
00108 {
00109 char log_msg_fmt1[] = "%d.%d %s [%[^:]:%u(%[^)])) [topics: %[^]]] %[^\n]s";
00110 num_parsed = sscanf(line.c_str(), log_msg_fmt1, &secs, &nsecs, level, file, &line_num, function, topics, msg);
00111 if (num_parsed == 8 )
00112 {
00113
00114 log->file = file;
00115 log->function = function;
00116 log->header.seq = seq;
00117 stamp.sec = secs;
00118 stamp.nsec = nsecs;
00119 log->header.stamp = stamp;
00120 log->level = level_string_to_level_type(std::string(level));
00121 log->line = line_num;
00122 log->msg = msg;
00123 }
00124 else
00125 {
00126
00127 char log_msg_fmt2[] = "[%[^]]][%[^]]] %d-%d-%d %d:%d:%d,%d: %[^\n]s";
00128 int year;
00129 int month;
00130 int day;
00131 int hour;
00132 int minute;
00133 int msecs;
00134 char name[1024];
00135 time_t rawtime;
00136 struct tm * timeinfo;
00137
00138 num_parsed = sscanf(line.c_str(), log_msg_fmt2, name, level, &year, &month, &day, &hour, &minute, &secs, &msecs, msg);
00139 if (num_parsed == 10)
00140 {
00141
00142 file[0] = 0;
00143 function[0] = 0;
00144 line_num = 0;
00145 time ( &rawtime );
00146 timeinfo = localtime ( &rawtime );
00147 timeinfo->tm_year = year - 1900;
00148 timeinfo->tm_mon = month - 1;
00149 timeinfo->tm_mday = day;
00150 timeinfo->tm_hour = hour;
00151 timeinfo->tm_min = minute;
00152 timeinfo->tm_sec = secs;
00153 rawtime = mktime ( timeinfo );
00154 secs = rawtime;
00155 nsecs = msecs * 1000000;
00156 log->file = file;
00157 log->function = function;
00158 log->header.seq = seq;
00159 stamp.sec = secs;
00160 stamp.nsec = nsecs;
00161 log->header.stamp = stamp;
00162 log->level = level_string_to_level_type(std::string(level));
00163 log->line = line_num;
00164 log->msg = msg;
00165 }
00166 else
00167 {
00168
00169 char log_msg_fmt3[] = "\x1b[%dm[ %[^]]] [%d.%d]: %[^\n\x1b]s";
00170
00171 int ansi_color;
00172 msg[0] = 0;
00173 num_parsed = sscanf(line.c_str(), log_msg_fmt3, &ansi_color, level, &secs, &nsecs, msg);
00174 if (num_parsed == 5)
00175 {
00176
00177 file[0] = 0;
00178 function[0] = 0;
00179 line_num = 0;
00180 log->file = file;
00181 log->function = function;
00182 log->header.seq = seq;
00183 stamp.sec = secs;
00184 stamp.nsec = nsecs;
00185 log->header.stamp = stamp;
00186 log->level = level_string_to_level_type(std::string(level));
00187 log->line = line_num;
00188 log->msg = msg;
00189 }
00190 else
00191 {
00192
00193 char log_msg_fmt4[] = "\x1b[%dm[ %[^]]] [%d.%d, %d.%d]: %[^\n\x1b]";
00194 int secs2;
00195 int nsecs2;
00196 msg[0] = 0;
00197 num_parsed = sscanf(line.c_str(), log_msg_fmt4, &ansi_color, level, &secs, &nsecs, &secs2, &nsecs2, msg);
00198 if (num_parsed == 7)
00199 {
00200
00201 file[0] = 0;
00202 function[0] = 0;
00203 line_num = 0;
00204 log->file = file;
00205 log->function = function;
00206 log->header.seq = seq;
00207 stamp.sec = secs;
00208 stamp.nsec = nsecs;
00209 log->header.stamp = stamp;
00210 log->level = level_string_to_level_type(std::string(level));
00211 log->line = line_num;
00212 log->msg = msg;
00213 }
00214 else
00215 {
00216 if (line.length() < MIN_MSG_SIZE)
00217 {
00218 return -1;
00219 }
00220 log->file = std::string("");
00221 log->function = std::string("");
00222 log->header.seq = seq;
00223 stamp.sec = 0;
00224 stamp.nsec = 0;
00225 log->header.stamp = stamp;
00226 log->level = level_string_to_level_type(std::string("DEBUG"));
00227 log->line = 0;
00228 log->msg = line;
00229 log->name = log->name + "-unparsed";
00230 }
00231 }
00232 }
00233 }
00234 }
00235 return 0;
00236 }
00237
00238 rosgraph_msgs::Log::_level_type RosoutLogLoader::level_string_to_level_type(std::string level_str)
00239 {
00240 if (level_str.compare("FATAL") == 0)
00241 {
00242 return rosgraph_msgs::Log::FATAL;
00243 }
00244 if (level_str.compare("ERROR") == 0)
00245 {
00246 return rosgraph_msgs::Log::ERROR;
00247 }
00248 if (level_str.compare("WARN") == 0)
00249 {
00250 return rosgraph_msgs::Log::WARN;
00251 }
00252 if (level_str.compare("INFO") == 0)
00253 {
00254 return rosgraph_msgs::Log::INFO;
00255 }
00256 return rosgraph_msgs::Log::DEBUG;
00257 }
00258
00259
00260 void RosoutLogLoader::promptForLogFile()
00261 {
00262 QString filename = QFileDialog::getOpenFileName(NULL,
00263 tr("Open ROS Log File"),
00264 QDir::homePath(),
00265 tr("Log Files (*.log)"));
00266
00267 if (filename != NULL)
00268 {
00269 loadRosLog(filename);
00270 }
00271 }
00272
00273 void RosoutLogLoader::promptForLogDirectory()
00274 {
00275 QString dirname = QFileDialog::getExistingDirectory(NULL,
00276 tr("Open directory containing log files"),
00277 QDir::homePath());
00278
00279 if (dirname != NULL)
00280 {
00281 loadRosLogDirectory(dirname);
00282 }
00283 }
00284
00285
00286 }