$search
00001 00002 /*************************************************************************** 00003 * nodemon_tui.cpp - Node monitoring text-based user interface 00004 * 00005 * Created: Fri Apr 08 12:57:45 2011 00006 * Copyright 2011 Tim Niemueller [www.niemueller.de] 00007 * 2011 SRI International 00008 * 2011 Carnegie Mellon University 00009 * 2011 Intel Labs Pittsburgh 00010 * 2011 Columbia University in the City of New York 00011 * 00012 ****************************************************************************/ 00013 00014 /* This program is free software; you can redistribute it and/or modify 00015 * it under the terms of the 3-clase BSD License. 00016 * 00017 * This program is distributed in the hope that it will be useful, 00018 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00019 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00020 * GNU Library General Public License for more details. 00021 * 00022 * Read the full text in the LICENSE file in the root directory. 00023 */ 00024 00025 #include "nodemon_tui.h" 00026 00027 #include <cstdio> 00028 #include <sys/stat.h> 00029 #include <sys/types.h> 00030 00041 NodeMonTUI::NodeMonTUI(ros::NodeHandle &nh) 00042 : __nh(nh) 00043 { 00044 __wnd_width = __wnd_height = 0; 00045 __node_width = MIN_NODE_WIDTH; 00046 __win_msgs = NULL; 00047 __msg_start = 0; 00048 00049 __state_sub = __nh.subscribe("/nodemon/state", 10, 00050 &NodeMonTUI::node_state_cb, this); 00051 __update_timer = __nh.createWallTimer(ros::WallDuration(UPDATE_INTERVAL_SEC), 00052 &NodeMonTUI::update_timer_cb, this); 00053 00054 initscr(); // Start curses mode 00055 curs_set(0); // invisible cursor 00056 noecho(); // disable printing of typed characters 00057 cbreak(); // disable line buffering 00058 timeout(0); // make getch return immediately 00059 keypad(stdscr, TRUE); 00060 00061 if(has_colors() == FALSE) { 00062 endwin(); 00063 printf("You terminal does not support color\n"); 00064 exit(1); 00065 } 00066 start_color(); 00067 use_default_colors(); // initialize default colors 00068 // defining colors doesn't work in bash/gnome-terminal 00069 //init_color(COLOR_LIGHT_GREY, 750, 750, 750); 00070 //init_color(COLOR_DARK_GREY, 250, 250, 250); 00071 //init_color(COLOR_ORANGE, 1000, 500, 0); 00072 init_pair(CPAIR_RED, COLOR_RED, -1); 00073 init_pair(CPAIR_ORANGE, COLOR_YELLOW, -1); 00074 init_pair(CPAIR_MAGENTA, COLOR_MAGENTA, -1); 00075 init_pair(CPAIR_BLACK, COLOR_BLACK, -1); 00076 init_pair(CPAIR_BLACK_BG, COLOR_WHITE, COLOR_BLACK); 00077 00078 reset_screen(); 00079 00080 __cache_path = ""; 00081 // try to read cache 00082 const char *home = getenv("HOME"); 00083 if (home != NULL) { 00084 __dot_ros_dir = std::string(home) + "/" DOT_ROS_DIR; 00085 __cache_path = __dot_ros_dir + "/" NODEMON_CACHE_FILE; 00086 00087 // just in case... 00088 mkdir(__dot_ros_dir.c_str(), 0700); 00089 00090 FILE *f = fopen(__cache_path.c_str(), "r"); 00091 if (f != NULL) { 00092 char tmp[1024]; 00093 while (fgets(tmp, 1024, f) != NULL) { 00094 tmp[strlen(tmp) - 1] = '\0'; // remove newline 00095 add_node(tmp, /* add to cache */ false); 00096 } 00097 fclose(f); 00098 } 00099 } 00100 } 00101 00102 00104 NodeMonTUI::~NodeMonTUI() 00105 { 00106 delwin(__win_msgs); 00107 endwin(); // End curses mode 00108 } 00109 00110 00116 void 00117 NodeMonTUI::print_debug(const char *str) 00118 { 00119 mvaddstr(__wnd_height-1, 3, str); 00120 } 00121 00122 00130 void 00131 NodeMonTUI::reset_screen(bool force) 00132 { 00133 int h, w; 00134 getmaxyx(stdscr, h, w); 00135 00136 if (force) { 00137 __wnd_width = __wnd_height = -1; 00138 } 00139 00140 if (w != __wnd_width || h != __wnd_height) { 00141 __wnd_width = w; 00142 __wnd_height = h; 00143 00144 erase(); 00145 00146 attron(A_BOLD); 00147 border(0, 0, 0, 0, 0, 0, 0, 0); 00148 mvaddch(h - (NUM_MSG_LINES + 2), 0, ACS_LTEE); 00149 move(h - (NUM_MSG_LINES + 2), 1); 00150 hline(0, w-2); 00151 mvaddch(h - (NUM_MSG_LINES + 2), w-1, ACS_RTEE); 00152 mvaddstr(0, 2, " Nodes "); 00153 mvaddstr(h - (NUM_MSG_LINES + 2), 2, " Messages "); 00154 attroff(A_BOLD); 00155 00156 if (__win_msgs) delwin(__win_msgs); 00157 __win_msgs = newwin(NUM_MSG_LINES, w - 2, h - (NUM_MSG_LINES+1), 1); 00158 scrollok(__win_msgs, TRUE); 00159 } 00160 } 00161 00165 void 00166 NodeMonTUI::update_screen() 00167 { 00168 for (InfoMap::iterator i = __ninfo.begin(); i != __ninfo.end(); ++i) { 00169 chtype cl = 0; 00170 const wchar_t *cc = L" "; 00171 int attrs = 0; 00172 00173 ros::WallTime now = ros::WallTime::now(); 00174 00175 bool timed_out = 00176 ((now - i->second.last_update).toSec() > TIMEOUT_SEC); 00177 00178 bool state_hang = i->second.last_msg && 00179 ((ros::Time::now() - i->second.last_msg->time).toSec() > TIMEOUT_SEC); 00180 00181 if (! i->second.last_msg) { 00182 // Node which has been added from cache, we're waiting for a heartbeat 00183 cl = CPAIR_BLACK; 00184 attrs |= A_BOLD; 00185 cc = L"\u2300"; 00186 00187 } else if (timed_out) { 00188 cl = CPAIR_BLACK; 00189 attrs |= A_BOLD; 00190 // 231b hourglass, unsupported in common fonts 00191 cc = L"\u231a"; 00192 00193 } else { 00194 switch (i->second.last_msg->state) { 00195 case nodemon_msgs::NodeState::STARTING: 00196 attrs |= A_BOLD; 00197 break; 00198 00199 case nodemon_msgs::NodeState::RECOVERING: 00200 cl = CPAIR_ORANGE; 00201 cc = L"\u26a0"; 00202 break; 00203 00204 case nodemon_msgs::NodeState::ERROR: 00205 cl = CPAIR_RED; 00206 cc = L"\u26a0"; 00207 break; 00208 00209 case nodemon_msgs::NodeState::WARNING: 00210 cl = CPAIR_MAGENTA; 00211 cc = L"\u26a0"; 00212 break; 00213 00214 case nodemon_msgs::NodeState::FATAL: 00215 cl = CPAIR_RED; 00216 attrs |= A_BOLD; 00217 cc = L"\u2620"; 00218 break; 00219 00220 case nodemon_msgs::NodeState::STOPPING: 00221 cl = CPAIR_BLACK; 00222 attrs |= A_BOLD; 00223 break; 00224 default: 00225 break; 00226 } 00227 00228 if (state_hang) { 00229 // 231b hourglass, unsupported in common fonts 00230 cc = L"\u231a"; 00231 } 00232 } 00233 if (i->second.last_msg && 00234 ((now - i->second.last_update).toSec() <= UPDATE_INTERVAL_SEC)) 00235 { 00236 if ((i->second.last_msg->state == nodemon_msgs::NodeState::FATAL) || 00237 state_hang) 00238 { 00239 cc = L"\u2661"; 00240 } else { 00241 cc = L"\u2665"; 00242 } 00243 } 00244 00245 attrs |= COLOR_PAIR(cl); 00246 attron(attrs); 00247 mvaddwstr(i->second.y, i->second.x, cc); 00248 mvaddstr(i->second.y, i->second.x + 2, i->first.c_str()); 00249 attroff(attrs); 00250 } 00251 refresh(); // Print it on to the real screen 00252 } 00253 00254 00258 void 00259 NodeMonTUI::print_messages() 00260 { 00261 werase(__win_msgs); 00262 00263 00264 int y = 0; 00265 std::list<message_t>::size_type num = 0; 00266 std::list<message_t>::iterator m = __messages.begin(); 00267 std::list<message_t>::size_type i; 00268 for (i = 0; m != __messages.end() && i < __msg_start; ++m, ++i) ; 00269 00270 for (; m != __messages.end() && num < NUM_MSG_LINES; ++m, ++num) { 00271 chtype cl = 0; 00272 int attrs = 0; 00273 switch (m->state) { 00274 case nodemon_msgs::NodeState::ERROR: 00275 cl = CPAIR_RED; 00276 break; 00277 case nodemon_msgs::NodeState::RECOVERING: 00278 cl = CPAIR_ORANGE; 00279 break; 00280 case nodemon_msgs::NodeState::WARNING: 00281 cl = CPAIR_MAGENTA; 00282 break; 00283 default: 00284 cl = CPAIR_RED; 00285 attrs |= A_BOLD; 00286 break; 00287 } 00288 attrs |= COLOR_PAIR(cl); 00289 wattron(__win_msgs, attrs); 00290 mvwaddstr(__win_msgs, y++, 0, m->text.c_str()); 00291 wattroff(__win_msgs, attrs); 00292 } 00293 wrefresh(__win_msgs); 00294 } 00295 00296 00301 bool 00302 NodeMonTUI::reorder() 00303 { 00304 bool changed = false; 00305 00306 int x = NODE_START_X; 00307 int y = NODE_START_Y; 00308 00309 for (InfoMap::iterator i = __ninfo.begin(); i != __ninfo.end(); ++i) { 00310 if ((i->second.x != x) || (i->second.y != y)) changed = true; 00311 00312 i->second.x = x; 00313 i->second.y = y; 00314 00315 if ((x + (2 * __node_width)) > __wnd_width) { 00316 x = NODE_START_X; 00317 y += 1; 00318 } else { 00319 x += __node_width; 00320 } 00321 } 00322 00323 return changed; 00324 } 00325 00326 00328 void 00329 NodeMonTUI::read_key() 00330 { 00331 int key = getch(); 00332 if (key == ERR) return; 00333 00334 // key code 27 is the Esc key 00335 if (key == KEY_UP) { 00336 if (__msg_start > 0) { 00337 --__msg_start; 00338 print_messages(); 00339 } 00340 } else if (key == KEY_DOWN) { 00341 if (__msg_start < __messages.size() - NUM_MSG_LINES) { 00342 ++__msg_start; 00343 print_messages(); 00344 } 00345 } else if (((key == 27) && (getch() == ERR)) || (key == 'q')) { 00346 ros::shutdown(); 00347 } else if (key == 'c') { 00348 clear(); 00349 } else if (key == 'C') { 00350 clear_messages(); 00351 } else if (key == 'i') { 00352 show_info(); 00353 } 00354 } 00355 00360 void 00361 NodeMonTUI::add_node(std::string nodename, bool add_to_cache) 00362 { 00363 node_info_t info; 00364 info.last_update = ros::WallTime::now(); 00365 info.x = 0; 00366 info.y = 0; 00367 __ninfo[nodename] = info; 00368 00369 if (((int)nodename.length() + 6) > __node_width) { 00370 __node_width = nodename.length() + 6; 00371 reset_screen(/* force */ true); 00372 } 00373 00374 if (reorder()) { 00375 reset_screen(/* force */ true); 00376 } 00377 00378 if (add_to_cache && __cache_path != "") { 00379 FILE *f = fopen(__cache_path.c_str(), "a"); 00380 if (f != NULL) { 00381 fprintf(f, "%s\n", nodename.c_str()); 00382 fclose(f); 00383 } 00384 } 00385 } 00386 00387 00389 void 00390 NodeMonTUI::clear() 00391 { 00392 __ninfo.clear(); 00393 __messages.clear(); 00394 00395 if (__cache_path != "") { 00396 FILE *f = fopen(__cache_path.c_str(), "w"); 00397 if (f != NULL) { 00398 fclose(f); 00399 } 00400 } 00401 00402 __node_width = MIN_NODE_WIDTH; 00403 erase(); 00404 reset_screen(/* force */ true); 00405 update_screen(); 00406 print_messages(); 00407 } 00408 00409 00411 void 00412 NodeMonTUI::clear_messages() 00413 { 00414 __messages.clear(); 00415 erase(); 00416 reset_screen(/* force */ true); 00417 update_screen(); 00418 print_messages(); 00419 } 00420 00421 00423 void 00424 NodeMonTUI::show_info() 00425 { 00426 if (__messages.empty()) { 00427 print_debug("No message received"); 00428 } else { 00429 std::list<message_t>::iterator m; 00430 for (m = __messages.begin(); m != __messages.end(); ++m) { 00431 if ((m->state == nodemon_msgs::NodeState::ERROR) || 00432 (m->state == nodemon_msgs::NodeState::FATAL) ) 00433 { 00434 std::string cmd = "gnome-open http://localhost:10117/errorkb" + 00435 m->msg->nodename + "/" + m->msg->machine_message; 00436 system(cmd.c_str()); 00437 break; 00438 } 00439 } 00440 print_debug("No recent error message"); 00441 } 00442 } 00443 00447 void 00448 NodeMonTUI::update_timer_cb(const ros::WallTimerEvent& event) 00449 { 00450 reset_screen(); 00451 update_screen(); 00452 print_messages(); 00453 read_key(); 00454 } 00455 00459 void 00460 NodeMonTUI::node_state_cb(const nodemon_msgs::NodeState::ConstPtr &msg) 00461 { 00462 if (__ninfo.find(msg->nodename) == __ninfo.end()) { 00463 add_node(msg->nodename); 00464 } 00465 00466 ros::WallTime msg_walltime(msg->time.sec, msg->time.nsec); 00467 00468 if (((msg->state == nodemon_msgs::NodeState::ERROR) || 00469 (msg->state == nodemon_msgs::NodeState::FATAL) || 00470 (msg->state == nodemon_msgs::NodeState::WARNING) || 00471 (msg->state == nodemon_msgs::NodeState::RECOVERING)) && 00472 (msg->machine_message != "") && 00473 (!__ninfo[msg->nodename].last_msg || 00474 ((__ninfo[msg->nodename].last_msg->time != msg->time) && 00475 (__ninfo[msg->nodename].last_msg->machine_message != msg->machine_message)))) 00476 { 00477 tm time_tm; 00478 time_t timet; 00479 timet = msg_walltime.sec; 00480 localtime_r(&timet, &time_tm); 00481 // stat date nodename machine message 00482 size_t ml = 2 + 21 + msg->nodename.size() + msg->machine_message.size() 00483 // "[...] " human message NULL 00484 + 3 + msg->human_message.size() + 1; 00485 char mstr[ml]; 00486 00487 const char *state = "F"; 00488 if (msg->state == nodemon_msgs::NodeState::ERROR) { 00489 state = "E"; 00490 } else if (msg->state == nodemon_msgs::NodeState::RECOVERING) { 00491 state = "R"; 00492 } else if (msg->state == nodemon_msgs::NodeState::WARNING) { 00493 state = "W"; 00494 } 00495 00496 sprintf(mstr, "%s %02d:%02d:%02d.%09u %s: [%s] %s", state, time_tm.tm_hour, 00497 time_tm.tm_min, time_tm.tm_sec, msg_walltime.nsec, 00498 msg->nodename.c_str(), msg->machine_message.c_str(), 00499 msg->human_message.c_str()); 00500 00501 message_t m; 00502 m.state = msg->state; 00503 m.text = mstr; 00504 m.msg = msg; 00505 00506 __messages.push_front(m); 00507 __msg_start = 0; 00508 if (__messages.size() > MAX_NUM_MSGS) { 00509 __messages.pop_back(); 00510 } 00511 } 00512 00513 __ninfo[msg->nodename].last_update = ros::WallTime::now(); 00514 __ninfo[msg->nodename].last_msg = msg; 00515 }