topic_model.h
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 #ifndef TOPIC_MODEL_H
5 #define TOPIC_MODEL_H
6 
7 #include <QAbstractTableModel>
8 
9 #include <rosbag_fancy_msgs/Status.h>
10 
11 class QTimer;
12 
13 namespace rqt_rosbag_fancy
14 {
15 
16 class TopicModel : public QAbstractTableModel
17 {
18 Q_OBJECT
19 public:
20  enum class Column
21  {
22  Activity,
23  Name,
24  Publisher,
25  Messages,
26  Rate,
27  Bytes,
28  Bandwidth,
29 
31  };
32 
33  explicit TopicModel(QObject* parent = 0);
34  virtual ~TopicModel();
35 
36  int columnCount(const QModelIndex& parent) const override;
37  int rowCount(const QModelIndex& parent) const override;
38 
39  QVariant data(const QModelIndex& index, int role) const override;
40  QVariant headerData(int section, Qt::Orientation orientation, int role) const override;
41 
42 public Q_SLOTS:
43  void setState(const rosbag_fancy_msgs::StatusConstPtr& status);
44 
45 private Q_SLOTS:
46  void clear();
47 
48 private:
49  rosbag_fancy_msgs::StatusConstPtr m_status;
50  bool m_valid = false;
51  QTimer* m_timer;
52 
53  QString rateToString(double rate) const;
54  QString memoryToString(uint64_t memory) const;
55 
56  std::vector<unsigned int> m_lastMsgCount;
57 };
58 
59 }
60 
61 #endif
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
rqt_rosbag_fancy::TopicModel
Definition: topic_model.h:16
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
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