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 namespace rqt_rosmon
14 {
15 
16 ROSMonModel::ROSMonModel(QObject* parent)
17  : QAbstractListModel(parent)
18 {
19  m_data << "[auto]";
20 
21  auto updateTimer = new QTimer(this);
22  connect(updateTimer, SIGNAL(timeout()), SLOT(updateData()));
23  updateTimer->start(2000);
24 }
25 
26 int ROSMonModel::rowCount(const QModelIndex& parent) const
27 {
28  if(parent.isValid())
29  return 0;
30 
31  return m_data.count();
32 }
33 
34 QVariant ROSMonModel::data(const QModelIndex& index, int role) const
35 {
36  int row = index.row();
37 
38  switch(role)
39  {
40  case Qt::DisplayRole:
41  case Qt::EditRole:
42  return m_data[row];
43  }
44 
45  return QVariant();
46 }
47 
49 {
50  std::vector<ros::master::TopicInfo> topics;
51  if(!ros::master::getTopics(topics))
52  return;
53 
54  QStringList nodeList;
55 
56  for(auto& topic : topics)
57  {
59  continue;
60 
61  nodeList << QString::fromStdString(ros::names::parentNamespace(topic.name));
62  }
63 
64  qSort(nodeList);
65 
66  nodeList.prepend("[auto]");
67 
68  int oldIdx = 1;
69  int newIdx = 1;
70 
71  while(oldIdx < m_data.size() || newIdx < nodeList.size())
72  {
73  if(oldIdx == m_data.size())
74  {
75  beginInsertRows(QModelIndex(), oldIdx, oldIdx);
76  m_data.append(nodeList[newIdx]);
77  endInsertRows();
78  oldIdx += 1;
79  newIdx += 1;
80  continue;
81  }
82 
83  if(newIdx == nodeList.size())
84  {
85  beginRemoveRows(QModelIndex(), oldIdx, oldIdx);
86  m_data.erase(m_data.begin() + oldIdx);
87  endRemoveRows();
88  continue;
89  }
90 
91  auto oldT = m_data[oldIdx];
92  auto newT = nodeList[newIdx];
93 
94  if(oldT == newT)
95  {
96  oldIdx++;
97  newIdx++;
98  }
99  else if(oldT < newT)
100  {
101  beginRemoveRows(QModelIndex(), oldIdx, oldIdx);
102  m_data.erase(m_data.begin() + oldIdx);
103  endRemoveRows();
104  }
105  else
106  {
107  beginInsertRows(QModelIndex(), oldIdx, oldIdx);
108  m_data.insert(oldIdx, newT);
109  endInsertRows();
110  oldIdx++;
111  newIdx++;
112  }
113  }
114 }
115 
116 }
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 Wed Jul 10 2019 03:10:15