6 #if HAVE_PLUGINLIB_NEW_HEADERS 13 #include <QMessageBox> 16 #include <QSortFilterProxyModel> 18 #include <rosmon_msgs/StartStop.h> 39 #if QT_VERSION_MAJOR >= 5 40 m_ui.nodeBox->setCurrentText(
"[auto]");
42 m_ui.nodeBox->setEditText(
"[auto]");
45 connect(
m_ui.nodeBox, SIGNAL(editTextChanged(QString)),
49 auto sortFilterProxy =
new QSortFilterProxyModel(
this);
50 sortFilterProxy->setSourceModel(
m_model);
51 sortFilterProxy->setDynamicSortFilter(
true);
53 m_ui.tableView->setModel(sortFilterProxy);
55 m_ui.tableView->setSortingEnabled(
true);
56 m_ui.tableView->setSelectionBehavior(QAbstractItemView::SelectRows);
57 m_ui.tableView->setSelectionMode(QAbstractItemView::ExtendedSelection);
58 m_ui.tableView->setContextMenuPolicy(Qt::CustomContextMenu);
63 int numCores = std::thread::hardware_concurrency();
67 loadDelegate->setRange(0.0, numCores);
77 long int av_pages = sysconf(_SC_PHYS_PAGES);
78 long int page_size = sysconf(_SC_PAGESIZE);
79 int64_t availableMemory = av_pages * page_size;
80 if(availableMemory < 0)
83 memDelegate->setRange(0.0, availableMemory);
89 connect(
m_ui.tableView, SIGNAL(customContextMenuRequested(QPoint)),
92 connect(
m_model, SIGNAL(stateReceived(rosmon_msgs::StateConstPtr)),
93 m_ui.tableView, SLOT(resizeRowsToContents())
111 if(instanceSettings.
contains(
"namespace"))
113 QString ns = instanceSettings.
value(
"namespace").toString();
114 m_ui.nodeBox->setEditText(ns);
118 if(instanceSettings.
contains(
"viewState"))
119 m_ui.tableView->horizontalHeader()->restoreState(instanceSettings.
value(
"viewState").toByteArray());
124 instanceSettings.
setValue(
"namespace",
m_ui.nodeBox->currentText());
125 instanceSettings.
setValue(
"viewState",
m_ui.tableView->horizontalHeader()->saveState());
130 QModelIndex index =
m_ui.tableView->indexAt(point);
135 QMenu menu(
m_ui.tableView);
137 QAction* startAction = menu.addAction(
"Start");
138 startAction->setProperty(
"action", rosmon_msgs::StartStopRequest::START);
140 QAction* stopAction = menu.addAction(
"Stop");
141 stopAction->setProperty(
"action", rosmon_msgs::StartStopRequest::STOP);
143 QAction* restartAction = menu.addAction(
"Restart");
144 restartAction->setProperty(
"action", rosmon_msgs::StartStopRequest::RESTART);
146 QAction* triggered = menu.exec(
m_ui.tableView->viewport()->mapToGlobal(point));
150 rosmon_msgs::StartStop srv;
151 srv.request.node = index.sibling(index.row(),
NodeModel::COL_NAME).data().toString().toStdString();
153 srv.request.action = triggered->property(
"action").toInt();
156 QMessageBox::critical(
m_w,
"Failure",
"Could not call start_stop service");
void setNamespace(const QString &ns)
void initPlugin(qt_gui_cpp::PluginContext &ctx) override
void shutdownPlugin() override
bool call(const std::string &service_name, MReq &req, MRes &res)
QVariant data(const QModelIndex &index, int role) const override
QVariant value(const QString &key, const QVariant &defaultValue=QVariant()) const
void addWidget(QWidget *widget)
bool contains(const QString &key) const
void showContextMenu(const QPoint &point)
void setValue(const QString &key, const QVariant &value)
void restoreSettings(const qt_gui_cpp::Settings &pluginSettings, const qt_gui_cpp::Settings &instanceSettings) override
ros::NodeHandle & getNodeHandle() const
void setNamespace(const QString &ns)
int rowCount(const QModelIndex &parent) const override
ROSMonModel * m_rosmonModel
QString namespaceString() const
void saveSettings(qt_gui_cpp::Settings &pluginSettings, qt_gui_cpp::Settings &instanceSettings) const override
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)