node_model.h
Go to the documentation of this file.
1 // Qt model for nodes controlled by a rosmon instance
2 // Author: Max Schwarz <max.schwarz@uni-bonn.de>
3 
4 #ifndef NODE_MODEL_H
5 #define NODE_MODEL_H
6 
7 #include <QAbstractTableModel>
8 
9 #include <rosmon_msgs/State.h>
10 
11 #include <ros/subscriber.h>
12 #include <ros/node_handle.h>
13 
14 namespace rqt_rosmon
15 {
16 
17 class NodeModel : public QAbstractTableModel
18 {
19 Q_OBJECT
20 public:
21  enum Column
22  {
28 
30  };
31 
32  enum Role
33  {
34  SortRole = Qt::UserRole
35  };
36 
37  explicit NodeModel(ros::NodeHandle& nh, QObject* parent = nullptr);
38  ~NodeModel() override = default;
39 
40  int rowCount(const QModelIndex & parent) const override;
41  int columnCount(const QModelIndex & parent) const override;
42  QVariant data(const QModelIndex & index, int role) const override;
43 
44  QVariant headerData(int section, Qt::Orientation orientation, int role) const override;
45 
46  inline QString namespaceString() const
47  { return m_namespace; }
48 
49 public Q_SLOTS:
50  void setNamespace(const QString& ns);
51  void unsubscribe();
52 Q_SIGNALS:
53  void stateReceived(const rosmon_msgs::StateConstPtr& state);
54 private Q_SLOTS:
55  void updateState(const rosmon_msgs::StateConstPtr& state);
56 private:
57  struct Entry
58  {
59  inline bool operator<(const Entry& other) const
60  { return name < other.name; }
61 
62  QString name;
63  QString ns;
64  int state;
66  double load;
67  uint64_t memory;
68  };
69 
71 
72  QString m_namespace;
73 
74  std::vector<Entry> m_entries;
75 
77 };
78 
79 }
80 
81 #endif
rqt_rosmon::NodeModel::m_entries
std::vector< Entry > m_entries
Definition: node_model.h:74
node_handle.h
rqt_rosmon::NodeModel::namespaceString
QString namespaceString() const
Definition: node_model.h:46
rqt_rosmon::NodeModel::unsubscribe
void unsubscribe()
Definition: node_model.cpp:54
rqt_rosmon::NodeModel::COL_NAME
@ COL_NAME
Definition: node_model.h:23
rqt_rosmon::NodeModel::COL_RESTART_COUNT
@ COL_RESTART_COUNT
Definition: node_model.h:25
rqt_rosmon::NodeModel::Entry::operator<
bool operator<(const Entry &other) const
Definition: node_model.h:59
rqt_rosmon::NodeModel::COL_MEMORY
@ COL_MEMORY
Definition: node_model.h:27
rqt_rosmon::NodeModel::Entry::memory
uint64_t memory
Definition: node_model.h:67
rqt_rosmon::NodeModel::NodeModel
NodeModel(ros::NodeHandle &nh, QObject *parent=nullptr)
Definition: node_model.cpp:17
rqt_rosmon::NodeModel::stateReceived
void stateReceived(const rosmon_msgs::StateConstPtr &state)
rqt_rosmon::NodeModel::COL_COUNT
@ COL_COUNT
Definition: node_model.h:29
rqt_rosmon::NodeModel::setNamespace
void setNamespace(const QString &ns)
Definition: node_model.cpp:29
rqt_rosmon::NodeModel::headerData
QVariant headerData(int section, Qt::Orientation orientation, int role) const override
Definition: node_model.cpp:209
rqt_rosmon::NodeModel::m_nh
ros::NodeHandle m_nh
Definition: node_model.h:70
rqt_rosmon::NodeModel::Entry::state
int state
Definition: node_model.h:64
subscriber.h
rqt_rosmon::NodeModel::Role
Role
Definition: node_model.h:32
rqt_rosmon::NodeModel::COL_NAMESPACE
@ COL_NAMESPACE
Definition: node_model.h:24
rqt_rosmon::NodeModel
Definition: node_model.h:17
rqt_rosmon::NodeModel::m_namespace
QString m_namespace
Definition: node_model.h:72
rqt_rosmon::NodeModel::Column
Column
Definition: node_model.h:21
rqt_rosmon::NodeModel::Entry
Definition: node_model.h:57
rqt_rosmon::NodeModel::rowCount
int rowCount(const QModelIndex &parent) const override
Definition: node_model.cpp:113
rqt_rosmon::NodeModel::~NodeModel
~NodeModel() override=default
rqt_rosmon::NodeModel::Entry::ns
QString ns
Definition: node_model.h:63
rqt_rosmon::NodeModel::Entry::name
QString name
Definition: node_model.h:62
rqt_rosmon::NodeModel::SortRole
@ SortRole
Definition: node_model.h:34
rqt_rosmon::NodeModel::data
QVariant data(const QModelIndex &index, int role) const override
Definition: node_model.cpp:129
rqt_rosmon::NodeModel::COL_LOAD
@ COL_LOAD
Definition: node_model.h:26
rqt_rosmon::NodeModel::m_sub_state
ros::Subscriber m_sub_state
Definition: node_model.h:76
rqt_rosmon::NodeModel::updateState
void updateState(const rosmon_msgs::StateConstPtr &state)
Definition: node_model.cpp:59
rqt_rosmon
Definition: bar_delegate.cpp:8
rqt_rosmon::NodeModel::Entry::restartCount
int restartCount
Definition: node_model.h:65
ros::NodeHandle
ros::Subscriber
rqt_rosmon::NodeModel::Entry::load
double load
Definition: node_model.h:66
rqt_rosmon::NodeModel::columnCount
int columnCount(const QModelIndex &parent) const override
Definition: node_model.cpp:121


rqt_rosmon
Author(s): Max Schwarz
autogenerated on Wed Feb 21 2024 04:01:19