rosmon_model.cpp
Go to the documentation of this file.
1 // List of all rosmon instances on the server
2 // Author: Max Schwarz <max.schwarz@uni-bonn.de>
3 
4 #include "rosmon_model.h"
5 
6 #include <QTimer>
7 
8 #include <rosmon_msgs/State.h>
9 
10 #include <ros/master.h>
11 #include <ros/names.h>
12 
13 #include <algorithm>
14 
15 namespace rqt_rosmon
16 {
17 
18 ROSMonModel::ROSMonModel(QObject* parent)
19  : QAbstractListModel(parent)
20 {
21  m_data << "[auto]";
22 
23  auto updateTimer = new QTimer(this);
24  connect(updateTimer, SIGNAL(timeout()), SLOT(updateData()));
25  updateTimer->start(2000);
26 }
27 
28 int ROSMonModel::rowCount(const QModelIndex& parent) const
29 {
30  if(parent.isValid())
31  return 0;
32 
33  return m_data.count();
34 }
35 
36 QVariant ROSMonModel::data(const QModelIndex& index, int role) const
37 {
38  int row = index.row();
39 
40  switch(role)
41  {
42  case Qt::DisplayRole:
43  case Qt::EditRole:
44  return m_data[row];
45  }
46 
47  return QVariant();
48 }
49 
51 {
52  std::vector<ros::master::TopicInfo> topics;
53  if(!ros::master::getTopics(topics))
54  return;
55 
56  QStringList nodeList;
57 
58  for(auto& topic : topics)
59  {
61  continue;
62 
63  nodeList << QString::fromStdString(ros::names::parentNamespace(topic.name));
64  }
65 
66  std::sort(nodeList.begin(), nodeList.end());
67 
68  nodeList.prepend("[auto]");
69 
70  int oldIdx = 1;
71  int newIdx = 1;
72 
73  while(oldIdx < m_data.size() || newIdx < nodeList.size())
74  {
75  if(oldIdx == m_data.size())
76  {
77  beginInsertRows(QModelIndex(), oldIdx, oldIdx);
78  m_data.append(nodeList[newIdx]);
79  endInsertRows();
80  oldIdx += 1;
81  newIdx += 1;
82  continue;
83  }
84 
85  if(newIdx == nodeList.size())
86  {
87  beginRemoveRows(QModelIndex(), oldIdx, oldIdx);
88  m_data.erase(m_data.begin() + oldIdx);
89  endRemoveRows();
90  continue;
91  }
92 
93  auto oldT = m_data[oldIdx];
94  auto newT = nodeList[newIdx];
95 
96  if(oldT == newT)
97  {
98  oldIdx++;
99  newIdx++;
100  }
101  else if(oldT < newT)
102  {
103  beginRemoveRows(QModelIndex(), oldIdx, oldIdx);
104  m_data.erase(m_data.begin() + oldIdx);
105  endRemoveRows();
106  }
107  else
108  {
109  beginInsertRows(QModelIndex(), oldIdx, oldIdx);
110  m_data.insert(oldIdx, newT);
111  endInsertRows();
112  oldIdx++;
113  newIdx++;
114  }
115  }
116 }
117 
118 }
ROSCPP_DECL std::string parentNamespace(const std::string &name)
QVariant data(const QModelIndex &index, int role) const override
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
ROSMonModel(QObject *parent=nullptr)
int rowCount(const QModelIndex &parent) const override


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