8 #include <fmt/format.h>
9 #include <fmt/chrono.h>
18 unsigned int g_statusLines = 2;
19 std::string g_windowTitle;
23 for(
unsigned int i = 0; i < g_statusLines+1; ++i)
29 term.setCursorVisible();
37 if(memory <
static_cast<uint64_t
>(1<<10))
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));
46 return fmt::format(
"{:.1f} TiB",
static_cast<double>(memory) /
static_cast<uint64_t
>(1ull<<40));
49 std::string rateToString(
double rate)
65 Column(
const std::string&
label,
unsigned int width = 0,
const std::string&
format = {})
69 this->
width = label.size();
81 TableWriter(Terminal& term,
const std::array<Column, Columns>& columns)
98 fmt::print(
format, col.label);
116 for(
unsigned int i = 0; i < col.width; ++i)
133 void printColumn(
const T& value, uint32_t color = 0)
139 m_term.setForegroundColor(color);
144 m_term.setStandardColors();
158 : m_topicManager{config}
160 , m_bagWriter{writer}
162 std::atexit(&cleanup);
170 g_statusLines = m_topicManager.topics().size();
176 template<
class... Args>
187 unsigned int cnt = 0;
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;
201 unsigned int maxTopicWidth = 0;
203 maxTopicWidth = std::max<unsigned int>(maxTopicWidth, topic.name.length());
205 TableWriter<6> writer{
m_term, {{
207 {
"Topic", maxTopicWidth},
214 writer.printHeader();
222 float messageRate = topic.messageRateAt(now);
229 totalActivity =
true;
230 writer.printColumn(
" ▮ ", 0x00FF00);
233 writer.printColumn(
"");
235 writer.printColumn(topic.name);
236 writer.printColumn(topic.numPublishers, topic.numPublishers == 0 ? 0x0000FF : 0);
238 uint32_t messageColor = (topic.totalMessages == 0) ? 0x0000FF : 0;
240 uint64_t messageCount = topic.id < counts.size() ? counts[topic.id] : 0;
241 uint64_t byteCount = topic.id < bytes.size() ? bytes[topic.id] : 0;
243 writer.printColumn(
fmt::format(
"{:10} ({:>8})", messageCount, rateToString(messageRate)), messageColor);
246 writer.printColumn(topic.dropCounter, topic.dropCounter > 0 ? 0x0000FF : 0);
251 totalMessages += messageCount;
252 totalBytes += byteCount;
253 totalRate += messageRate;
254 totalBandwidth += topic.bandwidth;
255 totalDrops += topic.dropCounter;
264 writer.printColumn(
" ▮ ", 0x00FF00);
266 writer.printColumn(
"");
267 writer.printColumn(
"All");
268 writer.printColumn(
"");
269 writer.printColumn(
fmt::format(
"{:10} ({:>8})", totalMessages, rateToString(totalRate)));
271 writer.printColumn(totalDrops, totalDrops > 0 ? 0x0000FF : 0);
291 printLine(cnt,
"Compression: {:>10}", [&](){
294 case rosbag::compression::Uncompressed: return
"None";
295 case rosbag::compression::BZ2: return
"BZ2";
296 case rosbag::compression::LZ4: return
"LZ4";
304 printLine(cnt,
"Bag size: {:>10} / {:>10} split size / {:>10} available",
312 printLine(cnt,
"Bag size: {:>10} / {:>10} available",
320 printLine(cnt,
"Directory size: {:>10} / {:>10}",
347 : m_topicManager{topics}
348 , m_startTime{startTime}
351 std::atexit(&cleanup);
359 g_statusLines = m_topicManager.topics().size();
365 template<
class... Args>
376 unsigned int cnt = 0;
383 float totalRate = 0.0f;
384 float totalBandwidth = 0.0f;
385 bool totalActivity =
false;
386 unsigned int totalDrops = 0;
388 unsigned int maxTopicWidth = 0;
390 maxTopicWidth = std::max<unsigned int>(maxTopicWidth, topic.name.length());
392 TableWriter<4> writer{
m_term, {{
394 {
"Topic", maxTopicWidth},
399 writer.printHeader();
404 float messageRate = topic.messageRateAt(now);
411 totalActivity =
true;
412 writer.printColumn(
" ▮ ", 0x00FF00);
415 writer.printColumn(
"");
417 writer.printColumn(topic.name);
419 uint32_t messageColor = (topic.totalMessages == 0) ? 0x0000FF : 0;
421 writer.printColumn(
fmt::format(
"{:>8}", rateToString(messageRate)), messageColor);
427 totalRate += messageRate;
428 totalBandwidth += topic.bandwidth;
429 totalDrops += topic.dropCounter;
438 writer.printColumn(
" ▮ ", 0x00FF00);
440 writer.printColumn(
"");
441 writer.printColumn(
"All");
442 writer.printColumn(
fmt::format(
"{:>8}", rateToString(totalRate)));
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()));
457 std::chrono::seconds startTimeS = std::chrono::duration_cast<std::chrono::seconds>(startTimeC.time_since_epoch());
458 std::time_t startTimeSC(startTimeS.count());
460 std::tm startTimeBUTC;
461 localtime_r(&startTimeSC, &startTimeB);
462 gmtime_r(&startTimeSC, &startTimeBUTC);
464 std::chrono::seconds endTimeS = std::chrono::duration_cast<std::chrono::seconds>(endTimeC.time_since_epoch());
465 std::time_t endTimeSC(endTimeS.count());
468 localtime_r(&endTimeSC, &endTimeB);
469 gmtime_r(&endTimeSC, &endTimeBUTC);
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(¤tTimeSC, ¤tTimeB);
476 gmtime_r(¤tTimeSC, ¤tTimeBUTC);
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);
500 for(
int i = 0; i < pos / 8; ++i)
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;
514 for(
int i = 0; i < w - pos/8 - 1; ++i)
532 fmt::print(
"[space]");
535 fmt::print(
" for pause, ");
539 fmt::print(
"[left]");
546 fmt::print(
"[right]");
549 fmt::print(
" for seeking\n");