Skip to content

Commit 5037bc7

Browse files
committed
Use public API only in visualization package
1 parent 0d6f790 commit 5037bc7

File tree

2 files changed

+38
-29
lines changed

2 files changed

+38
-29
lines changed

visualization/motion_planning_tasks/src/local_task_model.cpp

Lines changed: 37 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,6 @@
3737
#include "local_task_model.h"
3838
#include "factory_model.h"
3939
#include "properties/property_factory.h"
40-
#include <moveit/task_constructor/task_p.h>
4140
#include <rviz/properties/property_tree_model.h>
4241

4342
#include <ros/console.h>
@@ -63,64 +62,75 @@ QModelIndex LocalTaskModel::index(Node* n) const {
6362
if (n == root_)
6463
return QModelIndex();
6564

66-
const ContainerBasePrivate* parent = n->parent()->pimpl();
65+
const ContainerBase* parent = n->parent();
6766

6867
// the internal pointer refers to n
6968
int row = 0;
70-
for (const auto& child : parent->children()) {
71-
if (child->pimpl() == n)
72-
return createIndex(row, 0, n);
69+
auto findRow = [n, &row](const Stage& child, int /* depth */) -> bool {
70+
if (&child == n)
71+
return false; // found, don't continue traversal
7372
++row;
74-
}
75-
Q_ASSERT(false);
76-
return QModelIndex();
73+
return true;
74+
};
75+
parent->traverseChildren(findRow);
76+
Q_ASSERT(row < parent->numChildren());
77+
return createIndex(row, 0, n);
7778
}
7879

7980
LocalTaskModel::LocalTaskModel(ContainerBase::pointer&& container, const planning_scene::PlanningSceneConstPtr& scene,
8081
rviz::DisplayContext* display_context, QObject* parent)
8182
: BaseTaskModel(scene, display_context, parent), Task("", std::move(container)) {
82-
root_ = pimpl();
83+
root_ = this;
8384
flags_ |= LOCAL_MODEL;
8485
}
8586

8687
int LocalTaskModel::rowCount(const QModelIndex& parent) const {
8788
if (parent.column() > 0)
8889
return 0;
8990

90-
ContainerBasePrivate* c = dynamic_cast<ContainerBasePrivate*>(node(parent));
91+
ContainerBase* c = dynamic_cast<ContainerBase*>(node(parent));
9192
if (!c)
9293
return 0;
9394

94-
return c->children().size();
95+
return c->numChildren();
9596
}
9697

9798
QModelIndex LocalTaskModel::index(int row, int column, const QModelIndex& parent) const {
9899
if (column < 0 || column >= columnCount())
99100
return QModelIndex();
100101

101-
Q_ASSERT(dynamic_cast<ContainerBasePrivate*>(node(parent)));
102-
ContainerBasePrivate* p = static_cast<ContainerBasePrivate*>(node(parent));
103-
if (!p || row < 0 || (size_t)row >= p->children().size())
102+
Q_ASSERT(dynamic_cast<ContainerBase*>(node(parent)));
103+
ContainerBase* p = static_cast<ContainerBase*>(node(parent));
104+
if (!p || row < 0 || (size_t)row >= p->numChildren())
104105
return QModelIndex();
105106

106-
auto it = p->children().begin();
107-
std::advance(it, row);
108-
return createIndex(row, column, it->get()->pimpl());
107+
Node* child = nullptr;
108+
int idx = 0;
109+
p->traverseChildren([&idx, row, &child](const Stage& ch, int /* depth */) -> bool {
110+
if (idx == row) {
111+
child = const_cast<Node*>(&ch);
112+
return false;
113+
} else {
114+
++idx;
115+
return true;
116+
}
117+
});
118+
return createIndex(row, column, child);
109119
}
110120

111121
QModelIndex LocalTaskModel::parent(const QModelIndex& index) const {
112122
if (index.model() != this)
113123
return QModelIndex();
114124

115-
ContainerBasePrivate* parent = node(index)->parent()->pimpl();
125+
ContainerBase* parent = const_cast<ContainerBase*>(node(index)->parent());
116126
Q_ASSERT(parent);
117127

118128
return this->index(parent);
119129
}
120130

121131
Qt::ItemFlags LocalTaskModel::flags(const QModelIndex& index) const {
122132
Qt::ItemFlags flags = BaseTaskModel::flags(index);
123-
ContainerBasePrivate* c = dynamic_cast<ContainerBasePrivate*>(node(index));
133+
ContainerBase* c = dynamic_cast<ContainerBase*>(node(index));
124134
// dropping into containers is enabled
125135
if (c && stage_factory_)
126136
flags |= Qt::ItemIsDropEnabled;
@@ -139,7 +149,7 @@ QVariant LocalTaskModel::data(const QModelIndex& index, int role) const {
139149
case 0:
140150
return QString::fromStdString(n->name());
141151
case 1:
142-
return (uint)n->me()->solutions().size();
152+
return (uint)n->solutions().size();
143153
case 2:
144154
return 0;
145155
}
@@ -157,7 +167,7 @@ bool LocalTaskModel::setData(const QModelIndex& index, const QVariant& value, in
157167
const QString& name = value.toString();
158168
if (name == n->name().c_str())
159169
return false;
160-
n->me()->setName(name.toStdString());
170+
n->setName(name.toStdString());
161171
dataChanged(index, index);
162172
return true;
163173
}
@@ -168,10 +178,9 @@ bool LocalTaskModel::removeRows(int row, int count, const QModelIndex& parent) {
168178
if (flags_ & IS_RUNNING)
169179
return false; // cannot modify running task
170180

171-
Q_ASSERT(dynamic_cast<ContainerBase*>(node(parent)->me()));
172-
ContainerBasePrivate* cp = static_cast<ContainerBasePrivate*>(node(parent));
173-
ContainerBase* c = static_cast<ContainerBase*>(cp->me());
174-
if (row < 0 || (size_t)row + count > cp->children().size())
181+
Q_ASSERT(dynamic_cast<ContainerBase*>(node(parent)));
182+
ContainerBase* c = static_cast<ContainerBase*>(node(parent));
183+
if (row < 0 || (size_t)row + count > c->numChildren())
175184
return false;
176185

177186
beginRemoveRows(parent, row, row + count - 1);
@@ -195,7 +204,7 @@ bool LocalTaskModel::dropMimeData(const QMimeData* mime, Qt::DropAction action,
195204
if (!mime->hasFormat(mime_type))
196205
return false;
197206

198-
ContainerBasePrivate* c = dynamic_cast<ContainerBasePrivate*>(node(parent));
207+
ContainerBase* c = dynamic_cast<ContainerBase*>(node(parent));
199208
Q_ASSERT(c);
200209

201210
QString error;
@@ -204,7 +213,7 @@ bool LocalTaskModel::dropMimeData(const QMimeData* mime, Qt::DropAction action,
204213
return false;
205214

206215
beginInsertRows(parent, row, row);
207-
static_cast<ContainerBase*>(c->me())->insert(moveit::task_constructor::Stage::pointer(stage), row);
216+
c->insert(moveit::task_constructor::Stage::pointer(stage), row);
208217
endInsertRows();
209218
return true;
210219
}
@@ -231,7 +240,7 @@ rviz::PropertyTreeModel* LocalTaskModel::getPropertyModel(const QModelIndex& ind
231240
auto it_inserted = properties_.insert(std::make_pair(n, nullptr));
232241
if (it_inserted.second) { // newly inserted, create new model
233242
it_inserted.first->second =
234-
PropertyFactory::instance().createPropertyTreeModel(*n->me(), scene_.get(), display_context_);
243+
PropertyFactory::instance().createPropertyTreeModel(*n, scene_.get(), display_context_);
235244
it_inserted.first->second->setParent(this);
236245
}
237246
return it_inserted.first->second;

visualization/motion_planning_tasks/src/local_task_model.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@ namespace moveit_rviz_plugin {
4444
class LocalTaskModel : public BaseTaskModel, public moveit::task_constructor::Task
4545
{
4646
Q_OBJECT
47-
typedef moveit::task_constructor::StagePrivate Node;
47+
using Node = moveit::task_constructor::Stage;
4848
Node* root_;
4949
StageFactoryPtr stage_factory_;
5050
std::map<Node*, rviz::PropertyTreeModel*> properties_;

0 commit comments

Comments
 (0)