Go to the documentation of this file.
55 Q_ASSERT(
index.model() ==
this);
57 return static_cast<Node*
>(
index.internalPointer());
61 QModelIndex LocalTaskModel::index(
Node* n)
const {
69 auto find_row = [n, &row](
const Stage& child,
int ) ->
bool {
76 Q_ASSERT(row < parent->numChildren());
77 return createIndex(row, 0, n);
80 LocalTaskModel::LocalTaskModel(
ContainerBase::pointer&& container,
const planning_scene::PlanningSceneConstPtr& scene,
95 return c->numChildren();
100 return QModelIndex();
104 if (!p || row < 0 ||
static_cast<size_t>(row) >= p->
numChildren())
105 return QModelIndex();
107 Node* child =
nullptr;
111 child =
const_cast<Node*
>(&ch);
118 return createIndex(row, column, child);
122 if (
index.model() !=
this)
123 return QModelIndex();
128 return this->
index(parent);
132 Qt::ItemFlags
flags = BaseTaskModel::flags(
index);
136 flags |= Qt::ItemIsDropEnabled;
137 if (
index.column() == 0)
138 flags |= Qt::ItemIsEditable;
149 case Qt::DisplayRole:
150 switch (
index.column()) {
152 return QString::fromStdString(n->
name());
154 return static_cast<uint
>(n->
solutions().size());
165 if (!n ||
index.column() != 0 || role != Qt::EditRole)
185 if (row < 0 ||
static_cast<size_t>(row + count) >
c->numChildren())
188 beginRemoveRows(
parent, row, row + count - 1);
189 for (; count > 0; --count)
200 const QModelIndex& parent) {
206 if (!mime->hasFormat(mime_type))
217 beginInsertRows(
parent, row, row);
225 return QModelIndex();
235 return DisplaySolutionPtr();
242 auto it_inserted =
properties_.insert(std::make_pair(n,
nullptr));
243 if (it_inserted.second) {
244 it_inserted.first->second =
246 it_inserted.first->second->setParent(
this);
248 return it_inserted.first->second;
QAbstractItemModel * getSolutionModel(const QModelIndex &index) override
get solution model for given stage index
StageFactoryPtr stage_factory_
const ContainerBase * parent() const
bool traverseChildren(const StageCallback &processor) const
static PropertyFactory & instance()
rviz::PropertyTreeModel * getPropertyModel(const QModelIndex &index) override
get property model for given stage index
void setStageFactory(const StageFactoryPtr &factory) override
providing a StageFactory makes the model accepting drops
QVariant data(const QModelIndex &index, int role=Qt::DisplayRole) const override
rviz::PropertyTreeModel * createPropertyTreeModel(moveit::task_constructor::Stage &stage, const planning_scene::PlanningScene *scene, rviz::DisplayContext *display_context)
create PropertyTreeModel for given Stage
std::shared_ptr< StageFactory > StageFactoryPtr
DisplaySolutionPtr getSolution(const QModelIndex &index) override
get solution for given solution index
std::unique_ptr< Stage > pointer
const std::string & name() const
std::map< Node *, rviz::PropertyTreeModel * > properties_
bool dropMimeData(const QMimeData *data, Qt::DropAction action, int row, int column, const QModelIndex &parent) override
planning_scene::PlanningSceneConstPtr scene_
size_t numChildren() const
std::unique_ptr< ContainerBase > pointer
QModelIndex indexFromStageId(size_t id) const override
retrieve model index associated with given stage id
bool removeRows(int row, int count, const QModelIndex &parent) override
Node * node(const QModelIndex &index) const
void setName(const std::string &name)
const ordered< SolutionBaseConstPtr > & solutions() const
const std::string & name() const
rviz::DisplayContext * display_context_
Qt::ItemFlags flags(const QModelIndex &index) const override
int rowCount(const QModelIndex &parent=QModelIndex()) const override
QModelIndex index(Node *n) const
int columnCount(const QModelIndex &=QModelIndex()) const override
bool setData(const QModelIndex &index, const QVariant &value, int role=Qt::EditRole) override
QVariant data(const QModelIndex &index, int role) const override
visualization
Author(s): Robert Haschke
autogenerated on Thu Feb 27 2025 03:39:51