12 Q_DECLARE_METATYPE(rosmon_msgs::StateConstPtr)
18 : QAbstractTableModel(parent)
20 , m_namespace(
"/rosmon")
22 qRegisterMetaType<rosmon_msgs::StateConstPtr>();
23 connect(
this, SIGNAL(
stateReceived(rosmon_msgs::StateConstPtr)),
42 ROS_WARN(
"Got invalid name '%s'", qPrintable(ns));
61 std::vector<bool> covered(
m_entries.size(),
false);
64 for(
const auto& nodeState : state->nodes)
67 key.
name = QString::fromStdString(nodeState.name);
68 key.
ns = QString::fromStdString(nodeState.ns);
69 key.
state = nodeState.state;
71 key.
load = nodeState.system_load + nodeState.user_load;
72 key.
memory = nodeState.memory;
77 if(it ==
m_entries.end() || !((it->name == key.
name) && (it->ns == key.
ns)))
79 beginInsertRows(QModelIndex(), row, row);
81 covered.insert(covered.begin() + row,
true);
88 dataChanged(index(row, 0), index(row,
COL_COUNT));
94 std::size_t covIdx = 0;
102 beginRemoveRows(QModelIndex(), row, row);
134 if(index.row() < 0 || index.row() >= (int)
m_entries.size())
141 case Qt::DisplayRole:
142 switch(index.column())
149 return QString::number(entry.
load,
'f', 2);
157 switch(index.column())
160 return (uint)entry.
memory;
163 case Qt::TextAlignmentRole:
164 switch(index.column())
173 return int(Qt::AlignRight | Qt::AlignVCenter);
176 case Qt::BackgroundColorRole:
179 case rosmon_msgs::NodeState::RUNNING:
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);
190 switch(index.column())
199 return static_cast<unsigned int>(entry.
memory);
211 if(role != Qt::DisplayRole || orientation != Qt::Horizontal)
212 return QAbstractTableModel::headerData(section, orientation, role);
QVariant data(const QModelIndex &index, int role) const override
ros::Subscriber m_sub_state
QString formattedDataSize(qint64 bytes, int precision)
QVariant headerData(int section, Qt::Orientation orientation, int role) const override
int columnCount(const QModelIndex &parent) const override
void setNamespace(const QString &ns)
void updateState(const rosmon_msgs::StateConstPtr &state)
std::vector< Entry > m_entries
int rowCount(const QModelIndex &parent) const override
void stateReceived(const rosmon_msgs::StateConstPtr &state)