$search
00001 00002 /*************************************************************************** 00003 * nodemon_tui.h - Node monitoring text-based user interface 00004 * 00005 * Created: Sat Apr 09 11:04:24 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 <ros/ros.h> 00026 #include <nodemon_msgs/NodeState.h> 00027 00028 #include <ncurses.h> 00029 #include <list> 00030 #include <map> 00031 #include <string> 00032 00033 #define MIN_SCREEN_WIDTH 80 00034 #define MIN_SCREEN_HEIGHT 25 00035 00036 #define MIN_NODE_WIDTH 24 00037 #define NODES_PER_LINE 3 00038 #define NODE_START_X 2 00039 #define NODE_START_Y 2 00040 00041 #define NUM_MSG_LINES 16 00042 #define MAX_NUM_MSGS 100 00043 00044 #define UPDATE_INTERVAL_SEC 0.2 00045 #define TIMEOUT_SEC 5.0 00046 00047 #define CPAIR_RED 1 00048 #define CPAIR_ORANGE 2 00049 #define CPAIR_BLACK 3 00050 #define CPAIR_BLACK_BG 4 00051 #define CPAIR_MAGENTA 5 00052 00053 #define DOT_ROS_DIR ".ros" 00054 #define NODEMON_CACHE_FILE "nodemon_cache" 00055 00056 #ifndef __NODEMON_TUI_NODEMON_TUI_H_ 00057 #define __NODEMON_TUI_NODEMON_TUI_H_ 00058 00059 class NodeMonTUI 00060 { 00061 public: 00062 NodeMonTUI(ros::NodeHandle &nh); 00063 ~NodeMonTUI(); 00064 00065 void node_state_cb(const nodemon_msgs::NodeState::ConstPtr &msg); 00066 00067 void update_timer_cb(const ros::WallTimerEvent& event); 00068 00069 private: 00070 void reset_screen(bool force = false); 00071 void update_screen(); 00072 void print_messages(); 00073 void print_debug(const char *str); 00074 void read_key(); 00075 bool reorder(); 00076 void add_node(std::string nodename, bool add_to_cache = true); 00077 void clear(); 00078 void clear_messages(); 00079 void show_info(); 00080 00081 private: 00082 ros::NodeHandle &__nh; 00083 00084 ros::Subscriber __state_sub; 00085 ros::WallTimer __update_timer; 00086 00087 std::string __cache_path; 00088 std::string __dot_ros_dir; 00089 00090 int __node_width; 00091 int __wnd_width; 00092 int __wnd_height; 00093 00094 typedef struct { 00095 ros::WallTime last_update; 00096 int x; 00097 int y; 00098 nodemon_msgs::NodeState::ConstPtr last_msg; 00099 } node_info_t; 00100 00101 00102 typedef std::map<std::string, node_info_t> InfoMap; 00103 InfoMap __ninfo; 00104 00105 typedef struct { 00106 uint8_t state; 00107 std::string text; 00108 nodemon_msgs::NodeState::ConstPtr msg; 00109 } message_t; 00110 std::list<message_t> __messages; 00111 std::list<message_t>::size_type __msg_start; 00112 00113 00114 WINDOW *__win_msgs; 00115 }; 00116 00117 00118 #endif