topic_model.cpp
Go to the documentation of this file.
1 // Qt table model for rosbag_fancy messages
2 // Author: Christian Lenz <lenz@ais.uni-bonn.de>
3 
4 #include "topic_model.h"
5 
6 #include <QColor>
7 #include <QTimer>
8 #include <rosfmt/rosfmt.h>
9 
10 namespace rqt_rosbag_fancy
11 {
12 
13 TopicModel::TopicModel(QObject* parent)
14  : QAbstractTableModel(parent)
15 {
16  m_timer = new QTimer(this);
17  m_timer->setSingleShot(true);
18  m_timer->setInterval(3000);
19 
20  connect(m_timer, &QTimer::timeout, this, &TopicModel::clear);
21 }
22 
24 {
25 }
26 
28 {
29  m_valid = false;
30 
31  dataChanged(
32  index(0,0),
33  index(m_status->topics.size()-1, static_cast<int>(Column::ColumnCount)-1)
34  );
35 }
36 
37 int TopicModel::columnCount(const QModelIndex& parent) const
38 {
39  if(parent.isValid())
40  return 0;
41 
42  return static_cast<int>(Column::ColumnCount);
43 }
44 
45 int TopicModel::rowCount(const QModelIndex& parent) const
46 {
47  if(parent.isValid())
48  return 0;
49 
50  if(!m_status)
51  return 0;
52 
53  return m_status->topics.size();
54 }
55 
56 QVariant TopicModel::data(const QModelIndex& index, int role) const
57 {
58  if(!m_status)
59  return 0;
60 
61  if(index.parent().isValid())
62  return QVariant();
63 
64  int column = index.column();
65  if(column < 0 || column >= static_cast<int>(Column::ColumnCount))
66  return QVariant();
67 
68  Column col = static_cast<Column>(column);
69 
70  int row = index.row();
71  if(row < 0 || row >= (int)m_status->topics.size())
72  return QVariant();
73 
74  const auto& topic = m_status->topics[row];
75 
76  bool active = topic.messages > m_lastMsgCount[row];
77 
78  switch(role)
79  {
80  case Qt::ForegroundRole:
81  if(m_valid)
82  {
83  if(topic.publishers < 1 && col == Column::Publisher)
84  return QColor(Qt::white);
85  else
86  return QVariant{};
87  }
88  else
89  return QVariant{};
90 
91  break;
92 
93  case Qt::BackgroundRole:
94  if(m_valid)
95  {
96  if(active && col == Column::Activity && m_status->status == rosbag_fancy_msgs::Status::STATUS_RUNNING)
97  return QColor(Qt::green);
98  else if(topic.publishers < 1 && col == Column::Publisher)
99  return QColor(Qt::red);
100  else
101  return QVariant{};
102  }
103  else
104  return QColor(Qt::gray);
105 
106  break;
107 
108  case Qt::DisplayRole:
109  switch(col)
110  {
111  case Column::Activity:
112  return QString("");
113  case Column::Name:
114  return QString::fromStdString(topic.name);
115  case Column::Publisher:
116  return QString::number(topic.publishers);
117  case Column::Messages:
118  return QString::number(topic.messages_in_current_bag);
119  case Column::Rate:
120  return rateToString(topic.rate);
121  case Column::Bytes:
122  return memoryToString(topic.bytes);
123  case Column::Bandwidth:
124  return memoryToString(topic.bandwidth) + "/s";
125  default:
126  return QVariant();
127  }
128  break;
129 
130  case Qt::TextAlignmentRole:
131  switch(col)
132  {
133  case Column::Name:
134  return int(Qt::AlignLeft | Qt::AlignVCenter);
135 
136  default:
137  return int(Qt::AlignRight | Qt::AlignVCenter);
138  }
139  break;
140  }
141 
142  return QVariant();
143 }
144 
145 QVariant TopicModel::headerData(int section, Qt::Orientation orientation, int role) const
146 {
147  if(role != Qt::DisplayRole || orientation != Qt::Horizontal)
148  return QVariant();
149 
150  if(section < 0 || section > static_cast<int>(Column::ColumnCount))
151  return QVariant();
152 
153  Column col = static_cast<Column>(section);
154 
155  switch(col)
156  {
157  case Column::Activity:
158  return "Act";
159  case Column::Name:
160  return "Name";
161  case Column::Publisher:
162  return "Publisher";
163  case Column::Messages:
164  return "Messages";
165  case Column::Rate:
166  return "Rate";
167  case Column::Bytes:
168  return "Bytes";
169  case Column::Bandwidth:
170  return "Bandwidth";
171  default:
172  return QVariant();
173  }
174 }
175 
176 void TopicModel::setState(const rosbag_fancy_msgs::StatusConstPtr& state)
177 {
178  if(!m_status || m_status->topics.size() != state->topics.size())
179  {
180  m_lastMsgCount.clear();
181  m_lastMsgCount.reserve(state->topics.size());
182 
183  for(auto& t : state->topics)
184  m_lastMsgCount.push_back(t.messages);
185 
186  beginResetModel();
187  m_status = state;
188  endResetModel();
189 
190  return;
191  }
192 
193  for(unsigned int i=0;i<m_status->topics.size();i++)
194  m_lastMsgCount[i] = m_status->topics[i].messages;
195 
196  m_status = state;
197  m_valid = true;
198  dataChanged(
199  index(0,0),
200  index(m_status->topics.size()-1, static_cast<int>(Column::ColumnCount)-1)
201  );
202 
203  m_timer->start();
204 }
205 
206 QString TopicModel::rateToString(double rate) const
207 {
208  std::string s;
209  if(rate < 1000.0)
210  s = fmt::format("{:.1f} Hz", rate);
211  else if(rate < 1e6)
212  s = fmt::format("{:.1f} kHz", rate / 1e3);
213  else
214  s = fmt::format("{:.1f} MHz", rate / 1e6);
215 
216  return QString::fromStdString(s);
217 }
218 
219 QString TopicModel::memoryToString(uint64_t memory) const
220 {
221  std::string s;
222  if(memory < static_cast<uint64_t>(1<<10))
223  s = fmt::format("{}.0 B", memory);
224  else if(memory < static_cast<uint64_t>(1<<20))
225  s = fmt::format("{:.1f} KiB", static_cast<double>(memory) / static_cast<uint64_t>(1<<10));
226  else if(memory < static_cast<uint64_t>(1<<30))
227  s = fmt::format("{:.1f} MiB", static_cast<double>(memory) / static_cast<uint64_t>(1<<20));
228  else if(memory < static_cast<uint64_t>(1ull<<40))
229  s = fmt::format("{:.1f} GiB", static_cast<double>(memory) / static_cast<uint64_t>(1ull<<30));
230  else
231  s = fmt::format("{:.1f} TiB", static_cast<double>(memory) / static_cast<uint64_t>(1ull<<40));
232 
233  return QString::fromStdString(s);
234 }
235 
236 }
rosfmt.h
rqt_rosbag_fancy::TopicModel::Column::Bandwidth
@ Bandwidth
rqt_rosbag_fancy::TopicModel::rateToString
QString rateToString(double rate) const
Definition: topic_model.cpp:206
rqt_rosbag_fancy::TopicModel::Column::Activity
@ Activity
rqt_rosbag_fancy::TopicModel::Column::ColumnCount
@ ColumnCount
rqt_rosbag_fancy::TopicModel::m_timer
QTimer * m_timer
Definition: topic_model.h:51
rqt_rosbag_fancy::TopicModel::columnCount
int columnCount(const QModelIndex &parent) const override
Definition: topic_model.cpp:37
s
XmlRpcServer s
rqt_rosbag_fancy::TopicModel::Column
Column
Definition: topic_model.h:20
rqt_rosbag_fancy::TopicModel::rowCount
int rowCount(const QModelIndex &parent) const override
Definition: topic_model.cpp:45
rqt_rosbag_fancy::TopicModel::data
QVariant data(const QModelIndex &index, int role) const override
Definition: topic_model.cpp:56
rqt_rosbag_fancy::TopicModel::TopicModel
TopicModel(QObject *parent=0)
Definition: topic_model.cpp:13
rqt_rosbag_fancy::TopicModel::setState
void setState(const rosbag_fancy_msgs::StatusConstPtr &status)
Definition: topic_model.cpp:176
topic_model.h
rqt_rosbag_fancy::TopicModel::clear
void clear()
Definition: topic_model.cpp:27
rqt_rosbag_fancy::TopicModel::m_lastMsgCount
std::vector< unsigned int > m_lastMsgCount
Definition: topic_model.h:56
rqt_rosbag_fancy::TopicModel::memoryToString
QString memoryToString(uint64_t memory) const
Definition: topic_model.cpp:219
rqt_rosbag_fancy::TopicModel::Column::Name
@ Name
rqt_rosbag_fancy::TopicModel::m_status
rosbag_fancy_msgs::StatusConstPtr m_status
Definition: topic_model.h:49
rqt_rosbag_fancy::TopicModel::Column::Bytes
@ Bytes
rqt_rosbag_fancy::TopicModel::Column::Publisher
@ Publisher
rqt_rosbag_fancy::TopicModel::headerData
QVariant headerData(int section, Qt::Orientation orientation, int role) const override
Definition: topic_model.cpp:145
rqt_rosbag_fancy::TopicModel::Column::Rate
@ Rate
rqt_rosbag_fancy::TopicModel::m_valid
bool m_valid
Definition: topic_model.h:50
rqt_rosbag_fancy::TopicModel::~TopicModel
virtual ~TopicModel()
Definition: topic_model.cpp:23
rqt_rosbag_fancy
Definition: fancy_gui.cpp:20
rqt_rosbag_fancy::TopicModel::Column::Messages
@ Messages


rqt_rosbag_fancy
Author(s): Christian Lenz
autogenerated on Tue Feb 20 2024 03:21:03