From faa7b38ff9d4cb64c64c8b751c689453b7240f8b Mon Sep 17 00:00:00 2001 From: Robert Haschke Date: Sun, 4 Feb 2018 15:38:08 +0100 Subject: [PATCH] fix flaky "deletion" unittest --- .../src/task_list_model.cpp | 11 ++++-- .../utils/flat_merge_proxy_model.cpp | 34 ++++++++++--------- 2 files changed, 27 insertions(+), 18 deletions(-) diff --git a/visualization/motion_planning_tasks/src/task_list_model.cpp b/visualization/motion_planning_tasks/src/task_list_model.cpp index f7e376cf..25ca8401 100644 --- a/visualization/motion_planning_tasks/src/task_list_model.cpp +++ b/visualization/motion_planning_tasks/src/task_list_model.cpp @@ -135,6 +135,12 @@ void TaskListModel::onRemoveModel(QAbstractItemModel *model) FlatMergeProxyModel::onRemoveModel(model); if (model->parent() == this) model->deleteLater(); + + // mark model as removed + auto it = std::find_if(remote_tasks_.begin(), remote_tasks_.end(), + [model](const auto& pair) { return pair.second == model; }); + if (it != remote_tasks_.end()) + it->second = nullptr; } TaskListModel::TaskListModel(QObject *parent) @@ -149,7 +155,8 @@ TaskListModel::~TaskListModel() { removeRows(0, rowCount()); // free RemoteTaskModels for (auto& pair : remote_tasks_) { - if (pair.second) delete pair.second; + if (pair.second) + delete pair.second; } } @@ -232,7 +239,7 @@ void TaskListModel::processTaskDescriptionMessage(const std::string& id, } } else if (created) { // create new task model, if ID was not known before // the model is managed by this instance via Qt's parent-child mechanism - remote_task = new RemoteTaskModel(scene_); + remote_task = new RemoteTaskModel(scene_, this); remote_task->setSolutionClient(get_solution_client_); } if (!remote_task) diff --git a/visualization/motion_planning_tasks/utils/flat_merge_proxy_model.cpp b/visualization/motion_planning_tasks/utils/flat_merge_proxy_model.cpp index 3661b9cf..0fc0c550 100644 --- a/visualization/motion_planning_tasks/utils/flat_merge_proxy_model.cpp +++ b/visualization/motion_planning_tasks/utils/flat_merge_proxy_model.cpp @@ -157,6 +157,7 @@ public: data->storeMapping(src.internalPointer(), src_parent); } + // remove model referenced by it, call indicates that onRemoveModel() should be called bool removeModel(std::vector::iterator& it, bool call); private: @@ -430,24 +431,25 @@ bool FlatMergeProxyModel::removeModel(int pos) void FlatMergeProxyModel::onRemoveModel(QAbstractItemModel *model) { - QObject::disconnect(model, SIGNAL(rowsAboutToBeInserted(QModelIndex,int,int)), - this, SLOT(_q_sourceRowsAboutToBeInserted(QModelIndex,int,int))); - QObject::disconnect(model, SIGNAL(rowsInserted(QModelIndex,int,int)), - this, SLOT(_q_sourceRowsInserted(QModelIndex,int,int))); - QObject::disconnect(model, SIGNAL(rowsAboutToBeRemoved(QModelIndex,int,int)), - this, SLOT(_q_sourceRowsAboutToBeRemoved(QModelIndex,int,int))); - QObject::disconnect(model, SIGNAL(rowsRemoved(QModelIndex,int,int)), - this, SLOT(_q_sourceRowsRemoved(QModelIndex,int,int))); - QObject::disconnect(model, SIGNAL(rowsAboutToBeMoved(QModelIndex,int,int,QModelIndex,int)), - this, SLOT(_q_sourceRowsAboutToBeMoved(QModelIndex,int,int,QModelIndex,int))); - QObject::disconnect(model, SIGNAL(rowsMoved(QModelIndex,int,int,QModelIndex,int)), - this, SLOT(_q_sourceRowsMoved(QModelIndex,int,int,QModelIndex,int))); + disconnect(model, SIGNAL(destroyed(QObject*)), this, SLOT(_q_sourceDestroyed(QObject*))); + disconnect(model, SIGNAL(rowsAboutToBeInserted(QModelIndex,int,int)), + this, SLOT(_q_sourceRowsAboutToBeInserted(QModelIndex,int,int))); + disconnect(model, SIGNAL(rowsInserted(QModelIndex,int,int)), + this, SLOT(_q_sourceRowsInserted(QModelIndex,int,int))); + disconnect(model, SIGNAL(rowsAboutToBeRemoved(QModelIndex,int,int)), + this, SLOT(_q_sourceRowsAboutToBeRemoved(QModelIndex,int,int))); + disconnect(model, SIGNAL(rowsRemoved(QModelIndex,int,int)), + this, SLOT(_q_sourceRowsRemoved(QModelIndex,int,int))); + disconnect(model, SIGNAL(rowsAboutToBeMoved(QModelIndex,int,int,QModelIndex,int)), + this, SLOT(_q_sourceRowsAboutToBeMoved(QModelIndex,int,int,QModelIndex,int))); + disconnect(model, SIGNAL(rowsMoved(QModelIndex,int,int,QModelIndex,int)), + this, SLOT(_q_sourceRowsMoved(QModelIndex,int,int,QModelIndex,int))); #if QT_VERSION >= QT_VERSION_CHECK(5, 0, 0) - QObject::disconnect(model, SIGNAL(dataChanged(QModelIndex,QModelIndex,QVector)), - this, SLOT(_q_sourceDataChanged(QModelIndex,QModelIndex,QVector))); + disconnect(model, SIGNAL(dataChanged(QModelIndex,QModelIndex,QVector)), + this, SLOT(_q_sourceDataChanged(QModelIndex,QModelIndex,QVector))); #else - QObject::disconnect(model, SIGNAL(dataChanged(QModelIndex,QModelIndex)), - this, SLOT(_q_sourceDataChanged(QModelIndex,QModelIndex))); + disconnect(model, SIGNAL(dataChanged(QModelIndex,QModelIndex)), + this, SLOT(_q_sourceDataChanged(QModelIndex,QModelIndex))); #endif }