node_model.cpp
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 #include "node_model.h"
5 
6 #include <QColor>
7 
8 #include <ros/node_handle.h>
9 
10 #include "format_data_size.h"
11 
12 Q_DECLARE_METATYPE(rosmon_msgs::StateConstPtr)
13 
14 namespace rqt_rosmon
15 {
16 
17 NodeModel::NodeModel(ros::NodeHandle& nh, QObject* parent)
18  : QAbstractTableModel(parent)
19  , m_nh(nh)
20  , m_namespace("/rosmon")
21 {
22  qRegisterMetaType<rosmon_msgs::StateConstPtr>();
23  connect(this, SIGNAL(stateReceived(rosmon_msgs::StateConstPtr)),
24  SLOT(updateState(rosmon_msgs::StateConstPtr)),
25  Qt::QueuedConnection
26  );
27 }
28 
29 void NodeModel::setNamespace(const QString& ns)
30 {
31  m_namespace = ns;
32 
33  if(!ns.isEmpty())
34  {
35  try
36  {
37  ros::NodeHandle nh(m_nh, ns.toStdString());
38  m_sub_state = nh.subscribe("state", 1, &NodeModel::stateReceived, this);
39  }
40  catch(ros::InvalidNameException& name)
41  {
42  ROS_WARN("Got invalid name '%s'", qPrintable(ns));
44  }
45  }
46  else
48 
49  beginResetModel();
50  m_entries.clear();
51  endResetModel();
52 }
53 
55 {
57 }
58 
59 void NodeModel::updateState(const rosmon_msgs::StateConstPtr& state)
60 {
61  std::vector<bool> covered(m_entries.size(), false);
62 
63  // Look for changed & new rows
64  for(const auto& nodeState : state->nodes)
65  {
66  Entry key;
67  key.name = QString::fromStdString(nodeState.name);
68  key.ns = QString::fromStdString(nodeState.ns);
69  key.state = nodeState.state;
70  key.restartCount = nodeState.restart_count;
71  key.load = nodeState.system_load + nodeState.user_load;
72  key.memory = nodeState.memory;
73 
74  auto it = std::lower_bound(m_entries.begin(), m_entries.end(), key);
75  int row = it - m_entries.begin();
76 
77  if(it == m_entries.end() || !((it->name == key.name) && (it->ns == key.ns)))
78  {
79  beginInsertRows(QModelIndex(), row, row);
80  m_entries.insert(it, key);
81  covered.insert(covered.begin() + row, true);
82  endInsertRows();
83  }
84  else
85  {
86  *it = key;
87  covered[row] = true;
88  dataChanged(index(row, 0), index(row, COL_COUNT-1));
89  }
90  }
91 
92  // Look for deleted rows
93  auto it = m_entries.begin();
94  std::size_t covIdx = 0;
95 
96  while(it != m_entries.end())
97  {
98  int row = it - m_entries.begin();
99 
100  if(!covered[covIdx])
101  {
102  beginRemoveRows(QModelIndex(), row, row);
103  it = m_entries.erase(it);
104  endRemoveRows();
105  }
106  else
107  ++it;
108 
109  ++covIdx;
110  }
111 }
112 
113 int NodeModel::rowCount(const QModelIndex& parent) const
114 {
115  if(parent.isValid())
116  return 0;
117 
118  return m_entries.size();
119 }
120 
121 int NodeModel::columnCount(const QModelIndex& parent) const
122 {
123  if(parent.isValid())
124  return 0;
125 
126  return COL_COUNT;
127 }
128 
129 QVariant NodeModel::data(const QModelIndex& index, int role) const
130 {
131  if(!index.isValid())
132  return QVariant();
133 
134  if(index.row() < 0 || index.row() >= (int)m_entries.size())
135  return QVariant();
136 
137  const Entry& entry = m_entries[index.row()];
138 
139  switch(role)
140  {
141  case Qt::DisplayRole:
142  switch(index.column())
143  {
144  case COL_NAME:
145  return entry.name;
146  case COL_NAMESPACE:
147  return entry.ns;
148  case COL_LOAD:
149  return QString::number(entry.load, 'f', 2);
150  case COL_MEMORY:
151  return formattedDataSize(entry.memory, 2);
152  case COL_RESTART_COUNT:
153  return entry.restartCount;
154  }
155  break;
156  case Qt::EditRole:
157  switch(index.column())
158  {
159  case COL_MEMORY:
160  return (uint)entry.memory;
161  }
162  break;
163  case Qt::TextAlignmentRole:
164  switch(index.column())
165  {
166  case COL_NAME:
167  return QVariant();
168  case COL_NAMESPACE:
169  return QVariant();
170  case COL_RESTART_COUNT:
171  case COL_LOAD:
172  case COL_MEMORY:
173  return int(Qt::AlignRight | Qt::AlignVCenter);
174  }
175  break;
176  case Qt::BackgroundColorRole:
177  switch(entry.state)
178  {
179  case rosmon_msgs::NodeState::RUNNING:
180  return QVariant();
181  case rosmon_msgs::NodeState::IDLE:
182  return QColor(200, 200, 200);
183  case rosmon_msgs::NodeState::CRASHED:
184  return QColor(255, 100, 100);
185  case rosmon_msgs::NodeState::WAITING:
186  return QColor(255, 255, 128);
187  }
188  break;
189  case SortRole:
190  switch(index.column())
191  {
192  case COL_NAME:
193  return entry.name;
194  case COL_NAMESPACE:
195  return entry.ns;
196  case COL_LOAD:
197  return entry.load;
198  case COL_MEMORY:
199  return static_cast<unsigned int>(entry.memory);
200  case COL_RESTART_COUNT:
201  return entry.restartCount;
202  }
203  break;
204  }
205 
206  return QVariant();
207 }
208 
209 QVariant NodeModel::headerData(int section, Qt::Orientation orientation, int role) const
210 {
211  if(role != Qt::DisplayRole || orientation != Qt::Horizontal)
212  return QAbstractTableModel::headerData(section, orientation, role);
213 
214  switch(section)
215  {
216  case COL_NAME: return "Node";
217  case COL_NAMESPACE: return "Namespace";
218  case COL_LOAD: return "CPU Load";
219  case COL_MEMORY: return "Memory";
220  case COL_RESTART_COUNT: return "#Restarts";
221  }
222 
223  return QVariant();
224 }
225 
226 }
227 
QVariant data(const QModelIndex &index, int role) const override
Definition: node_model.cpp:129
ros::Subscriber m_sub_state
Definition: node_model.h:76
#define ROS_WARN(...)
ros::NodeHandle m_nh
Definition: node_model.h:70
QString formattedDataSize(qint64 bytes, int precision)
QVariant headerData(int section, Qt::Orientation orientation, int role) const override
Definition: node_model.cpp:209
int columnCount(const QModelIndex &parent) const override
Definition: node_model.cpp:121
void setNamespace(const QString &ns)
Definition: node_model.cpp:29
void updateState(const rosmon_msgs::StateConstPtr &state)
Definition: node_model.cpp:59
std::vector< Entry > m_entries
Definition: node_model.h:74
int rowCount(const QModelIndex &parent) const override
Definition: node_model.cpp:113
void stateReceived(const rosmon_msgs::StateConstPtr &state)


rqt_rosmon
Author(s): Max Schwarz
autogenerated on Sat Jan 9 2021 03:35:46