$search
#include <nodemon_tui.h>
Classes | |
| struct | message_t |
| struct | node_info_t |
Public Member Functions | |
| void | node_state_cb (const nodemon_msgs::NodeState::ConstPtr &msg) |
| NodeMonTUI (ros::NodeHandle &nh) | |
| void | update_timer_cb (const ros::WallTimerEvent &event) |
| ~NodeMonTUI () | |
Private Types | |
| typedef std::map< std::string, node_info_t > | InfoMap |
Private Member Functions | |
| void | add_node (std::string nodename, bool add_to_cache=true) |
| void | clear () |
| void | clear_messages () |
| void | print_debug (const char *str) |
| void | print_messages () |
| void | read_key () |
| bool | reorder () |
| void | reset_screen (bool force=false) |
| void | show_info () |
| void | update_screen () |
Private Attributes | |
| std::string | __cache_path |
| std::string | __dot_ros_dir |
| std::list< message_t > | __messages |
| std::list< message_t >::size_type | __msg_start |
| ros::NodeHandle & | __nh |
| InfoMap | __ninfo |
| int | __node_width |
| ros::Subscriber | __state_sub |
| ros::WallTimer | __update_timer |
| WINDOW * | __win_msgs |
| int | __wnd_height |
| int | __wnd_width |
Node monitoring TUI. This class implements a text-based user interface (TUI) using the ncurses library. It shows heartbeat and error information about processes.
Definition at line 59 of file nodemon_tui.h.
typedef std::map<std::string, node_info_t> NodeMonTUI::InfoMap [private] |
Definition at line 102 of file nodemon_tui.h.
| NodeMonTUI::NodeMonTUI | ( | ros::NodeHandle & | nh | ) |
| NodeMonTUI::~NodeMonTUI | ( | ) |
Destructor.
Definition at line 104 of file nodemon_tui.cpp.
| void NodeMonTUI::add_node | ( | std::string | nodename, | |
| bool | add_to_cache = true | |||
| ) | [private] |
Add a node.
| nodename | name of the node to add | |
| add_to_cache | true to add the node to the cache file, false not to |
Definition at line 361 of file nodemon_tui.cpp.
| void NodeMonTUI::clear | ( | ) | [private] |
Clear the list of nodes and messages.
Definition at line 390 of file nodemon_tui.cpp.
| void NodeMonTUI::clear_messages | ( | ) | [private] |
Clear message list.
Definition at line 412 of file nodemon_tui.cpp.
| void NodeMonTUI::node_state_cb | ( | const nodemon_msgs::NodeState::ConstPtr & | msg | ) |
Callback when receiving a node state message.
| msg | received message. |
Definition at line 460 of file nodemon_tui.cpp.
| void NodeMonTUI::print_debug | ( | const char * | str | ) | [private] |
Print debug message. The message will appear in the lower left corner of the main window. Consecutive calls to this method will overwrite the previous message.
| str | string to print |
Definition at line 117 of file nodemon_tui.cpp.
| void NodeMonTUI::print_messages | ( | ) | [private] |
Print messages. This prints the message strings.
Definition at line 259 of file nodemon_tui.cpp.
| void NodeMonTUI::read_key | ( | ) | [private] |
Read a key and call the appropriate callbacks.
Definition at line 329 of file nodemon_tui.cpp.
| bool NodeMonTUI::reorder | ( | ) | [private] |
Reorder nodes. This recalculates the positions for all nodes.
Definition at line 302 of file nodemon_tui.cpp.
| void NodeMonTUI::reset_screen | ( | bool | force = false |
) | [private] |
Reset the screen. If the screen size has changed, or the force flag is set to true, the screen will be erased and the chrome (borders, titles) will be drawn.
| force | true to force a re-draw, false to only redraw if screen dimensions have changed. |
Definition at line 131 of file nodemon_tui.cpp.
| void NodeMonTUI::show_info | ( | ) | [private] |
Show info of most recent error.
Definition at line 424 of file nodemon_tui.cpp.
| void NodeMonTUI::update_screen | ( | ) | [private] |
Update screen content. This will print the current information about nodes.
Definition at line 166 of file nodemon_tui.cpp.
| void NodeMonTUI::update_timer_cb | ( | const ros::WallTimerEvent & | event | ) |
Callback for update timer event.
| event | event information |
Definition at line 448 of file nodemon_tui.cpp.
std::string NodeMonTUI::__cache_path [private] |
Definition at line 87 of file nodemon_tui.h.
std::string NodeMonTUI::__dot_ros_dir [private] |
Definition at line 88 of file nodemon_tui.h.
std::list<message_t> NodeMonTUI::__messages [private] |
Definition at line 110 of file nodemon_tui.h.
std::list<message_t>::size_type NodeMonTUI::__msg_start [private] |
Definition at line 111 of file nodemon_tui.h.
ros::NodeHandle& NodeMonTUI::__nh [private] |
Definition at line 82 of file nodemon_tui.h.
InfoMap NodeMonTUI::__ninfo [private] |
Definition at line 103 of file nodemon_tui.h.
int NodeMonTUI::__node_width [private] |
Definition at line 90 of file nodemon_tui.h.
ros::Subscriber NodeMonTUI::__state_sub [private] |
Definition at line 84 of file nodemon_tui.h.
ros::WallTimer NodeMonTUI::__update_timer [private] |
Definition at line 85 of file nodemon_tui.h.
WINDOW* NodeMonTUI::__win_msgs [private] |
Definition at line 114 of file nodemon_tui.h.
int NodeMonTUI::__wnd_height [private] |
Definition at line 92 of file nodemon_tui.h.
int NodeMonTUI::__wnd_width [private] |
Definition at line 91 of file nodemon_tui.h.