ui.cpp
Go to the documentation of this file.
1 // Terminal UI
2 // Author: Max Schwarz <max.schwarz@uni-bonn.de>
3 
4 #include "ui.h"
5 #include "bag_writer.h"
6 #include "bag_reader.h"
7 
8 #include <fmt/format.h>
9 #include <fmt/chrono.h>
10 
11 #include <ros/node_handle.h>
12 
13 namespace rosbag_fancy
14 {
15 
16 namespace
17 {
18  unsigned int g_statusLines = 2;
19  std::string g_windowTitle;
20 
21  void cleanup()
22  {
23  for(unsigned int i = 0; i < g_statusLines+1; ++i)
24  printf("\n");
25 
26  Terminal term;
27 
28  // Switch cursor back on
29  term.setCursorVisible();
30 
31  // Switch character echo on
32  term.setEcho(true);
33  }
34 
35  std::string memoryToString(uint64_t memory)
36  {
37  if(memory < static_cast<uint64_t>(1<<10))
38  return fmt::format("{}.0 B", memory);
39  else if(memory < static_cast<uint64_t>(1<<20))
40  return fmt::format("{:.1f} KiB", static_cast<double>(memory) / static_cast<uint64_t>(1<<10));
41  else if(memory < static_cast<uint64_t>(1<<30))
42  return fmt::format("{:.1f} MiB", static_cast<double>(memory) / static_cast<uint64_t>(1<<20));
43  else if(memory < static_cast<uint64_t>(1ull<<40))
44  return fmt::format("{:.1f} GiB", static_cast<double>(memory) / static_cast<uint64_t>(1ull<<30));
45  else
46  return fmt::format("{:.1f} TiB", static_cast<double>(memory) / static_cast<uint64_t>(1ull<<40));
47  }
48 
49  std::string rateToString(double rate)
50  {
51  if(rate < 1000.0)
52  return fmt::format("{:5.1f} Hz", rate);
53  else if(rate < 1e6)
54  return fmt::format("{:5.1f} kHz", rate / 1e3);
55  else
56  return fmt::format("{:5.1f} MHz", rate / 1e6);
57  }
58 
59  template<int Columns>
60  class TableWriter
61  {
62  public:
63  struct Column
64  {
65  Column(const std::string& label, unsigned int width = 0, const std::string& format = {})
67  {
68  if(width == 0)
69  this->width = label.size();
70 
71  valueFormatString = fmt::format("{{:{}{}}}", this->width, format);
72  }
73 
74  std::string label;
75  unsigned int width;
76  std::string format;
77 
78  std::string valueFormatString;
79  };
80 
81  TableWriter(Terminal& term, const std::array<Column, Columns>& columns)
82  : m_term(term)
83  , m_cols(columns)
84  {}
85 
86  void printHeader()
87  {
88  {
89  bool first = true;
90  for(auto& col : m_cols)
91  {
92  if(first)
93  first = false;
94  else
95  fmt::print(" │ ");
96 
97  std::string format = fmt::format("{{:^{}}}", col.width);
98  fmt::print(format, col.label);
99  }
100  fmt::print("\n");
101  }
102 
103  printDash();
104  }
105 
106  void printDash()
107  {
108  bool first = true;
109  for(auto& col : m_cols)
110  {
111  if(first)
112  first = false;
113  else
114  fmt::print("─┼─");
115 
116  for(unsigned int i = 0; i < col.width; ++i)
117  fmt::print("─");
118  }
119  fmt::print("\n");
120  }
121 
122  void startRow()
123  {
124  m_currentCol = 0;
125  }
126 
127  void endRow()
128  {
129  fmt::print("\n");
130  }
131 
132  template<class T>
133  void printColumn(const T& value, uint32_t color = 0)
134  {
135  if(m_currentCol != 0)
136  fmt::print(" │ ");
137 
138  if(color != 0)
139  m_term.setForegroundColor(color);
140 
141  fmt::print(m_cols[m_currentCol].valueFormatString, value);
142 
143  if(color != 0)
144  m_term.setStandardColors();
145 
146  m_currentCol++;
147  }
148 
149  private:
150  Terminal& m_term;
151  std::array<Column, Columns> m_cols;
152 
153  unsigned int m_currentCol = 0;
154  };
155 }
156 
157 UI::UI(TopicManager& config, MessageQueue& queue, BagWriter& writer)
158  : m_topicManager{config}
159  , m_queue{queue}
160  , m_bagWriter{writer}
161 {
162  std::atexit(&cleanup);
163 
164  // Switch cursor off
166 
167  // Switch character echo off
168  m_term.setEcho(false);
169 
170  g_statusLines = m_topicManager.topics().size();
171 
172  ros::NodeHandle nh;
173  m_timer = nh.createSteadyTimer(ros::WallDuration(0.1), boost::bind(&UI::draw, this));
174 }
175 
176 template<class... Args>
177 void UI::printLine(unsigned int& lineCounter, const Args& ... args)
178 {
179  lineCounter++;
181  fmt::print(args...);
182  putchar('\n');
183 }
184 
185 void UI::draw()
186 {
187  unsigned int cnt = 0;
188 
190 
191  printLine(cnt, "");
192  printLine(cnt, "");
193 
194  uint64_t totalMessages = 0;
195  uint64_t totalBytes = 0;
196  float totalRate = 0.0f;
197  float totalBandwidth = 0.0f;
198  bool totalActivity = false;
199  unsigned int totalDrops = 0;
200 
201  unsigned int maxTopicWidth = 0;
202  for(auto& topic : m_topicManager.topics())
203  maxTopicWidth = std::max<unsigned int>(maxTopicWidth, topic.name.length());
204 
205  TableWriter<6> writer{m_term, {{
206  {"Act"},
207  {"Topic", maxTopicWidth},
208  {"Pub"},
209  {"Messages", 22},
210  {"Bytes", 25},
211  {"Drops"}
212  }}};
213 
214  writer.printHeader();
215  cnt += 2;
216 
217  auto& counts = m_bagWriter.messageCounts();
218  auto& bytes = m_bagWriter.byteCounts();
219 
220  for(auto& topic : m_topicManager.topics())
221  {
222  float messageRate = topic.messageRateAt(now);
223  bool activity = topic.lastMessageTime > m_lastDrawTime;
224 
225  writer.startRow();
226 
227  if(activity)
228  {
229  totalActivity = true;
230  writer.printColumn(" ▮ ", 0x00FF00);
231  }
232  else
233  writer.printColumn("");
234 
235  writer.printColumn(topic.name);
236  writer.printColumn(topic.numPublishers, topic.numPublishers == 0 ? 0x0000FF : 0);
237 
238  uint32_t messageColor = (topic.totalMessages == 0) ? 0x0000FF : 0;
239 
240  uint64_t messageCount = topic.id < counts.size() ? counts[topic.id] : 0;
241  uint64_t byteCount = topic.id < bytes.size() ? bytes[topic.id] : 0;
242 
243  writer.printColumn(fmt::format("{:10} ({:>8})", messageCount, rateToString(messageRate)), messageColor);
244  writer.printColumn(fmt::format("{:>10} ({:>10}/s)", memoryToString(byteCount), memoryToString(topic.bandwidth)));
245 
246  writer.printColumn(topic.dropCounter, topic.dropCounter > 0 ? 0x0000FF : 0);
247 
248  writer.endRow();
249  cnt++;
250 
251  totalMessages += messageCount;
252  totalBytes += byteCount;
253  totalRate += messageRate;
254  totalBandwidth += topic.bandwidth;
255  totalDrops += topic.dropCounter;
256 
258  }
259  writer.printDash();
260  cnt++;
261 
262  writer.startRow();
263  if(totalActivity)
264  writer.printColumn(" ▮ ", 0x00FF00);
265  else
266  writer.printColumn("");
267  writer.printColumn("All");
268  writer.printColumn("");
269  writer.printColumn(fmt::format("{:10} ({:>8})", totalMessages, rateToString(totalRate)));
270  writer.printColumn(fmt::format("{:>10} ({:>10}/s)", memoryToString(totalBytes), memoryToString(totalBandwidth)));
271  writer.printColumn(totalDrops, totalDrops > 0 ? 0x0000FF : 0);
272 
273  writer.endRow();
274  cnt++;
275 
276  printLine(cnt, "");
277  if(m_bagWriter.running())
278  {
279  m_term.setForegroundColor(0x00FF00);
280  printLine(cnt, "Recording...");
282  }
283  else
284  {
285  m_term.setForegroundColor(0x0000FF);
286  printLine(cnt, "Paused.");
288  }
289  printLine(cnt, "Message queue: {:10} messages, {:>10}", m_queue.messagesInQueue(), memoryToString(m_queue.bytesInQueue()));
290 
291  printLine(cnt, "Compression: {:>10}", [&](){
292  switch(m_bagWriter.compression())
293  {
294  case rosbag::compression::Uncompressed: return "None";
295  case rosbag::compression::BZ2: return "BZ2";
296  case rosbag::compression::LZ4: return "LZ4";
297  }
298 
299  return "Unknown";
300  }());
301 
302  if(m_bagWriter.splitSizeInBytes() != 0)
303  {
304  printLine(cnt, "Bag size: {:>10} / {:>10} split size / {:>10} available",
308  );
309  }
310  else
311  {
312  printLine(cnt, "Bag size: {:>10} / {:>10} available",
315  );
316  }
317 
319  {
320  printLine(cnt, "Directory size: {:>10} / {:>10}",
323  );
324  }
325  else
326  {
327  printLine(cnt, "Directory size: {:>10}",
329  );
330  }
331 
332  g_statusLines = cnt;
333 
334  // Move back
336  m_term.moveCursorUp(g_statusLines);
338  fflush(stdout);
339 
340  m_lastDrawTime = now;
341 }
342 
343 
344 
345 // Playback UI
346 PlaybackUI::PlaybackUI(TopicManager& topics, const ros::Time& startTime, const ros::Time& endTime)
347  : m_topicManager{topics}
348  , m_startTime{startTime}
349  , m_endTime{endTime}
350 {
351  std::atexit(&cleanup);
352 
353  // Switch cursor off
355 
356  // Switch character echo off
357  m_term.setEcho(false);
358 
359  g_statusLines = m_topicManager.topics().size();
360 
361  ros::NodeHandle nh;
362  m_timer = nh.createSteadyTimer(ros::WallDuration(0.1), boost::bind(&PlaybackUI::draw, this));
363 }
364 
365 template<class... Args>
366 void PlaybackUI::printLine(unsigned int& lineCounter, const Args& ... args)
367 {
368  lineCounter++;
370  fmt::print(args...);
371  putchar('\n');
372 }
373 
375 {
376  unsigned int cnt = 0;
377 
379 
380  printLine(cnt, "");
381  printLine(cnt, "");
382 
383  float totalRate = 0.0f;
384  float totalBandwidth = 0.0f;
385  bool totalActivity = false;
386  unsigned int totalDrops = 0;
387 
388  unsigned int maxTopicWidth = 0;
389  for(auto& topic : m_topicManager.topics())
390  maxTopicWidth = std::max<unsigned int>(maxTopicWidth, topic.name.length());
391 
392  TableWriter<4> writer{m_term, {{
393  {"Act"},
394  {"Topic", maxTopicWidth},
395  {"Messages", 22},
396  {"Bytes", 25}
397  }}};
398 
399  writer.printHeader();
400  cnt += 2;
401 
402  for(auto& topic : m_topicManager.topics())
403  {
404  float messageRate = topic.messageRateAt(now);
405  bool activity = topic.lastMessageTime > m_lastDrawTime;
406 
407  writer.startRow();
408 
409  if(activity)
410  {
411  totalActivity = true;
412  writer.printColumn(" ▮ ", 0x00FF00);
413  }
414  else
415  writer.printColumn("");
416 
417  writer.printColumn(topic.name);
418 
419  uint32_t messageColor = (topic.totalMessages == 0) ? 0x0000FF : 0;
420 
421  writer.printColumn(fmt::format("{:>8}", rateToString(messageRate)), messageColor);
422  writer.printColumn(fmt::format("{:>10}/s", memoryToString(topic.bandwidth)));
423 
424  writer.endRow();
425  cnt++;
426 
427  totalRate += messageRate;
428  totalBandwidth += topic.bandwidth;
429  totalDrops += topic.dropCounter;
430 
432  }
433  writer.printDash();
434  cnt++;
435 
436  writer.startRow();
437  if(totalActivity)
438  writer.printColumn(" ▮ ", 0x00FF00);
439  else
440  writer.printColumn("");
441  writer.printColumn("All");
442  writer.printColumn(fmt::format("{:>8}", rateToString(totalRate)));
443  writer.printColumn(fmt::format("{:>10}/s", memoryToString(totalBandwidth)));
444 
445  writer.endRow();
446  cnt++;
447 
448  printLine(cnt, "");
449 
450  // Size info
451  {
452  // A lot of std::chrono magic to get local/UTC time
453  std::chrono::time_point<std::chrono::system_clock, std::chrono::nanoseconds> startTimeC(std::chrono::nanoseconds(m_startTime.toNSec()));
454  std::chrono::time_point<std::chrono::system_clock, std::chrono::nanoseconds> endTimeC(std::chrono::nanoseconds(m_endTime.toNSec()));
455  std::chrono::time_point<std::chrono::system_clock, std::chrono::nanoseconds> currentTimeC(std::chrono::nanoseconds(m_positionInBag.toNSec()));
456 
457  std::chrono::seconds startTimeS = std::chrono::duration_cast<std::chrono::seconds>(startTimeC.time_since_epoch());
458  std::time_t startTimeSC(startTimeS.count());
459  std::tm startTimeB;
460  std::tm startTimeBUTC;
461  localtime_r(&startTimeSC, &startTimeB);
462  gmtime_r(&startTimeSC, &startTimeBUTC);
463 
464  std::chrono::seconds endTimeS = std::chrono::duration_cast<std::chrono::seconds>(endTimeC.time_since_epoch());
465  std::time_t endTimeSC(endTimeS.count());
466  std::tm endTimeB;
467  std::tm endTimeBUTC;
468  localtime_r(&endTimeSC, &endTimeB);
469  gmtime_r(&endTimeSC, &endTimeBUTC);
470 
471  std::chrono::seconds currentTimeS = std::chrono::duration_cast<std::chrono::seconds>(currentTimeC.time_since_epoch());
472  std::time_t currentTimeSC(currentTimeS.count());
473  std::tm currentTimeB;
474  std::tm currentTimeBUTC;
475  localtime_r(&currentTimeSC, &currentTimeB);
476  gmtime_r(&currentTimeSC, &currentTimeBUTC);
477 
478  std::chrono::duration<double, std::nano> duration{(m_endTime - m_startTime).toNSec()};
479  std::chrono::duration<double, std::nano> positionInBag{(m_positionInBag - m_startTime).toNSec()};
480 
481  printLine(cnt, "Start time: {:%Y-%m-%d %H:%M:%S} ({}) / {:%Y-%m-%d %H:%M:%S} (UTC)", startTimeB, daylight ? tzname[1] : tzname[0], startTimeBUTC);
482  printLine(cnt, "End time: {:%Y-%m-%d %H:%M:%S} ({}) / {:%Y-%m-%d %H:%M:%S} (UTC)", endTimeB, daylight ? tzname[1] : tzname[0], endTimeBUTC);
483  printLine(cnt, "Current time: {:%Y-%m-%d %H:%M:%S} ({}) / {:%Y-%m-%d %H:%M:%S} (UTC)", currentTimeB, daylight ? tzname[1] : tzname[0], currentTimeBUTC);
484  printLine(cnt, "Duration: {:.2%H:%M:%S} ({:7.2f}s)", duration, (m_endTime - m_startTime).toSec());
485  printLine(cnt, "Position: {:.2%H:%M:%S} ({:7.2f}s)", positionInBag, (m_positionInBag - m_startTime).toSec());
486  printLine(cnt, "");
487  }
488 
489  // Progress bar
490  {
491  int w = 80, h;
492  m_term.getSize(&w, &h);
493 
494  w -= 3;
495  fmt::print("│");
496 
497  int steps = w * 8;
498  int pos = (m_positionInBag - m_startTime).toSec() / (m_endTime - m_startTime).toSec() * steps;
499 
500  for(int i = 0; i < pos / 8; ++i)
501  fmt::print("█");
502  switch(pos % 8)
503  {
504  case 0: fmt::print(" "); break;
505  case 1: fmt::print("▏"); break;
506  case 2: fmt::print("▎"); break;
507  case 3: fmt::print("▍"); break;
508  case 4: fmt::print("▌"); break;
509  case 5: fmt::print("▋"); break;
510  case 6: fmt::print("▊"); break;
511  case 7: fmt::print("▉"); break;
512  }
513 
514  for(int i = 0; i < w - pos/8 - 1; ++i)
515  putchar(' ');
516  fmt::print("│\n");
517 
518  cnt++;
519  }
520 
521  printLine(cnt, "");
522 
523  {
525 
527 
528  fmt::print("Hit ");
529 
530  if(m_paused)
532  fmt::print("[space]");
534 
535  fmt::print(" for pause, ");
536 
537  if(now - m_lastSeekBwd < ros::WallDuration(0.5))
539  fmt::print("[left]");
541 
542  fmt::print("/");
543 
544  if(now - m_lastSeekFwd < ros::WallDuration(0.5))
546  fmt::print("[right]");
548 
549  fmt::print(" for seeking\n");
550 
551  cnt++;
552  }
553 
554  g_statusLines = cnt;
555 
556  // Move back
558  m_term.moveCursorUp(g_statusLines);
560  fflush(stdout);
561 
562  m_lastDrawTime = now;
563 }
564 
566 {
567  m_positionInBag = stamp;
568 }
569 
570 void PlaybackUI::setPaused(bool paused)
571 {
572  m_paused = paused;
573 }
574 
576 {
577  int c = m_term.readKey();
578  if(c < 0)
579  return;
580 
581  switch(c)
582  {
583  case Terminal::SK_Left:
586  break;
587  case Terminal::SK_Right:
590  break;
591  case ' ':
592  pauseRequested();
593  break;
594  case 'q':
595  exitRequested();
596  break;
597  }
598 }
599 
600 }
rosbag_fancy::MessageQueue
Definition: message_queue.h:23
ui.h
rosbag_fancy::Terminal::readKey
int readKey()
Definition: terminal.cpp:432
rosbag_fancy::PlaybackUI::m_topicManager
TopicManager & m_topicManager
Definition: ui.h:63
rosbag_fancy::PlaybackUI::printLine
void printLine(unsigned int &lineCounter, const Args &... args)
Definition: ui.cpp:366
rosbag_fancy::UI::m_topicManager
TopicManager & m_topicManager
Definition: ui.h:32
rosbag_fancy::UI::m_term
Terminal m_term
Definition: ui.h:36
node_handle.h
rosbag_fancy::PlaybackUI::exitRequested
boost::signals2::signal< void()> exitRequested
Definition: ui.h:57
rosbag_fancy::BagWriter::deleteOldAtInBytes
std::uint64_t deleteOldAtInBytes() const
Definition: bag_writer.h:52
valueFormatString
std::string valueFormatString
Definition: ui.cpp:78
rosbag_fancy::Terminal::setForegroundColor
void setForegroundColor(uint32_t color)
Set 24-bit foreground color.
Definition: terminal.cpp:293
rosbag_fancy::MessageQueue::bytesInQueue
uint64_t bytesInQueue() const
Definition: message_queue.h:44
rosbag_fancy::Terminal::moveCursorUp
void moveCursorUp(int numLines)
Move cursor up by numLines.
Definition: terminal.cpp:385
rosbag_fancy::BagWriter::compression
rosbag::compression::CompressionType compression() const
Definition: bag_writer.h:67
width
unsigned int width
Definition: ui.cpp:75
rosbag_fancy::PlaybackUI::m_startTime
ros::Time m_startTime
Definition: ui.h:65
rosbag_fancy::BagWriter::freeSpace
std::uint64_t freeSpace() const
Definition: bag_writer.h:55
rosbag_fancy::Terminal::setCursorInvisible
void setCursorInvisible()
hide cursor
Definition: terminal.cpp:246
rosbag_fancy
Definition: bag_reader.cpp:240
rosbag_fancy::Terminal::Black
@ Black
Definition: terminal.h:32
rosbag_fancy::PlaybackUI::m_lastSeekBwd
ros::SteadyTime m_lastSeekBwd
Definition: ui.h:76
rosbag_fancy::TopicManager::topics
std::vector< Topic > & topics()
Definition: topic_manager.h:106
rosbag_fancy::PlaybackUI::seekBackwardRequested
boost::signals2::signal< void()> seekBackwardRequested
Definition: ui.h:55
rosbag_fancy::PlaybackUI::setPositionInBag
void setPositionInBag(const ros::Time &stamp)
Definition: ui.cpp:565
rosbag_fancy::PlaybackUI::PlaybackUI
PlaybackUI(TopicManager &topics, const ros::Time &startTime, const ros::Time &endTime)
Definition: ui.cpp:346
label
std::string label
Definition: ui.cpp:74
rosbag_fancy::BagWriter::sizeInBytes
std::uint64_t sizeInBytes() const
Definition: bag_writer.h:43
rosbag_fancy::PlaybackUI::m_lastSeekFwd
ros::SteadyTime m_lastSeekFwd
Definition: ui.h:75
rosbag_fancy::Terminal::SK_Right
@ SK_Right
Definition: terminal.h:169
rosbag_fancy::BagWriter::messageCounts
const std::vector< std::uint64_t > & messageCounts() const
Definition: bag_writer.h:61
rosbag_fancy::PlaybackUI::handleInput
void handleInput()
Definition: ui.cpp:575
rosbag_fancy::PlaybackUI::m_term
Terminal m_term
Definition: ui.h:68
rosbag_fancy::Terminal::setSimplePair
void setSimplePair(SimpleColor fg, SimpleColor bg)
Definition: terminal.cpp:359
ros::SteadyTime::now
static SteadyTime now()
m_cols
std::array< Column, Columns > m_cols
Definition: ui.cpp:151
rosbag_fancy::PlaybackUI::m_positionInBag
ros::Time m_positionInBag
Definition: ui.h:73
rosbag_fancy::UI::draw
void draw()
Definition: ui.cpp:185
m_term
Terminal & m_term
Definition: ui.cpp:150
bag_writer.h
ros::WallTime::now
static WallTime now()
ros::SteadyTime
rosbag_fancy::Terminal::getSize
bool getSize(int *columns, int *rows)
Get current window size.
Definition: terminal.cpp:398
rosbag_fancy::PlaybackUI::seekForwardRequested
boost::signals2::signal< void()> seekForwardRequested
Definition: ui.h:54
rosbag_fancy::PlaybackUI::m_paused
bool m_paused
Definition: ui.h:78
rosbag_fancy::mem_str::memoryToString
std::string memoryToString(uint64_t memory)
Definition: mem_str.cpp:15
rosbag_fancy::PlaybackUI::m_lastDrawTime
ros::WallTime m_lastDrawTime
Definition: ui.h:71
rosbag_fancy::PlaybackUI::m_endTime
ros::Time m_endTime
Definition: ui.h:66
rosbag_fancy::BagWriter::directorySizeInBytes
std::uint64_t directorySizeInBytes() const
Definition: bag_writer.h:49
m_currentCol
unsigned int m_currentCol
Definition: ui.cpp:153
rosbag_fancy::PlaybackUI::setPaused
void setPaused(bool paused)
Definition: ui.cpp:570
rosbag_fancy::PlaybackUI::draw
void draw()
Definition: ui.cpp:374
rosbag_fancy::Terminal::White
@ White
Definition: terminal.h:39
ros::WallTime
format
std::string format
Definition: ui.cpp:76
rosbag_fancy::BagWriter::splitSizeInBytes
std::uint64_t splitSizeInBytes() const
Definition: bag_writer.h:46
rosbag_fancy::UI::printLine
void printLine(unsigned int &lineCounter, const Args &... args)
Definition: ui.cpp:177
rosbag_fancy::BagWriter
Definition: bag_writer.h:23
rosbag_fancy::BagWriter::running
bool running() const
Definition: bag_writer.h:40
rosbag_fancy::UI::m_bagWriter
BagWriter & m_bagWriter
Definition: ui.h:34
ros::Time
ros::NodeHandle::createSteadyTimer
SteadyTimer createSteadyTimer(SteadyTimerOptions &ops) const
rosbag_fancy::UI::UI
UI(TopicManager &config, MessageQueue &queue, BagWriter &writer)
Definition: ui.cpp:157
bag_reader.h
rosbag_fancy::Terminal::setStandardColors
void setStandardColors()
Reset fg + bg to standard terminal colors.
Definition: terminal.cpp:368
rosbag_fancy::UI::m_queue
MessageQueue & m_queue
Definition: ui.h:33
TimeBase< Time, Duration >::toNSec
uint64_t toNSec() const
rosbag_fancy::Terminal::SK_Left
@ SK_Left
Definition: terminal.h:169
args
rosbag_fancy::MessageQueue::messagesInQueue
uint64_t messagesInQueue() const
Definition: message_queue.h:47
rosbag_fancy::Terminal::setEcho
void setEcho(bool on)
Definition: terminal.cpp:311
ros::WallDuration
rosbag_fancy::Terminal::moveCursorToStartOfLine
void moveCursorToStartOfLine()
Move cursor to start of the line.
Definition: terminal.cpp:393
rosbag_fancy::PlaybackUI::pauseRequested
boost::signals2::signal< void()> pauseRequested
Definition: ui.h:56
rosbag_fancy::BagWriter::byteCounts
const std::vector< std::uint64_t > & byteCounts() const
Definition: bag_writer.h:64
rosbag_fancy::TopicManager
Definition: topic_manager.h:101
ros::NodeHandle
rosbag_fancy::UI::m_lastDrawTime
ros::WallTime m_lastDrawTime
Definition: ui.h:39
rosbag_fancy::Terminal::clearToEndOfLine
void clearToEndOfLine()
Clear characters from cursor to end of line.
Definition: terminal.cpp:377


rosbag_fancy
Author(s):
autogenerated on Tue Feb 20 2024 03:20:59