mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-11-04 14:49:57 +08:00
fix flaky "deletion" unittest
This commit is contained in:
parent
015dc2314a
commit
faa7b38ff9
@ -135,6 +135,12 @@ void TaskListModel::onRemoveModel(QAbstractItemModel *model)
|
|||||||
FlatMergeProxyModel::onRemoveModel(model);
|
FlatMergeProxyModel::onRemoveModel(model);
|
||||||
if (model->parent() == this)
|
if (model->parent() == this)
|
||||||
model->deleteLater();
|
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)
|
TaskListModel::TaskListModel(QObject *parent)
|
||||||
@ -149,7 +155,8 @@ TaskListModel::~TaskListModel() {
|
|||||||
removeRows(0, rowCount());
|
removeRows(0, rowCount());
|
||||||
// free RemoteTaskModels
|
// free RemoteTaskModels
|
||||||
for (auto& pair : remote_tasks_) {
|
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
|
} 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
|
// 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_);
|
remote_task->setSolutionClient(get_solution_client_);
|
||||||
}
|
}
|
||||||
if (!remote_task)
|
if (!remote_task)
|
||||||
|
|||||||
@ -157,6 +157,7 @@ public:
|
|||||||
data->storeMapping(src.internalPointer(), src_parent);
|
data->storeMapping(src.internalPointer(), src_parent);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// remove model referenced by it, call indicates that onRemoveModel() should be called
|
||||||
bool removeModel(std::vector<ModelData>::iterator& it, bool call);
|
bool removeModel(std::vector<ModelData>::iterator& it, bool call);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
@ -430,24 +431,25 @@ bool FlatMergeProxyModel::removeModel(int pos)
|
|||||||
|
|
||||||
void FlatMergeProxyModel::onRemoveModel(QAbstractItemModel *model)
|
void FlatMergeProxyModel::onRemoveModel(QAbstractItemModel *model)
|
||||||
{
|
{
|
||||||
QObject::disconnect(model, SIGNAL(rowsAboutToBeInserted(QModelIndex,int,int)),
|
disconnect(model, SIGNAL(destroyed(QObject*)), this, SLOT(_q_sourceDestroyed(QObject*)));
|
||||||
this, SLOT(_q_sourceRowsAboutToBeInserted(QModelIndex,int,int)));
|
disconnect(model, SIGNAL(rowsAboutToBeInserted(QModelIndex,int,int)),
|
||||||
QObject::disconnect(model, SIGNAL(rowsInserted(QModelIndex,int,int)),
|
this, SLOT(_q_sourceRowsAboutToBeInserted(QModelIndex,int,int)));
|
||||||
this, SLOT(_q_sourceRowsInserted(QModelIndex,int,int)));
|
disconnect(model, SIGNAL(rowsInserted(QModelIndex,int,int)),
|
||||||
QObject::disconnect(model, SIGNAL(rowsAboutToBeRemoved(QModelIndex,int,int)),
|
this, SLOT(_q_sourceRowsInserted(QModelIndex,int,int)));
|
||||||
this, SLOT(_q_sourceRowsAboutToBeRemoved(QModelIndex,int,int)));
|
disconnect(model, SIGNAL(rowsAboutToBeRemoved(QModelIndex,int,int)),
|
||||||
QObject::disconnect(model, SIGNAL(rowsRemoved(QModelIndex,int,int)),
|
this, SLOT(_q_sourceRowsAboutToBeRemoved(QModelIndex,int,int)));
|
||||||
this, SLOT(_q_sourceRowsRemoved(QModelIndex,int,int)));
|
disconnect(model, SIGNAL(rowsRemoved(QModelIndex,int,int)),
|
||||||
QObject::disconnect(model, SIGNAL(rowsAboutToBeMoved(QModelIndex,int,int,QModelIndex,int)),
|
this, SLOT(_q_sourceRowsRemoved(QModelIndex,int,int)));
|
||||||
this, SLOT(_q_sourceRowsAboutToBeMoved(QModelIndex,int,int,QModelIndex,int)));
|
disconnect(model, SIGNAL(rowsAboutToBeMoved(QModelIndex,int,int,QModelIndex,int)),
|
||||||
QObject::disconnect(model, SIGNAL(rowsMoved(QModelIndex,int,int,QModelIndex,int)),
|
this, SLOT(_q_sourceRowsAboutToBeMoved(QModelIndex,int,int,QModelIndex,int)));
|
||||||
this, SLOT(_q_sourceRowsMoved(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)
|
#if QT_VERSION >= QT_VERSION_CHECK(5, 0, 0)
|
||||||
QObject::disconnect(model, SIGNAL(dataChanged(QModelIndex,QModelIndex,QVector<int>)),
|
disconnect(model, SIGNAL(dataChanged(QModelIndex,QModelIndex,QVector<int>)),
|
||||||
this, SLOT(_q_sourceDataChanged(QModelIndex,QModelIndex,QVector<int>)));
|
this, SLOT(_q_sourceDataChanged(QModelIndex,QModelIndex,QVector<int>)));
|
||||||
#else
|
#else
|
||||||
QObject::disconnect(model, SIGNAL(dataChanged(QModelIndex,QModelIndex)),
|
disconnect(model, SIGNAL(dataChanged(QModelIndex,QModelIndex)),
|
||||||
this, SLOT(_q_sourceDataChanged(QModelIndex,QModelIndex)));
|
this, SLOT(_q_sourceDataChanged(QModelIndex,QModelIndex)));
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user