ui.cpp
Go to the documentation of this file.
1 // console user interface
2 // Author: Max Schwarz <max.schwarz@uni-bonn.de>
3 
4 #include "ui.h"
5 #include "husl/husl.h"
6 
7 #include <cstdlib>
8 #include <ros/node_handle.h>
9 
10 #include <fmt/format.h>
11 
12 static unsigned int g_statusLines = 2;
13 static std::string g_windowTitle;
14 
15 void cleanup()
16 {
17  for(unsigned int i = 0; i < g_statusLines+1; ++i)
18  printf("\n");
19 
20  rosmon::Terminal term;
21 
22  // Switch cursor back on
23  term.setCursorVisible();
24 
25  // Switch character echo on
26  term.setEcho(true);
27 
28  // Restore window title (at least try)
29  if(!g_windowTitle.empty())
30  term.clearWindowTitle(g_windowTitle + "[-]");
31 }
32 
33 namespace rosmon
34 {
35 
36 UI::UI(monitor::Monitor* monitor, const FDWatcher::Ptr& fdWatcher)
37  : m_monitor(monitor)
38  , m_fdWatcher(fdWatcher)
39  , m_columns(80)
40  , m_selectedNode(-1)
41 {
42  std::atexit(cleanup);
43  m_monitor->logMessageSignal.connect(boost::bind(&UI::log, this, _1));
44 
45  m_sizeTimer = ros::NodeHandle().createWallTimer(ros::WallDuration(2.0), boost::bind(&UI::checkWindowSize, this));
47 
48  m_terminalCheckTimer = ros::NodeHandle().createWallTimer(ros::WallDuration(0.1), boost::bind(&UI::checkTerminal, this));
50 
52  setupColors();
53 
54  // Switch cursor off
56 
57  // Switch character echo off
58  m_term.setEcho(false);
59 
60  // Configure window title
61  std::string title = m_monitor->config()->windowTitle();
62  if(!title.empty())
63  {
64  m_term.setWindowTitle(title);
65  g_windowTitle = title;
66  }
67 
68  // Setup colors & styles
70  auto white = m_term.color(0xffffff, Terminal::White);
71  auto barFg = m_term.color(0xffffff, Terminal::Black);
72 
77 
84 
89 
90  fdWatcher->registerFD(STDIN_FILENO, boost::bind(&UI::readInput, this));
91 }
92 
94 {
95  m_fdWatcher->removeFD(STDIN_FILENO);
96 }
97 
99 {
100  // Sample colors from the HUSL space
101  int n = m_monitor->nodes().size();
102 
103  for(int i = 0; i < n; ++i)
104  {
105  float hue = i * 360 / n;
106  float sat = 100;
107  float lum = 20;
108 
109  float r, g, b;
110  HUSLtoRGB(&r, &g, &b, hue, sat, lum);
111 
112  r *= 255.0f;
113  g *= 255.0f;
114  b *= 255.0f;
115 
116  unsigned int color =
117  std::min(255, std::max(0, static_cast<int>(r)))
118  | (std::min(255, std::max(0, static_cast<int>(g))) << 8)
119  | (std::min(255, std::max(0, static_cast<int>(b))) << 16);
120 
121  m_nodeColorMap[m_monitor->nodes()[i]->fullName()] = ChannelInfo{&m_term, color};
122  }
123 }
124 
125 // Could be done more elegantly in C++14 with a variadic lambda
126 namespace
127 {
128  class ColumnPrinter
129  {
130  public:
131  constexpr unsigned int column() const
132  { return m_column; }
133 
134  template<typename ... Args>
135  void operator()(Args&& ... args)
136  {
137  std::string str = fmt::format(std::forward<Args>(args)...);
138  m_column += str.size();
139  fputs(str.c_str(), stdout);
140  }
141  private:
142  unsigned int m_column = 0;
143  };
144 }
145 
146 std::string UI::nodeDisplayName(monitor::NodeMonitor& node, std::size_t maxWidth)
147 {
148  std::string fullName;
149  if(node.namespaceString().empty())
150  fullName = node.name();
151  else
152  fullName = node.namespaceString() + "/" + node.name();
153 
154  // Strip initial / to save space
155  if(!fullName.empty() && fullName[0] == '/')
156  fullName = fullName.substr(1);
157 
158  return fullName.substr(0, maxWidth);
159 }
160 
162 {
163  const int NODE_WIDTH = 13;
164 
165  unsigned int lines = 0;
166 
167  // Draw line using UTF-8 box characters
168  {
172  for(int i = 0; i < m_columns; ++i)
173  fmt::print("▂");
174  putchar('\n');
175 
176  lines++;
177  }
178 
179  // Print menu / status line
180  {
183 
184  ColumnPrinter print;
185 
186  auto printKey = [&](const std::string& key, const std::string& label) {
188  print(" {}:", key);
189  m_style_bar.use();
190  print(" {} ", label);
191  };
192 
193  if(m_searchActive)
194  {
196  print("Searching for: {}", m_searchString);
197  m_style_bar.use();
198  }
199  else if(m_selectedNode != -1)
200  {
202  auto& selectedNode = m_monitor->nodes()[m_selectedNode];
203 
204  std::string state;
205  switch(selectedNode->state())
206  {
207  case monitor::NodeMonitor::STATE_RUNNING: state = "is running"; break;
208  case monitor::NodeMonitor::STATE_IDLE: state = "is idle"; break;
209  case monitor::NodeMonitor::STATE_CRASHED: state = "has crashed"; break;
210  case monitor::NodeMonitor::STATE_WAITING: state = "is waiting"; break;
211  default: state = "<UNKNOWN>"; break;
212  }
213 
214  print("Node '{}' {}. Actions: ", selectedNode->fullName(), state);
215  printKey("s", "start");
216  printKey("k", "stop");
217  printKey("d", "debug");
218 
219  if(selectedNode->isMuted())
220  printKey("u", "unmute");
221  else
222  printKey("m", "mute");
223  }
224  else
225  {
226  printKey("A-Z", "Node actions");
227  printKey("F6", "Start all");
228  printKey("F7", "Stop all");
229  printKey("F8", "Toggle WARN+ only");
230  printKey("F9", "Mute all");
231  printKey("F10", "Unmute all");
232  printKey("/", "Node search");
233 
234  if(stderrOnly())
235  {
236  print(" ");
239  print("! WARN+ output only !");
240  m_style_bar.use();
241  }
242 
243  if(anyMuted())
244  {
245  print(" ");
248  print("! Caution: Nodes muted !");
249  m_style_bar.use();
250  }
251  }
252 
253  for(int i = print.column(); i < m_columns; ++i)
254  putchar(' ');
255 
256  putchar('\n');
257 
258  lines++;
259  }
260 
261  int col = 0;
262 
265  if(m_searchActive)
266  {
267  const auto& nodes = m_monitor->nodes();
268  unsigned int i = 0;
269 
270  // We can use the space of the [ ] and key characters
271  constexpr auto SEARCH_NODE_WIDTH = NODE_WIDTH+3;
272 
273  std::size_t nodeWidth = SEARCH_NODE_WIDTH;
274  for(auto& nodeIdx : m_searchNodes)
275  nodeWidth = std::max(nodeWidth, nodeDisplayName(*nodes[nodeIdx]).length());
276 
277  // If it doesn't fit on one line, constrain to SEARCH_NODE_WIDTH
278  if(m_searchNodes.size() * (nodeWidth+1) >= static_cast<std::size_t>(m_columns-1))
279  nodeWidth = SEARCH_NODE_WIDTH;
280 
281  const int BLOCK_WIDTH = nodeWidth;
282  for(auto& nodeIdx : m_searchNodes)
283  {
284  const auto& node = m_monitor->nodes()[nodeIdx];
285 
286  if(i == m_searchSelectedIndex)
288  else
290 
291  std::string label = nodeDisplayName(*node, nodeWidth);
292  fmt::print("{:^{}}", label, nodeWidth);
294 
295  // Primitive wrapping control
296  col += BLOCK_WIDTH;
297 
298  if(col + 1 + BLOCK_WIDTH <= m_columns)
299  {
300  printf(" ");
301  col += 1;
302  }
303  else if(col + 1 + BLOCK_WIDTH > m_columns)
304  {
305  col = 0;
306  lines++;
307  putchar('\n');
309  }
310 
311  ++i;
312  }
313 
314  m_searchDisplayColumns = (m_columns+1) / (BLOCK_WIDTH+1);
315  }
316  else
317  {
318  char key = 'a';
319  int i = 0;
320 
321  for(auto& node : m_monitor->nodes())
322  {
323  if(m_selectedNode == -1)
324  {
325  // Print key with grey background
326  if(node->isMuted())
328  else
330 
331  fmt::print("{:c}", key);
332  }
333  else
334  {
336  fmt::print(" ");
337  }
338 
339  if(m_selectedNode == -1 || m_selectedNode == i)
340  {
341  switch(node->state())
342  {
345  break;
348  break;
351  break;
354  break;
355  }
356  }
357  else
358  {
359  switch(node->state())
360  {
363  break;
366  break;
369  break;
372  break;
373  }
374  }
375 
376  std::string label = nodeDisplayName(*node, NODE_WIDTH);
377  if(i == m_selectedNode)
378  fmt::print("[{:^{}}]", label, NODE_WIDTH);
379  else
380  fmt::print(" {:^{}} ", label, NODE_WIDTH);
382 
383  // Primitive wrapping control
384  const int BLOCK_WIDTH = NODE_WIDTH + 3;
385  col += BLOCK_WIDTH;
386 
387  if(col + 1 + BLOCK_WIDTH <= m_columns)
388  {
389  printf(" ");
390  col += 1;
391  }
392  else if(col + 1 + BLOCK_WIDTH > m_columns)
393  {
394  col = 0;
395  lines++;
396  putchar('\n');
398  }
399 
400  if(key == 'z')
401  key = 'A';
402  else if(key == 'Z')
403  key = '0';
404  else if(key == '9')
405  key = ' ';
406  else if(key != ' ')
407  ++key;
408 
409  ++i;
410  }
411  }
412 
413  // Erase rest of the lines
414  for(unsigned int i = lines; i < g_statusLines; ++i)
415  printf("\n\033[K");
416 
417  g_statusLines = std::max(lines, g_statusLines);
418 }
419 
420 void UI::log(const LogEvent& event)
421 {
422  // Is this node muted? Muted events go into the log, but are not shown in
423  // the UI.
424  if(event.muted)
425  return;
426 
427  // Are we supposed to show stdout?
428  if(event.channel == LogEvent::Channel::Stdout && (!event.showStdout || stderrOnly()))
429  return;
430 
431  const std::string& clean = event.message;
432 
433  auto it = m_nodeColorMap.find(event.source);
434 
435  // Is this a node message?
436  if(it != m_nodeColorMap.end())
437  {
438  m_term.setLineWrap(false);
439 
440  auto actualLabelWidth = std::max<unsigned int>(m_nodeLabelWidth, event.source.size());
441  auto lines = it->second.parser.wrap(clean, m_columns - actualLabelWidth - 2);
442 
443  for(unsigned int line = 0; line < lines.size(); ++line)
444  {
445  // Draw label
446  if(m_term.has256Colors())
447  {
448  if(it != m_nodeColorMap.end())
449  {
450  m_term.setBackgroundColor(it->second.labelColor);
452  }
453  }
454  else
455  {
457  }
458 
459  if(line == 0)
460  fmt::print("{:>{}}:", event.source, m_nodeLabelWidth);
461  else
462  {
463  for(unsigned int i = 0; i < actualLabelWidth-1; ++i)
464  putchar(' ');
465  fmt::print("~ ");
466  }
469  putchar(' ');
470 
471  fputs(lines[line].c_str(), stdout);
472  putchar('\n');
473  }
474 
475  m_term.setLineWrap(true);
476  }
477  else
478  {
479  fmt::print("{:>{}}:", event.source, m_nodeLabelWidth);
482  putchar(' ');
483 
484  unsigned int len = clean.length();
485  while(len != 0 && (clean[len-1] == '\n' || clean[len-1] == '\r'))
486  len--;
487 
488  switch(event.type)
489  {
490  case LogEvent::Type::Raw:
492  break;
495  break;
498  break;
499  }
500 
501  fwrite(clean.c_str(), 1, len, stdout);
503  putchar('\n');
504  }
505 
508  fflush(stdout);
509 
510  scheduleUpdate();
511 }
512 
514 {
515  if(!m_term.interactive())
516  return;
517 
518  if(!m_refresh_required)
519  return;
520 
521  m_refresh_required = false;
522 
523  // Disable automatic linewrap. This prevents ugliness on terminal resize.
524  m_term.setLineWrap(false);
525 
526  // We currently are at the beginning of the status line.
527  drawStatusLine();
528 
529  // Move back
533 
534  // Enable automatic linewrap again
535  m_term.setLineWrap(true);
536 
537  fflush(stdout);
538 }
539 
541 {
542  int rows, columns;
543  if(m_term.getSize(&columns, &rows))
544  m_columns = columns;
545 
546  std::size_t w = 20;
547  for(const auto& node : m_monitor->nodes())
548  w = std::max(w, node->fullName().size());
549 
550  m_nodeLabelWidth = std::min<unsigned int>(w, m_columns/4);
551 }
552 
554 {
555  int c = m_term.readKey();
556  if(c < 0)
557  return;
558 
559  handleKey(c);
560 }
561 
563 {
564  int c = m_term.readLeftover();
565  if(c < 0)
566  return;
567 
568  handleKey(c);
569 }
570 
571 void UI::handleKey(int c)
572 {
573  // Instead of trying to figure out when exactly we need a redraw, just
574  // redraw on every keystroke.
575  scheduleUpdate();
576 
577  // Are we in search mode?
578  if(m_searchActive)
579  {
580  if(c == '\n')
581  {
584  else
585  m_selectedNode = -1;
586 
587  m_searchActive = false;
588  return;
589  }
590 
591  if(c == '\E')
592  {
593  m_selectedNode = -1;
594  m_searchActive = false;
595  return;
596  }
597 
598  if(c == '\t')
599  {
603 
604  return;
605  }
606 
608  {
611 
612  if(c == Terminal::SK_Right)
613  {
614  if(col < static_cast<int>(m_searchDisplayColumns)-1 && m_searchSelectedIndex < m_searchNodes.size()-1)
616  return;
617  }
618 
619  if(c == Terminal::SK_Left)
620  {
621  if(col > 0)
623  return;
624  }
625 
626  if(c == Terminal::SK_Up)
627  {
628  if(row > 0)
630  return;
631  }
632 
633  if(c == Terminal::SK_Down)
634  {
635  int numRows = (m_searchNodes.size() + m_searchDisplayColumns - 1) / m_searchDisplayColumns;
636  if(row < numRows - 1)
638  return;
639  }
640  }
641 
642  if(c == Terminal::SK_Backspace)
643  {
644  if(!m_searchString.empty())
645  m_searchString.pop_back();
646  }
647  else if(std::isgraph(c))
648  m_searchString.push_back(c);
649 
651 
652  // Recompute matched nodes
653  m_searchNodes.clear();
654  const auto& nodes = m_monitor->nodes();
655  for(unsigned int i = 0; i < nodes.size(); ++i)
656  {
657  const auto& node = nodes[i];
658  auto idx = nodeDisplayName(*node).find(m_searchString);
659  if(idx != std::string::npos)
660  m_searchNodes.push_back(i);
661  }
662 
663  return;
664  }
665 
666  if(m_selectedNode == -1)
667  {
668  int nodeIndex = -1;
669 
670  if(c == Terminal::SK_F6)
671  {
672  startAll();
673  return;
674  }
675 
676  if(c == Terminal::SK_F7)
677  {
678  stopAll();
679  return;
680  }
681 
682  // Check for Mute all keys first
683  if(c == Terminal::SK_F9)
684  {
685  muteAll();
686  return;
687  }
688 
689  if(c == Terminal::SK_F10)
690  {
691  unmuteAll();
692  return;
693  }
694 
695  // Check for Stderr Only Toggle
696  if(c == Terminal::SK_F8)
697  {
699  return;
700  }
701 
702  // Search
703  if(c == '/')
704  {
705  m_searchString = {};
707  m_searchNodes.resize(m_monitor->nodes().size());
708  std::iota(m_searchNodes.begin(), m_searchNodes.end(), 0);
709  m_searchActive = true;
710  return;
711  }
712 
713  if(c >= 'a' && c <= 'z')
714  nodeIndex = c - 'a';
715  else if(c >= 'A' && c <= 'Z')
716  nodeIndex = 26 + c - 'A';
717  else if(c >= '0' && c <= '9')
718  nodeIndex = 26 + 26 + c - '0';
719 
720  if(nodeIndex < 0 || (size_t)nodeIndex >= m_monitor->nodes().size())
721  return;
722 
723  m_selectedNode = nodeIndex;
724  }
725  else
726  {
727  auto& node = m_monitor->nodes()[m_selectedNode];
728 
729  switch(c)
730  {
731  case 's':
732  node->start();
733  break;
734  case 'k':
735  node->stop();
736  break;
737  case 'd':
738  node->launchDebugger();
739  break;
740  case 'm':
741  node->setMuted(true);
742  break;
743  case 'u':
744  node->setMuted(false);
745  break;
746  }
747 
748  m_selectedNode = -1;
749  }
750 }
751 
752 bool UI::anyMuted() const
753 {
754  return std::any_of(m_monitor->nodes().begin(), m_monitor->nodes().end(), [](const monitor::NodeMonitor::Ptr& n){
755  return n->isMuted();
756  });
757 }
758 
760 {
761  for(auto& n : m_monitor->nodes())
762  n->start();
763 }
764 
766 {
767  for(auto& n : m_monitor->nodes())
768  n->stop();
769 }
770 
772 {
773  for(auto& n : m_monitor->nodes())
774  n->setMuted(true);
775 }
776 
778 {
779  for(auto& n : m_monitor->nodes())
780  n->setMuted(false);
781 }
782 
784 {
785  m_refresh_required = true;
786 }
787 
789 {
790  return m_stderr_only;
791 }
792 
794 {
796 }
797 
798 }
const std::vector< NodeMonitor::Ptr > & nodes() const
Definition: monitor.h:41
~UI()
Definition: ui.cpp:93
boost::signals2::signal< void(LogEvent)> logMessageSignal
Definition: monitor.h:49
std::map< std::string, ChannelInfo > m_nodeColorMap
Definition: ui.h:85
int m_selectedNode
Definition: ui.h:87
void scheduleUpdate()
Definition: ui.cpp:783
bool anyMuted() const
Definition: ui.cpp:752
bool m_stderr_only
Definition: ui.h:77
bool interactive() const
Definition: terminal.h:217
bool getSize(int *columns, int *rows)
Get current window size.
Definition: terminal.cpp:480
void setupColors()
Definition: ui.cpp:98
std::string m_searchString
Definition: ui.h:92
Monitors a single node process.
Definition: node_monitor.h:25
void setSimpleBackground(SimpleColor color)
Definition: terminal.cpp:416
void cleanup()
Definition: ui.cpp:15
void moveCursorToStartOfLine()
Move cursor to start of the line.
Definition: terminal.cpp:467
bool m_refresh_required
Definition: ui.h:76
std::string nodeDisplayName(monitor::NodeMonitor &node, std::size_t maxWidth=std::string::npos)
Definition: ui.cpp:146
Color color(SimpleColor code)
Definition: terminal.cpp:616
void checkTerminal()
Definition: ui.cpp:562
FDWatcher::Ptr m_fdWatcher
Definition: ui.h:75
void setBackgroundColor(uint32_t color)
Set 24-bit background color.
Definition: terminal.cpp:341
UI(monitor::Monitor *monitor, const FDWatcher::Ptr &fdWatcher)
Definition: ui.cpp:36
Terminal::Style m_style_nodeIdle
Definition: ui.h:107
Terminal::Style m_style_barLine
Definition: ui.h:99
void startAll()
Definition: ui.cpp:759
ROSCPP_DECL std::string clean(const std::string &name)
Channel channel
Definition: log_event.h:42
Terminal::Style m_style_nodeWaitingFaded
Definition: ui.h:115
unsigned int m_searchSelectedIndex
Definition: ui.h:93
monitor::Monitor * m_monitor
Definition: ui.h:74
ROSCONSOLE_DECL void print(FilterBase *filter, void *logger, Level level, const char *file, int line, const char *function, const char *fmt,...) ROSCONSOLE_PRINTF_ATTRIBUTE(7
void setEcho(bool on)
Definition: terminal.cpp:377
bool stderrOnly()
Definition: ui.cpp:788
void setSimplePair(SimpleColor fg, SimpleColor bg)
Definition: terminal.cpp:425
Terminal::Style m_style_nodeCrashed
Definition: ui.h:109
ros::WallTimer m_sizeTimer
Definition: ui.h:82
Idle (e.g. exited with code 0)
Definition: node_monitor.h:34
void update()
Definition: ui.cpp:513
std::string namespaceString() const
Node namespace.
Definition: node_monitor.h:165
Terminal::Style m_style_nodeWaiting
Definition: ui.h:110
void HUSLtoRGB(float *r, float *g, float *b, float h, float s, float l)
Definition: husl.c:56
Terminal::Style m_style_nodeIdleFaded
Definition: ui.h:112
void setLineWrap(bool on)
Definition: terminal.cpp:472
state
Definition: basic.py:139
void clearToEndOfLine()
Clear characters from cursor to end of line.
Definition: terminal.cpp:451
bool m_searchActive
Definition: ui.h:91
void toggleStderrOnly()
Definition: ui.cpp:793
static std::string g_windowTitle
Definition: ui.cpp:13
Terminal::Style m_style_nodeRunningFaded
Definition: ui.h:113
unsigned int m_nodeLabelWidth
Definition: ui.h:117
Terminal::Style m_style_bar
Definition: ui.h:100
Terminal::Style m_style_nodeKeyMuted
Definition: ui.h:105
Terminal::Style m_style_nodeKey
Definition: ui.h:104
void drawStatusLine()
Definition: ui.cpp:161
std::vector< unsigned int > m_searchNodes
Definition: ui.h:94
unsigned int m_column
Definition: ui.cpp:142
Terminal m_term
Definition: ui.h:79
string b
Definition: busy_node.py:4
void setStandardColors()
Reset fg + bg to standard terminal colors.
Definition: terminal.cpp:434
void checkWindowSize()
Definition: ui.cpp:540
Waiting for automatic restart after crash.
Definition: node_monitor.h:37
Terminal::Color m_color_bar
Definition: ui.h:97
static unsigned int g_statusLines
Definition: ui.cpp:12
void setCursorVisible()
restore cursor
Definition: terminal.cpp:320
void setSimpleForeground(SimpleColor color)
Definition: terminal.cpp:407
void readInput()
Definition: ui.cpp:553
void unmuteAll()
Definition: ui.cpp:777
Encapsulates terminal control.
Definition: terminal.h:22
void moveCursorUp(int numLines)
Move cursor up by numLines.
Definition: terminal.cpp:459
bool has256Colors() const
Definition: terminal.cpp:307
void setWindowTitle(const std::string &title)
Definition: terminal.cpp:493
void log(const LogEvent &event)
Definition: ui.cpp:420
Terminal::Style m_style_nodeRunning
Definition: ui.h:108
void setCursorInvisible()
hide cursor
Definition: terminal.cpp:312
Terminal::Style m_style_barKey
Definition: ui.h:101
Crashed (i.e. exited with code != 0)
Definition: node_monitor.h:36
launch::LaunchConfig::ConstPtr config() const
Definition: monitor.h:46
unsigned int m_searchDisplayColumns
Definition: ui.h:95
void muteAll()
Definition: ui.cpp:771
ros::WallTimer m_terminalCheckTimer
Definition: ui.h:83
std::string name() const
Node name.
Definition: node_monitor.h:161
std::string source
Definition: log_event.h:38
void handleKey(int key)
Definition: ui.cpp:571
void clearWindowTitle(const std::string &backup)
Definition: terminal.cpp:506
Terminal::Style m_style_nodeCrashedFaded
Definition: ui.h:114
Terminal::Style m_style_barHighlight
Definition: ui.h:102
std::shared_ptr< NodeMonitor > Ptr
Definition: node_monitor.h:28
void stopAll()
Definition: ui.cpp:765
int m_columns
Definition: ui.h:81


rosmon_core
Author(s): Max Schwarz
autogenerated on Sat Jan 9 2021 03:35:43