60 #include <QButtonGroup>
65 static QPointer<rviz::PanelDockWidget> widget =
nullptr;
70 QTreeView* view =
new QTreeView();
71 view->setModel(
new FactoryModel(*factory, factory->mimeType(), view));
73 view->setHeaderHidden(
true);
74 view->setDragDropMode(QAbstractItemView::DragOnly);
75 widget = mgr->
addPane(
"Motion Planning Stages", view);
90 #if QT_VERSION >= QT_VERSION_CHECK(5, 15, 0)
91 connect(
d->tool_buttons_group, &QButtonGroup::idClicked,
d->stackedWidget,
92 [d](
int index) { d->stackedWidget->setCurrentIndex(index); });
94 connect(
d->tool_buttons_group,
static_cast<void (QButtonGroup::*)(
int)
>(&QButtonGroup::buttonClicked),
95 d->stackedWidget, [d](
int index) { d->stackedWidget->setCurrentIndex(index); });
97 connect(
d->stackedWidget, &QStackedWidget::currentChanged,
d->tool_buttons_group,
98 [d](
int index) { d->tool_buttons_group->button(index)->setChecked(true); });
100 auto* task_view =
new TaskView(
this,
d->property_root);
101 connect(
d->button_exec_solution, SIGNAL(clicked()), task_view, SLOT(onExecCurrentSolution()));
104 addSubPanel(task_view,
"Tasks View", QIcon(
":/icons/tasks.png"));
105 d->stackedWidget->setCurrentIndex(0);
108 addSubPanel(
new GlobalSettingsWidget(
this,
d->property_root),
"Global Settings", QIcon(
":/icons/settings.png"));
110 connect(
d->button_show_stage_dock_widget, SIGNAL(clicked()),
this, SLOT(showStageDockWidget()));
124 auto button =
new QToolButton(w);
125 button->setToolTip(title);
126 button->setIcon(icon);
127 button->setCheckable(
true);
129 int index =
d->stackedWidget->count();
130 d->tool_buttons_layout->insertWidget(
index, button);
131 d->tool_buttons_group->addButton(button,
index);
132 d->stackedWidget->addWidget(w);
134 w->setWindowTitle(title);
164 "Motion Planning Tasks",
"moveit_task_constructor/Motion Planning Tasks", Qt::LeftDockWidgetArea);
177 tool_buttons_group =
new QButtonGroup(panel);
178 tool_buttons_group->setExclusive(
true);
180 button_show_stage_dock_widget->setVisible(
false);
190 for (
int i = 0; i <
d_ptr->stackedWidget->count(); ++i) {
192 w->
save(
config.mapMakeChild(w->windowTitle()));
198 for (
int i = 0; i <
d_ptr->stackedWidget->count(); ++i) {
200 w->
load(
config.mapGetChild(w->windowTitle()));
211 void setExpanded(QTreeView* view,
const QModelIndex& index,
bool expand,
int depth = -1) {
212 if (!
index.isValid())
221 view->setExpanded(index, expand);
231 tasks_view->setModel(meta_model);
232 QObject::connect(meta_model, SIGNAL(rowsInserted(QModelIndex,
int,
int)), q_ptr,
233 SLOT(configureInsertedModels(QModelIndex,
int,
int)));
235 tasks_view->setSelectionMode(QAbstractItemView::ExtendedSelection);
236 tasks_view->setAcceptDrops(
true);
237 tasks_view->setDefaultDropAction(Qt::CopyAction);
238 tasks_view->setDropIndicatorShown(
true);
239 tasks_view->setDragEnabled(
true);
241 actionShowTimeColumn->setChecked(
true);
245 tasks_view->addActions({ actionRemoveTaskTreeRows, actionShowTimeColumn });
249 auto* meta_model =
static_cast<MetaTaskListModel*
>(tasks_view->model());
254 auto* meta_model =
static_cast<MetaTaskListModel*
>(tasks_view->model());
264 auto* meta_model =
static_cast<MetaTaskListModel*
>(tasks_view->model());
265 for (
int row = meta_model->
rowCount() - 1; row >= 0; --row)
270 if (parent.isValid() && !parent.parent().isValid()) {
272 for (
int row = first; row <= last; ++row) {
274 QModelIndex child = parent.model()->index(row, 0, parent);
288 tasks_view->setExpanded(parent,
true);
304 d_ptr->tasks_property_splitter->setStretchFactor(0, 3);
305 d_ptr->tasks_property_splitter->setStretchFactor(1, 1);
308 connect(
d->actionRemoveTaskTreeRows, SIGNAL(triggered()),
this, SLOT(removeSelectedStages()));
309 connect(
d->actionAddLocalTask, SIGNAL(triggered()),
this, SLOT(addTask()));
310 connect(
d->actionShowTimeColumn, &QAction::triggered, [
this](
bool checked) { show_time_column->setValue(checked); });
312 connect(
d->tasks_view->selectionModel(), SIGNAL(currentChanged(QModelIndex, QModelIndex)),
this,
313 SLOT(onCurrentStageChanged(QModelIndex, QModelIndex)));
315 onCurrentStageChanged(
d->tasks_view->currentIndex(), QModelIndex());
318 connect(d_ptr->tasks_property_splitter, SIGNAL(splitterMoved(
int,
int)),
this, SIGNAL(configChanged()));
319 connect(d_ptr->tasks_solutions_splitter, SIGNAL(splitterMoved(
int,
int)),
this, SIGNAL(configChanged()));
320 connect(d_ptr->tasks_view->header(), SIGNAL(sectionResized(
int,
int,
int)),
this, SIGNAL(configChanged()));
321 connect(d_ptr->solutions_view->header(), SIGNAL(sectionResized(
int,
int,
int)),
this, SIGNAL(configChanged()));
322 connect(d_ptr->solutions_view->header(), SIGNAL(sortIndicatorChanged(
int, Qt::SortOrder)),
this,
323 SIGNAL(configChanged()));
326 auto configs =
new rviz::Property(
"Task View Settings", QVariant(), QString(), root);
327 initial_task_expand =
328 new rviz::EnumProperty(
"Task Expansion",
"All Expanded",
"Configure how to initially expand new tasks", configs);
329 initial_task_expand->addOption(
"Top-level Expanded", EXPAND_TOP);
330 initial_task_expand->addOption(
"All Expanded", EXPAND_ALL);
331 initial_task_expand->addOption(
"All Closed", EXPAND_NONE);
335 "Configure what to do with old tasks whose solutions cannot be queried anymore", configs);
336 old_task_handling->addOption(
"Keep", OLD_TASK_KEEP);
337 old_task_handling->addOption(
"Replace", OLD_TASK_REPLACE);
338 old_task_handling->addOption(
"Remove", OLD_TASK_REMOVE);
341 show_time_column =
new rviz::BoolProperty(
"Show Computation Times",
true,
"Show the 'time' column", configs);
344 d_ptr->configureExistingModels();
352 auto write_splitter_sizes = [&
config](QSplitter* splitter,
const QString& key) {
354 for (
int s : splitter->sizes()) {
359 write_splitter_sizes(
d_ptr->tasks_property_splitter,
"property_splitter");
360 write_splitter_sizes(
d_ptr->tasks_solutions_splitter,
"solutions_splitter");
362 auto write_column_sizes = [&
config](QHeaderView* view,
const QString& key) {
364 for (
int c = 0, end = view->count();
c != end; ++
c) {
366 item.
setValue(view->sectionSize(c));
369 write_column_sizes(
d_ptr->tasks_view->header(),
"tasks_view_columns");
370 write_column_sizes(
d_ptr->solutions_view->header(),
"solutions_view_columns");
372 const QHeaderView* view =
d_ptr->solutions_view->header();
374 group.mapSetValue(
"column", view->sortIndicatorSection());
375 group.mapSetValue(
"order", view->sortIndicatorOrder());
382 auto read_sizes = [&
config](
const QString& key) {
384 QList<int> sizes, empty;
385 for (
int i = 0; i <
group.listLength(); ++i) {
391 int int_value =
value.toInt(&
ok);
398 d_ptr->tasks_property_splitter->setSizes(read_sizes(
"property_splitter"));
399 d_ptr->tasks_solutions_splitter->setSizes(read_sizes(
"solutions_splitter"));
402 for (
int w : read_sizes(
"tasks_view_columns"))
403 d_ptr->tasks_view->setColumnWidth(++column, w);
405 for (
int w : read_sizes(
"solutions_view_columns"))
406 d_ptr->tasks_view->setColumnWidth(++column, w);
408 QTreeView* view =
d_ptr->solutions_view;
411 if (
group.mapGetInt(
"column", &column) &&
group.mapGetInt(
"order", &order))
412 view->sortByColumn(column,
static_cast<Qt::SortOrder
>(order));
416 QModelIndex current =
d_ptr->tasks_view->currentIndex();
417 if (!current.isValid())
419 bool is_top_level = !current.parent().isValid();
426 current = current.model()->index(task_list_model->
rowCount() - 1, 0, current);
427 d_ptr->tasks_view->scrollTo(current);
428 d_ptr->tasks_view->setCurrentIndex(current);
429 d_ptr->tasks_view->edit(current);
433 auto*
m =
d_ptr->tasks_view->model();
434 for (
const auto& range :
d_ptr->tasks_view->selectionModel()->selection())
435 m->removeRows(range.top(), range.bottom() - range.top() + 1, range.parent());
440 d_ptr->actionAddLocalTask->setEnabled(current.isValid() &&
441 (!current.parent().isValid() || !current.parent().parent().isValid()));
443 d_ptr->actionRemoveTaskTreeRows->setEnabled(current.isValid() && current.parent().isValid());
446 QModelIndex task_index;
452 QTreeView* view =
d_ptr->solutions_view;
453 int sort_column = view->header()->sortIndicatorSection();
454 Qt::SortOrder sort_order = view->header()->sortIndicatorOrder();
456 QItemSelectionModel* sm = view->selectionModel();
457 QAbstractItemModel*
m = task ? task->getSolutionModel(task_index) :
nullptr;
458 if (view->model() != m) {
460 view->sortByColumn(sort_column, sort_order);
463 sm = view->selectionModel();
464 connect(sm, SIGNAL(currentChanged(QModelIndex, QModelIndex)),
this,
466 connect(sm, SIGNAL(selectionChanged(QItemSelection, QItemSelection)),
this,
471 view =
d_ptr->property_view;
472 sm = view->selectionModel();
473 m = task ? task->getPropertyModel(task_index) :
nullptr;
474 if (view->model() != m) {
484 if (!display || !current.isValid())
490 TaskSolutionVisualization* vis = display->visualization();
491 DisplaySolutionPtr solution;
493 solution = task->getSolution(current);
494 display->setSolutionStatus(
bool(solution));
495 }
catch (
const std::invalid_argument& e) {
497 display->setSolutionStatus(
false, e.what());
499 vis->interruptCurrentDisplay();
500 vis->showTrajectory(solution,
true);
504 QItemSelectionModel* sm =
d_ptr->solutions_view->selectionModel();
505 const QModelIndexList& selected_rows = sm->selectedRows();
512 display->clearMarkers();
513 for (
const auto& index : selected_rows) {
514 DisplaySolutionPtr solution;
516 solution = task->getSolution(
index);
517 display->setSolutionStatus(
bool(solution));
518 }
catch (
const std::invalid_argument& e) {
520 display->setSolutionStatus(
false, e.what());
522 display->addMarkers(solution);
527 const QModelIndex& current =
d_ptr->solutions_view->currentIndex();
528 if (!current.isValid())
534 const DisplaySolutionPtr& solution = task->getSolution(current);
537 ROS_ERROR(
"Failed to connect to the 'execute_task_solution' action server");
541 moveit_task_constructor_msgs::ExecuteTaskSolutionGoal goal;
542 solution->fillMessage(goal.solution);
550 d_ptr->tasks_view->header()->setSectionHidden(3, !show);
551 d_ptr->actionShowTimeColumn->setChecked(show);
562 view->setModel(properties);
569 d->view->expandAll();
586 #include "moc_task_panel.cpp"