#include <task_list_model.h>
Public Types | |
enum | TaskModelFlag : uint8_t { LOCAL_MODEL = 0x01, IS_DESTROYED = 0x02, IS_INITIALIZED = 0x04, IS_RUNNING = 0x08 } |
Public Member Functions | |
BaseTaskModel (const planning_scene::PlanningSceneConstPtr &scene, rviz::DisplayContext *display_context, QObject *parent=nullptr) | |
int | columnCount (const QModelIndex &=QModelIndex()) const override |
QVariant | data (const QModelIndex &index, int role) const override |
virtual rviz::PropertyTreeModel * | getPropertyModel (const QModelIndex &index)=0 |
get property model for given stage index More... | |
virtual DisplaySolutionPtr | getSolution (const QModelIndex &index)=0 |
get solution for given solution index More... | |
virtual QAbstractItemModel * | getSolutionModel (const QModelIndex &index)=0 |
get solution model for given stage index More... | |
QVariant | headerData (int section, Qt::Orientation orientation, int role) const override |
virtual QModelIndex | indexFromStageId (size_t id) const =0 |
retrieve model index associated with given stage id More... | |
virtual void | setStageFactory (const StageFactoryPtr &) |
unsigned int | taskFlags () const |
Static Public Member Functions | |
static QVariant | flowIcon (moveit::task_constructor::InterfaceFlags f) |
Protected Attributes | |
rviz::DisplayContext * | display_context_ |
unsigned int | flags_ = 0 |
planning_scene::PlanningSceneConstPtr | scene_ |
Base class to represent a single local or remote Task as a Qt model.
Definition at line 71 of file task_list_model.h.
Enumerator | |
---|---|
LOCAL_MODEL | |
IS_DESTROYED | |
IS_INITIALIZED | |
IS_RUNNING |
Definition at line 80 of file task_list_model.h.
|
inline |
Definition at line 88 of file task_list_model.h.
|
inlineoverride |
Definition at line 92 of file task_list_model.h.
|
override |
Definition at line 109 of file task_list_model.cpp.
|
static |
Definition at line 117 of file task_list_model.cpp.
|
pure virtual |
get property model for given stage index
Implemented in moveit_rviz_plugin::LocalTaskModel, and moveit_rviz_plugin::RemoteTaskModel.
|
pure virtual |
get solution for given solution index
Implemented in moveit_rviz_plugin::LocalTaskModel, and moveit_rviz_plugin::RemoteTaskModel.
|
pure virtual |
get solution model for given stage index
Implemented in moveit_rviz_plugin::LocalTaskModel, and moveit_rviz_plugin::RemoteTaskModel.
|
override |
Definition at line 103 of file task_list_model.cpp.
|
pure virtual |
retrieve model index associated with given stage id
Implemented in moveit_rviz_plugin::LocalTaskModel, and moveit_rviz_plugin::RemoteTaskModel.
|
inlinevirtual |
Reimplemented in moveit_rviz_plugin::LocalTaskModel.
Definition at line 96 of file task_list_model.h.
|
inline |
Definition at line 97 of file task_list_model.h.
|
protected |
Definition at line 77 of file task_list_model.h.
|
protected |
Definition at line 75 of file task_list_model.h.
|
protected |
Definition at line 76 of file task_list_model.h.