mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
ui tuning
- TabWidget for Task Tree, Settings, ... - adjust width of columns in task tree - right-align numbers - some icons
This commit is contained in:
parent
3faea3b63a
commit
1f7184b755
@ -28,6 +28,7 @@ endif()
|
||||
|
||||
set(CMAKE_INCLUDE_CURRENT_DIR ON)
|
||||
set(CMAKE_AUTOMOC ON)
|
||||
set(CMAKE_AUTORCC ON)
|
||||
add_definitions(-DQT_NO_KEYWORDS)
|
||||
|
||||
catkin_package(
|
||||
|
||||
@ -15,6 +15,7 @@ add_library(${MOVEIT_LIB_NAME}
|
||||
factory_model.cpp
|
||||
plugin_init.cpp
|
||||
${UIC_FILES}
|
||||
resources.qrc
|
||||
)
|
||||
set_target_properties(${MOVEIT_LIB_NAME} PROPERTIES VERSION ${${PROJECT_NAME}_VERSION})
|
||||
target_link_libraries(${MOVEIT_LIB_NAME}
|
||||
|
||||
BIN
visualization/motion_planning_tasks/src/icons/add.png
Normal file
BIN
visualization/motion_planning_tasks/src/icons/add.png
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 321 B |
BIN
visualization/motion_planning_tasks/src/icons/failed.png
Normal file
BIN
visualization/motion_planning_tasks/src/icons/failed.png
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 788 B |
BIN
visualization/motion_planning_tasks/src/icons/new-stage.png
Normal file
BIN
visualization/motion_planning_tasks/src/icons/new-stage.png
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 416 B |
BIN
visualization/motion_planning_tasks/src/icons/settings.png
Normal file
BIN
visualization/motion_planning_tasks/src/icons/settings.png
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 420 B |
BIN
visualization/motion_planning_tasks/src/icons/success.png
Normal file
BIN
visualization/motion_planning_tasks/src/icons/success.png
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 595 B |
BIN
visualization/motion_planning_tasks/src/icons/tasks.png
Normal file
BIN
visualization/motion_planning_tasks/src/icons/tasks.png
Normal file
Binary file not shown.
|
After Width: | Height: | Size: 645 B |
@ -80,6 +80,7 @@ LocalTaskModel::LocalTaskModel(QObject *parent)
|
||||
, Task()
|
||||
{
|
||||
root_ = pimpl();
|
||||
flags_ |= LOCAL_MODEL;
|
||||
}
|
||||
|
||||
LocalTaskModel::LocalTaskModel(Stage::pointer &&container, QObject *parent)
|
||||
@ -151,7 +152,7 @@ QVariant LocalTaskModel::data(const QModelIndex &index, int role) const
|
||||
}
|
||||
break;
|
||||
}
|
||||
return QVariant();
|
||||
return BaseTaskModel::data(index, role);
|
||||
}
|
||||
|
||||
bool LocalTaskModel::setData(const QModelIndex &index, const QVariant &value, int role)
|
||||
@ -219,4 +220,16 @@ bool LocalTaskModel::dropMimeData(const QMimeData *mime, Qt::DropAction action,
|
||||
return true;
|
||||
}
|
||||
|
||||
QAbstractItemModel *LocalTaskModel::getSolutionModel(const QModelIndex &index)
|
||||
{
|
||||
// TODO implement
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
DisplaySolutionPtr LocalTaskModel::getSolution(const QModelIndex &index)
|
||||
{
|
||||
// TODO implement
|
||||
return DisplaySolutionPtr();
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@ -70,6 +70,9 @@ public:
|
||||
/// providing a StageFactory makes the model accepting drops
|
||||
void setStageFactory(const StageFactoryPtr &factory);
|
||||
bool dropMimeData(const QMimeData *data, Qt::DropAction action, int row, int column, const QModelIndex &parent) override;
|
||||
|
||||
QAbstractItemModel* getSolutionModel(const QModelIndex& index) override;
|
||||
DisplaySolutionPtr getSolution(const QModelIndex &index) override;
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
@ -185,7 +185,8 @@ QVariant RemoteTaskModel::data(const QModelIndex &index, int role) const
|
||||
return (flags_ & IS_DESTROYED) ? QColor(Qt::red) : QApplication::palette().text().color();
|
||||
break;
|
||||
}
|
||||
return QVariant();
|
||||
|
||||
return BaseTaskModel::data(index, role);
|
||||
}
|
||||
|
||||
bool RemoteTaskModel::setData(const QModelIndex &index, const QVariant &value, int role)
|
||||
@ -291,6 +292,26 @@ DisplaySolutionPtr RemoteTaskModel::processSolutionMessage(const moveit_task_con
|
||||
return s;
|
||||
}
|
||||
|
||||
QAbstractItemModel* RemoteTaskModel::getSolutionModel(const QModelIndex &index)
|
||||
{
|
||||
Node *n = node(index);
|
||||
if (!n) return nullptr;
|
||||
return n->solved_.get();
|
||||
}
|
||||
|
||||
DisplaySolutionPtr RemoteTaskModel::getSolution(const QModelIndex &index)
|
||||
{
|
||||
Q_ASSERT(index.isValid());
|
||||
|
||||
uint32_t id = index.sibling(index.row(), 0).data(Qt::UserRole).toUInt();
|
||||
auto it = id_to_solution_.find(id);
|
||||
if (it == id_to_solution_.cend()) {
|
||||
// TODO: request solution via service
|
||||
return DisplaySolutionPtr();
|
||||
}
|
||||
return it->second;
|
||||
}
|
||||
|
||||
|
||||
RemoteSolutionModel::RemoteSolutionModel(QObject *parent)
|
||||
: QAbstractListModel(parent)
|
||||
|
||||
@ -72,6 +72,9 @@ public:
|
||||
void processStageDescriptions(const moveit_task_constructor_msgs::TaskDescription::_stages_type &msg);
|
||||
void processStageStatistics(const moveit_task_constructor_msgs::TaskStatistics::_stages_type &msg);
|
||||
DisplaySolutionPtr processSolutionMessage(const moveit_task_constructor_msgs::Solution &msg);
|
||||
|
||||
QAbstractItemModel* getSolutionModel(const QModelIndex& index) override;
|
||||
DisplaySolutionPtr getSolution(const QModelIndex &index) override;
|
||||
};
|
||||
|
||||
|
||||
|
||||
10
visualization/motion_planning_tasks/src/resources.qrc
Normal file
10
visualization/motion_planning_tasks/src/resources.qrc
Normal file
@ -0,0 +1,10 @@
|
||||
<RCC>
|
||||
<qresource prefix="/">
|
||||
<file>icons/add.png</file>
|
||||
<file>icons/settings.png</file>
|
||||
<file>icons/failed.png</file>
|
||||
<file>icons/new-stage.png</file>
|
||||
<file>icons/success.png</file>
|
||||
<file>icons/tasks.png</file>
|
||||
</qresource>
|
||||
</RCC>
|
||||
@ -41,29 +41,63 @@
|
||||
|
||||
#include <ros/console.h>
|
||||
#include <QMimeData>
|
||||
#include <QHeaderView>
|
||||
#include <QScrollBar>
|
||||
#include <qevent.h>
|
||||
|
||||
namespace moveit_rviz_plugin {
|
||||
|
||||
static const std::string LOGNAME("TaskListModel");
|
||||
|
||||
QString TaskListModel::horizontalHeader(int column)
|
||||
QVariant TaskListModel::horizontalHeader(int column, int role)
|
||||
{
|
||||
switch (column) {
|
||||
case 0: return tr("Name");
|
||||
case 1: return tr("# solved");
|
||||
case 2: return tr("# failed");
|
||||
switch (role) {
|
||||
case Qt::DisplayRole:
|
||||
switch (column) {
|
||||
case 0: return tr("Name");
|
||||
case 1: return tr(u8"✓");
|
||||
case 2: return tr(u8"✗");
|
||||
}
|
||||
break;
|
||||
|
||||
case Qt::ForegroundRole:
|
||||
switch (column) {
|
||||
case 1: return QColor(Qt::darkGreen);
|
||||
case 2: return QColor(Qt::red);
|
||||
}
|
||||
break;
|
||||
|
||||
case Qt::TextAlignmentRole:
|
||||
return column == 0 ? Qt::AlignLeft : Qt::AlignRight;
|
||||
|
||||
case Qt::ToolTipRole:
|
||||
switch (column) {
|
||||
case 1: return tr("successful solutions");
|
||||
case 2: return tr("failed solution attempts");
|
||||
case 3: return tr("pending");
|
||||
}
|
||||
break;
|
||||
}
|
||||
return QString();
|
||||
|
||||
return QVariant();
|
||||
}
|
||||
|
||||
QVariant BaseTaskModel::headerData(int section, Qt::Orientation orientation, int role) const
|
||||
{
|
||||
if (orientation == Qt::Horizontal && role == Qt::DisplayRole)
|
||||
return TaskListModel::horizontalHeader(section);
|
||||
if (orientation == Qt::Horizontal)
|
||||
return TaskListModel::horizontalHeader(section, role);
|
||||
return QAbstractItemModel::headerData(section, orientation, role);
|
||||
}
|
||||
|
||||
QVariant BaseTaskModel::data(const QModelIndex &index, int role) const
|
||||
{
|
||||
switch (role) {
|
||||
case Qt::TextAlignmentRole:
|
||||
return index.column() == 0 ? Qt::AlignLeft : Qt::AlignRight;
|
||||
}
|
||||
return QVariant();
|
||||
}
|
||||
|
||||
Qt::ItemFlags BaseTaskModel::flags(const QModelIndex &index) const
|
||||
{
|
||||
Qt::ItemFlags flags = QAbstractItemModel::flags(index);
|
||||
@ -144,8 +178,8 @@ QStringList TaskListModel::mimeTypes() const
|
||||
|
||||
QVariant TaskListModel::headerData(int section, Qt::Orientation orientation, int role) const
|
||||
{
|
||||
if (orientation == Qt::Horizontal && role == Qt::DisplayRole)
|
||||
return TaskListModel::horizontalHeader(section);
|
||||
if (orientation == Qt::Horizontal)
|
||||
return TaskListModel::horizontalHeader(section, role);
|
||||
else
|
||||
return QAbstractItemModel::headerData(section, orientation, role);
|
||||
}
|
||||
@ -249,9 +283,104 @@ Qt::DropActions TaskListModel::supportedDropActions() const
|
||||
}
|
||||
|
||||
|
||||
TaskListView::TaskListView(QWidget *parent)
|
||||
AutoAdjustingTreeView::AutoAdjustingTreeView(QWidget *parent)
|
||||
: QTreeView(parent)
|
||||
{
|
||||
// consider viewportSizeHint()
|
||||
setSizeAdjustPolicy(QAbstractScrollArea::AdjustToContents);
|
||||
}
|
||||
|
||||
void AutoAdjustingTreeView::setStretchSection(int section)
|
||||
{
|
||||
stretch_section_ = section;
|
||||
updateGeometry();
|
||||
}
|
||||
|
||||
void AutoAdjustingTreeView::setAutoHideSections(const QList<int> §ions)
|
||||
{
|
||||
auto_hide_cols_ = sections;
|
||||
updateGeometry();
|
||||
}
|
||||
|
||||
void AutoAdjustingTreeView::setModel(QAbstractItemModel *model)
|
||||
{
|
||||
size_hints_.clear();
|
||||
QTreeView::setModel(model);
|
||||
|
||||
updateGeometry();
|
||||
}
|
||||
|
||||
QSize AutoAdjustingTreeView::viewportSizeHint() const
|
||||
{
|
||||
bool preferred = sizePolicy().horizontalPolicy() & QSizePolicy::ShrinkFlag;
|
||||
auto m = model();
|
||||
auto *h = header();
|
||||
size_hints_.clear();
|
||||
|
||||
int width = 0;
|
||||
for (int i=0, end = m ? m->columnCount() : 0; i < end; ++i) {
|
||||
size_hints_.push_back(h->sectionSizeHint(i));
|
||||
if (preferred || !auto_hide_cols_.contains(i))
|
||||
width += size_hints_.back();
|
||||
}
|
||||
|
||||
QSize main_size (width, sizeHintForRow(0) * ((!preferred || !m) ? 2 : m->rowCount()));
|
||||
|
||||
// add size for header
|
||||
QSize header_size (0, header()->isVisible() ? header()->height() : 0);
|
||||
|
||||
// add size for scrollbars
|
||||
QSize scrollbars (verticalScrollBar()->isVisible() ? verticalScrollBar()->width() : 0,
|
||||
horizontalScrollBar()->isVisible() ? horizontalScrollBar()->height() : 0);
|
||||
|
||||
return main_size + header_size + scrollbars;
|
||||
}
|
||||
|
||||
void AutoAdjustingTreeView::resizeEvent(QResizeEvent *event)
|
||||
{
|
||||
auto *m = model();
|
||||
int columns = m ? m->columnCount() : 0;
|
||||
if ((int)size_hints_.size() != columns)
|
||||
viewportSizeHint();
|
||||
|
||||
// auto hide/show columns > 0, stretch last column to width
|
||||
int available_width = event->size().width();
|
||||
|
||||
int required_width = std::accumulate(size_hints_.begin(), size_hints_.end(), 0);
|
||||
std::vector<int> width = size_hints_;
|
||||
|
||||
// if required is larger than available width, try to hide some columns
|
||||
QListIterator<int> it(auto_hide_cols_);
|
||||
for (it.toBack(); it.hasPrevious() && required_width > available_width;) {
|
||||
int section = it.previous();
|
||||
required_width -= size_hints_[section];
|
||||
width[section] = 0;
|
||||
}
|
||||
|
||||
// extend width to current column width if possible
|
||||
for (int i=0; i < columns; ++i) {
|
||||
if (i == stretch_section_) continue; // ignore auto-stretch section for now
|
||||
int delta = columnWidth(i) > 0 ? columnWidth(i) - width[i] : 0;
|
||||
if (delta < 0 || required_width + delta <= available_width) {
|
||||
width[i] += delta;
|
||||
required_width += delta;
|
||||
}
|
||||
}
|
||||
|
||||
// stretch section if there is still space available
|
||||
if (stretch_section_ >= 0 && stretch_section_ < (int)width.size() &&
|
||||
width[stretch_section_] > 0 && available_width > required_width)
|
||||
width[stretch_section_] += available_width - required_width;
|
||||
|
||||
// apply stuff
|
||||
for (int i=0; i < columns; ++i)
|
||||
setColumnWidth(i, width[i]);
|
||||
}
|
||||
|
||||
|
||||
TaskListView::TaskListView(QWidget *parent) : AutoAdjustingTreeView(parent)
|
||||
{
|
||||
setStretchSection(0);
|
||||
}
|
||||
|
||||
// dropping onto an item, should expand this item
|
||||
|
||||
@ -62,18 +62,23 @@ protected:
|
||||
|
||||
public:
|
||||
enum TaskModelFlag {
|
||||
IS_DESTROYED = 0x01,
|
||||
IS_INITIALIZED = 0x02,
|
||||
IS_RUNNING = 0x04,
|
||||
LOCAL_MODEL = 0x01,
|
||||
IS_DESTROYED = 0x02,
|
||||
IS_INITIALIZED = 0x04,
|
||||
IS_RUNNING = 0x08,
|
||||
};
|
||||
|
||||
BaseTaskModel(QObject *parent = nullptr) : QAbstractItemModel(parent) {}
|
||||
|
||||
int columnCount(const QModelIndex &parent = QModelIndex()) const override { return 3; }
|
||||
QVariant headerData(int section, Qt::Orientation orientation, int role) const override;
|
||||
QVariant data(const QModelIndex &index, int role) const override;
|
||||
|
||||
Qt::ItemFlags flags(const QModelIndex &index) const override;
|
||||
unsigned int taskFlags() const { return flags_; }
|
||||
|
||||
virtual QAbstractItemModel* getSolutionModel(const QModelIndex& index) = 0;
|
||||
virtual DisplaySolutionPtr getSolution(const QModelIndex &index) = 0;
|
||||
};
|
||||
|
||||
|
||||
@ -113,7 +118,7 @@ public:
|
||||
void setScene(const planning_scene::PlanningSceneConstPtr& scene);
|
||||
|
||||
int columnCount(const QModelIndex &parent = QModelIndex()) const override { return 3; }
|
||||
static QString horizontalHeader(int column);
|
||||
static QVariant horizontalHeader(int column, int role);
|
||||
QVariant headerData(int section, Qt::Orientation orientation, int role) const override;
|
||||
|
||||
/// process an incoming task description message - only call in Qt's main loop
|
||||
@ -139,7 +144,29 @@ public:
|
||||
};
|
||||
|
||||
|
||||
class TaskListView : public QTreeView {
|
||||
class AutoAdjustingTreeView : public QTreeView {
|
||||
Q_OBJECT
|
||||
Q_PROPERTY(int stretchSection MEMBER stretch_section_ READ stretchSection WRITE setStretchSection)
|
||||
|
||||
mutable std::vector<int> size_hints_; // size hints for sections
|
||||
QList<int> auto_hide_cols_; // auto-hiding sections
|
||||
int stretch_section_ = -1;
|
||||
|
||||
public:
|
||||
AutoAdjustingTreeView(QWidget *parent = nullptr);
|
||||
|
||||
int stretchSection() const { return stretch_section_; }
|
||||
void setStretchSection(int section);
|
||||
|
||||
void setAutoHideSections(const QList<int> §ions);
|
||||
|
||||
void setModel(QAbstractItemModel *model);
|
||||
QSize viewportSizeHint() const override;
|
||||
void resizeEvent(QResizeEvent *event) override;
|
||||
};
|
||||
|
||||
|
||||
class TaskListView : public AutoAdjustingTreeView {
|
||||
Q_OBJECT
|
||||
public:
|
||||
TaskListView(QWidget *parent = nullptr);
|
||||
|
||||
@ -43,6 +43,7 @@
|
||||
#include "local_task_model.h"
|
||||
#include "factory_model.h"
|
||||
#include "pluginlib_factory.h"
|
||||
#include "task_display.h"
|
||||
#include <moveit/task_constructor/stage.h>
|
||||
|
||||
#include <rviz/properties/property.h>
|
||||
@ -77,9 +78,12 @@ TaskPanel::TaskPanel(QWidget* parent)
|
||||
{
|
||||
Q_D(TaskPanel);
|
||||
// connect signals
|
||||
connect(d->actionRemoveTaskTreeRows, SIGNAL(triggered()), this, SLOT(removeTaskTreeRows()));
|
||||
connect(d->actionRemoveTaskTreeRows, SIGNAL(triggered()), this, SLOT(removeSelectedStages()));
|
||||
connect(d->actionAddLocalTask, SIGNAL(triggered()), this, SLOT(addTask()));
|
||||
connect(d->button_show_stage_dock_widget, SIGNAL(clicked()), this, SLOT(showStageDockWidget()));
|
||||
|
||||
connect(d->tasks_view->selectionModel(), SIGNAL(currentChanged(QModelIndex, QModelIndex)),
|
||||
this, SLOT(onCurrentStageChanged(QModelIndex,QModelIndex)));
|
||||
}
|
||||
|
||||
TaskPanel::~TaskPanel()
|
||||
@ -101,6 +105,9 @@ TaskPanelPrivate::TaskPanelPrivate(TaskPanel *q_ptr)
|
||||
tasks_view->setDropIndicatorShown(true);
|
||||
tasks_view->setDragEnabled(true);
|
||||
|
||||
solutions_view->setAutoHideSections({1, 2});
|
||||
solutions_view->setStretchSection(2);
|
||||
|
||||
// init actions
|
||||
tasks_view->addActions({actionRemoveTaskTreeRows, actionAddLocalTask});
|
||||
|
||||
@ -112,6 +119,20 @@ void TaskPanelPrivate::initSettings(rviz::Property* root)
|
||||
{
|
||||
}
|
||||
|
||||
std::pair<TaskListModel*, TaskDisplay*>
|
||||
TaskPanelPrivate::getTaskListModel(const QModelIndex &index) const
|
||||
{
|
||||
auto *meta_model = static_cast<TaskListModelCache*>(tasks_view->model());
|
||||
return meta_model->getTaskListModel(index);
|
||||
}
|
||||
|
||||
std::pair<BaseTaskModel*, QModelIndex>
|
||||
TaskPanelPrivate::getTaskModel(const QModelIndex &index) const
|
||||
{
|
||||
auto *meta_model = static_cast<TaskListModelCache*>(tasks_view->model());
|
||||
return meta_model->getTaskModel(index);
|
||||
}
|
||||
|
||||
void TaskPanel::onInitialize()
|
||||
{
|
||||
}
|
||||
@ -130,28 +151,50 @@ void TaskPanel::load(const rviz::Config& config)
|
||||
|
||||
void TaskPanel::addTask()
|
||||
{
|
||||
Q_D(TaskPanel);
|
||||
QModelIndex current = d->tasks_view->currentIndex();
|
||||
TaskListModel* task_list_model
|
||||
= static_cast<TaskListModel*>(TaskListModelCache::instance().getModel(current).first);
|
||||
QModelIndex current = d_ptr->tasks_view->currentIndex();
|
||||
if (!current.isValid())
|
||||
Q_ASSERT(false); // TODO: insert new display?
|
||||
|
||||
TaskListModel* task_list_model = d_ptr->getTaskListModel(current).first;
|
||||
Q_ASSERT(task_list_model);
|
||||
task_list_model->insertModel(new LocalTaskModel(task_list_model), current.row());
|
||||
}
|
||||
|
||||
void TaskPanel::showStageDockWidget()
|
||||
{
|
||||
Q_D(TaskPanel);
|
||||
rviz::PanelDockWidget *dock = getStageDockWidget(vis_manager_->getWindowManager());
|
||||
if (dock) dock->show();
|
||||
}
|
||||
|
||||
void TaskPanel::removeTaskTreeRows()
|
||||
void TaskPanel::removeSelectedStages()
|
||||
{
|
||||
Q_D(TaskPanel);
|
||||
auto *m = d_ptr->tasks_view->model();
|
||||
for (const auto &range : d_ptr->tasks_view->selectionModel()->selection())
|
||||
m->removeRows(range.top(), range.bottom()-range.top()+1, range.parent());
|
||||
}
|
||||
|
||||
void TaskPanel::onCurrentStageChanged(const QModelIndex ¤t, const QModelIndex &previous)
|
||||
{
|
||||
BaseTaskModel *task;
|
||||
QModelIndex task_index;
|
||||
std::tie(task, task_index) = d_ptr->getTaskModel(current);
|
||||
d_ptr->actionRemoveTaskTreeRows->setEnabled(task != nullptr);
|
||||
|
||||
auto *view = d_ptr->solutions_view;
|
||||
QItemSelectionModel *sm = view->selectionModel();
|
||||
QAbstractItemModel *m = task ? task->getSolutionModel(task_index) : nullptr;
|
||||
view->setModel(m);
|
||||
delete sm; // we don't store the selection model
|
||||
|
||||
if (m)
|
||||
connect(view->selectionModel(), SIGNAL(currentChanged(QModelIndex, QModelIndex)),
|
||||
this, SLOT(onCurrentSolutionChanged(QModelIndex,QModelIndex)));
|
||||
}
|
||||
|
||||
void TaskPanel::onCurrentSolutionChanged(const QModelIndex ¤t, const QModelIndex &previous)
|
||||
{
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
#include "moc_task_panel.cpp"
|
||||
|
||||
@ -71,7 +71,11 @@ public:
|
||||
public Q_SLOTS:
|
||||
void addTask();
|
||||
void showStageDockWidget();
|
||||
void removeTaskTreeRows();
|
||||
|
||||
protected Q_SLOTS:
|
||||
void removeSelectedStages();
|
||||
void onCurrentStageChanged(const QModelIndex ¤t, const QModelIndex &previous);
|
||||
void onCurrentSolutionChanged(const QModelIndex ¤t, const QModelIndex &previous);
|
||||
};
|
||||
|
||||
}
|
||||
|
||||
@ -11,60 +11,171 @@
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>Form</string>
|
||||
<string>Tasks Panel</string>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="tasks_view_label_layout">
|
||||
<property name="spacing">
|
||||
<number>6</number>
|
||||
<widget class="QTabWidget" name="tabWidget">
|
||||
<property name="currentIndex">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QLabel" name="tasks_view_label">
|
||||
<property name="text">
|
||||
<string>Task Tree</string>
|
||||
<widget class="QWidget" name="tab_tasks">
|
||||
<attribute name="icon">
|
||||
<iconset resource="resources.qrc">
|
||||
<normaloff>:/icons/tasks.png</normaloff>:/icons/tasks.png</iconset>
|
||||
</attribute>
|
||||
<attribute name="title">
|
||||
<string/>
|
||||
</attribute>
|
||||
<layout class="QVBoxLayout" name="tab_tasks_layout">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QToolButton" name="button_show_stage_dock_widget">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>18</width>
|
||||
<height>18</height>
|
||||
</size>
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset theme="add">
|
||||
<normaloff>.</normaloff>.</iconset>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="moveit_rviz_plugin::TaskListView" name="tasks_view">
|
||||
<property name="contextMenuPolicy">
|
||||
<enum>Qt::ActionsContextMenu</enum>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="tasks_view_label_layout">
|
||||
<property name="spacing">
|
||||
<number>6</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QLabel" name="tasks_view_label">
|
||||
<property name="text">
|
||||
<string>Task Tree</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QToolButton" name="button_show_stage_dock_widget">
|
||||
<property name="maximumSize">
|
||||
<size>
|
||||
<width>18</width>
|
||||
<height>18</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="resources.qrc">
|
||||
<normaloff>:/icons/new-stage.png</normaloff>:/icons/new-stage.png</iconset>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QSplitter" name="splitter">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<widget class="moveit_rviz_plugin::TaskListView" name="tasks_view">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Expanding">
|
||||
<horstretch>2</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="contextMenuPolicy">
|
||||
<enum>Qt::ActionsContextMenu</enum>
|
||||
</property>
|
||||
<attribute name="headerStretchLastSection">
|
||||
<bool>false</bool>
|
||||
</attribute>
|
||||
</widget>
|
||||
<widget class="moveit_rviz_plugin::AutoAdjustingTreeView" name="solutions_view">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Preferred" vsizetype="Expanding">
|
||||
<horstretch>1</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="rootIsDecorated">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="uniformRowHeights">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="sortingEnabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<attribute name="headerStretchLastSection">
|
||||
<bool>false</bool>
|
||||
</attribute>
|
||||
</widget>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<widget class="QWidget" name="tab_settings">
|
||||
<attribute name="icon">
|
||||
<iconset resource="resources.qrc">
|
||||
<normaloff>:/icons/settings.png</normaloff>:/icons/settings.png</iconset>
|
||||
</attribute>
|
||||
<attribute name="title">
|
||||
<string/>
|
||||
</attribute>
|
||||
<layout class="QVBoxLayout" name="tab_settings_layout">
|
||||
<property name="spacing">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="leftMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="topMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="rightMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="bottomMargin">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<item>
|
||||
<widget class="QLabel" name="settings_view_label">
|
||||
<property name="text">
|
||||
<string>Settings</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="rviz::PropertyTreeWidget" name="settings_view"/>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QLabel" name="settings_view_label">
|
||||
<property name="text">
|
||||
<string>Settings</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="rviz::PropertyTreeWidget" name="settings_view"/>
|
||||
</item>
|
||||
</layout>
|
||||
<action name="actionRemoveTaskTreeRows">
|
||||
<property name="text">
|
||||
@ -97,7 +208,14 @@
|
||||
<extends>QTreeView</extends>
|
||||
<header>task_list_model.h</header>
|
||||
</customwidget>
|
||||
<customwidget>
|
||||
<class>moveit_rviz_plugin::AutoAdjustingTreeView</class>
|
||||
<extends>QTreeView</extends>
|
||||
<header>task_list_model.h</header>
|
||||
</customwidget>
|
||||
</customwidgets>
|
||||
<resources/>
|
||||
<resources>
|
||||
<include location="resources.qrc"/>
|
||||
</resources>
|
||||
<connections/>
|
||||
</ui>
|
||||
|
||||
@ -46,12 +46,24 @@
|
||||
|
||||
namespace moveit_rviz_plugin {
|
||||
|
||||
class BaseTaskModel;
|
||||
class TaskListModel;
|
||||
class TaskDisplay;
|
||||
|
||||
class TaskPanelPrivate : public Ui_TaskPanel {
|
||||
public:
|
||||
TaskPanelPrivate(TaskPanel *q_ptr);
|
||||
|
||||
void initSettings(rviz::Property *root);
|
||||
|
||||
/// retrieve TaskListModel corresponding to given index
|
||||
inline std::pair<TaskListModel*, TaskDisplay*>
|
||||
getTaskListModel(const QModelIndex &index) const;
|
||||
|
||||
/// retrieve TaskModel corresponding to given index
|
||||
inline std::pair<BaseTaskModel*, QModelIndex>
|
||||
getTaskModel(const QModelIndex& index) const;
|
||||
|
||||
TaskPanel* q_ptr;
|
||||
rviz::PropertyTreeModel* settings;
|
||||
};
|
||||
|
||||
Loading…
Reference in New Issue
Block a user