#include <local_task_model.h>
Public Member Functions | |
QVariant | data (const QModelIndex &index, int role=Qt::DisplayRole) const override |
bool | dropMimeData (const QMimeData *data, Qt::DropAction action, int row, int column, const QModelIndex &parent) override |
Qt::ItemFlags | flags (const QModelIndex &index) const override |
rviz::PropertyTreeModel * | getPropertyModel (const QModelIndex &index) override |
get property model for given stage index More... | |
DisplaySolutionPtr | getSolution (const QModelIndex &index) override |
get solution for given solution index More... | |
QAbstractItemModel * | getSolutionModel (const QModelIndex &index) override |
get solution model for given stage index More... | |
QModelIndex | index (int row, int column, const QModelIndex &parent=QModelIndex()) const override |
QModelIndex | indexFromStageId (size_t id) const override |
retrieve model index associated with given stage id More... | |
LocalTaskModel (ContainerBase::pointer &&container, const planning_scene::PlanningSceneConstPtr &scene, rviz::DisplayContext *display_context, QObject *parent=nullptr) | |
QModelIndex | parent (const QModelIndex &index) const override |
bool | removeRows (int row, int count, const QModelIndex &parent) override |
int | rowCount (const QModelIndex &parent=QModelIndex()) const override |
bool | setData (const QModelIndex &index, const QVariant &value, int role=Qt::EditRole) override |
void | setStageFactory (const StageFactoryPtr &factory) override |
providing a StageFactory makes the model accepting drops More... | |
![]() | |
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 |
QVariant | headerData (int section, Qt::Orientation orientation, int role) const override |
unsigned int | taskFlags () const |
![]() | |
void | add (Stage::pointer &&stage) |
TaskCallbackList::const_iterator | addTaskCallback (TaskCallback &&cb) |
void | clear () final |
void | enableIntrospection (bool enable=true) |
void | eraseTaskCallback (TaskCallbackList::const_iterator which) |
moveit::core::MoveItErrorCode | execute (const SolutionBase &s) |
bool | explainFailure (std::ostream &os=std::cout) const override |
const std::list< SolutionBaseConstPtr > & | failures () const |
Stage * | findChild (const std::string &name) const |
const moveit::core::RobotModelConstPtr & | getRobotModel () const |
void | init () |
void | insert (Stage::pointer &&stage, int before=-1) override |
Introspection & | introspection () |
void | loadRobotModel (const std::string &robot_description="robot_description") |
const std::string & | name () const |
size_t | numSolutions () const |
Task & | operator= (Task &&other) |
Stage * | operator[] (int index) const |
moveit::core::MoveItErrorCode | plan (size_t max_solutions=0) |
void | preempt () |
void | printState (std::ostream &os=std::cout) const |
PropertyMap & | properties () |
const PropertyMap & | properties () const |
void | publishAllSolutions (bool wait=true) |
void | reset () final |
void | resetPreemptRequest () |
void | setName (const std::string &name) |
void | setProperty (const std::string &name, const boost::any &value) |
void | setProperty (const std::string &name, const char *value) |
void | setRobotModel (const moveit::core::RobotModelConstPtr &robot_model) |
const ordered< SolutionBaseConstPtr > & | solutions () const |
ContainerBase * | stages () |
const ContainerBase * | stages () const |
Task (const std::string &ns="", bool introspection=true, ContainerBase::pointer &&container=std::make_unique< SerialContainer >("task pipeline")) | |
Task (Task &&other) | |
~Task () override | |
Private Types | |
using | Node = moveit::task_constructor::Stage |
Private Member Functions | |
QModelIndex | index (Node *n) const |
Node * | node (const QModelIndex &index) const |
Private Attributes | |
std::map< Node *, rviz::PropertyTreeModel * > | properties_ |
Node * | root_ |
StageFactoryPtr | stage_factory_ |
Additional Inherited Members | |
![]() | |
enum | TaskModelFlag : uint8_t { LOCAL_MODEL = 0x01, IS_DESTROYED = 0x02, IS_INITIALIZED = 0x04, IS_RUNNING = 0x08 } |
![]() | |
typedef std::function< void(const Task &t)> | TaskCallback |
typedef std::list< TaskCallback > | TaskCallbackList |
![]() | |
static QVariant | flowIcon (moveit::task_constructor::InterfaceFlags f) |
![]() | |
typedef std::unique_ptr< ContainerBase > | pointer |
typedef std::function< bool(const Stage &, unsigned int)> | StageCallback |
![]() | |
typedef std::unique_ptr< Stage > | pointer |
enum | PropertyInitializerSource |
typedef std::function< void(const SolutionBase &)> | SolutionCallback |
typedef std::list< SolutionCallback > | SolutionCallbackList |
![]() | |
bool | canCompute () const override |
void | compute () override |
void | onNewSolution (const SolutionBase &s) override |
![]() | |
WrapperBase (WrapperBasePrivate *impl, Stage::pointer &&child=Stage::pointer()) | |
bool | canCompute () const override |
void | compute () override |
void | insert (Stage::pointer &&stage, int before=-1) override |
Stage * | wrapped () |
const Stage * | wrapped () const |
WrapperBase (const std::string &name="wrapper", Stage::pointer &&child=Stage::pointer()) | |
![]() | |
void | liftSolution (const SolutionBase &solution) |
void | liftSolution (const SolutionBase &solution, double cost) |
void | liftSolution (const SolutionBase &solution, double cost, std::string comment) |
ParallelContainerBase (ParallelContainerBasePrivate *impl) | |
void | sendBackward (InterfaceState &&from, const InterfaceState &to, SubTrajectory &&trajectory) |
void | sendForward (const InterfaceState &from, InterfaceState &&to, SubTrajectory &&trajectory) |
void | spawn (InterfaceState &&state, SubTrajectory &&trajectory) |
ParallelContainerBase (const std::string &name="parallel container") | |
![]() | |
ContainerBase (ContainerBasePrivate *impl) | |
void | add (Stage::pointer &&stage) |
Stage * | findChild (const std::string &name) const |
void | init (const moveit::core::RobotModelConstPtr &robot_model) override |
size_t | numChildren () const |
Stage * | operator[] (int index) const |
bool | pruning () const |
virtual Stage::pointer | remove (int pos) |
virtual Stage::pointer | remove (Stage *child) |
void | setPruning (bool pruning) |
bool | traverseChildren (const StageCallback &processor) const |
bool | traverseRecursively (const StageCallback &processor) const |
![]() | |
Stage (const Stage &)=delete | |
Stage (StagePrivate *impl) | |
SolutionCallbackList::const_iterator | addSolutionCallback (SolutionCallback &&cb) |
const std::list< SolutionBaseConstPtr > & | failures () const |
std::set< std::string > | forwardedProperties () const |
void | forwardProperties (const InterfaceState &source, InterfaceState &dest) |
double | getTotalComputeTime () const |
Introspection * | introspection () const |
uint32_t | introspectionId () const |
const std::string & | markerNS () |
const std::string & | name () const |
size_t | numFailures () const |
const ContainerBase * | parent () const |
PropertyMap & | properties () |
const PropertyMap & | properties () const |
void | removeSolutionCallback (SolutionCallbackList::const_iterator which) |
void | reportPropertyError (const Property::error &e) |
void | setCostTerm (const CostTermConstPtr &term) |
void | setCostTerm (T term) |
void | setForwardedProperties (const std::set< std::string > &names) |
void | setMarkerNS (const std::string &marker_ns) |
void | setName (const std::string &name) |
void | setProperty (const std::string &name, const boost::any &value) |
void | setProperty (const std::string &name, const char *value) |
void | setTimeout (double timeout) |
void | setTrajectoryExecutionInfo (TrajectoryExecutionInfo trajectory_execution_info) |
void | silentFailure () |
const ordered< SolutionBaseConstPtr > & | solutions () const |
bool | storeFailures () const |
double | timeout () const |
TrajectoryExecutionInfo | trajectoryExecutionInfo () const |
virtual | ~Stage () |
![]() | |
rviz::DisplayContext * | display_context_ |
unsigned int | flags_ = 0 |
planning_scene::PlanningSceneConstPtr | scene_ |
![]() | |
StagePrivate * | pimpl_ |
DEFAULT | |
INTERFACE | |
MANUAL | |
PARENT | |
Definition at line 76 of file local_task_model.h.
Definition at line 111 of file local_task_model.h.
moveit_rviz_plugin::LocalTaskModel::LocalTaskModel | ( | ContainerBase::pointer && | container, |
const planning_scene::PlanningSceneConstPtr & | scene, | ||
rviz::DisplayContext * | display_context, | ||
QObject * | parent = nullptr |
||
) |
Definition at line 80 of file local_task_model.cpp.
|
override |
Definition at line 142 of file local_task_model.cpp.
|
override |
Definition at line 199 of file local_task_model.cpp.
|
override |
Definition at line 131 of file local_task_model.cpp.
|
overridevirtual |
get property model for given stage index
Implements moveit_rviz_plugin::BaseTaskModel.
Definition at line 238 of file local_task_model.cpp.
|
overridevirtual |
get solution for given solution index
Implements moveit_rviz_plugin::BaseTaskModel.
Definition at line 233 of file local_task_model.cpp.
|
overridevirtual |
get solution model for given stage index
Implements moveit_rviz_plugin::BaseTaskModel.
Definition at line 228 of file local_task_model.cpp.
|
override |
Definition at line 98 of file local_task_model.cpp.
|
private |
Definition at line 61 of file local_task_model.cpp.
|
overridevirtual |
retrieve model index associated with given stage id
Implements moveit_rviz_plugin::BaseTaskModel.
Definition at line 223 of file local_task_model.cpp.
|
inlineprivate |
Definition at line 51 of file local_task_model.cpp.
|
override |
Definition at line 121 of file local_task_model.cpp.
|
override |
Definition at line 177 of file local_task_model.cpp.
|
override |
Definition at line 87 of file local_task_model.cpp.
|
override |
Definition at line 163 of file local_task_model.cpp.
|
overridevirtual |
providing a StageFactory makes the model accepting drops
Reimplemented from moveit_rviz_plugin::BaseTaskModel.
Definition at line 195 of file local_task_model.cpp.
|
private |
Definition at line 114 of file local_task_model.h.
|
private |
Definition at line 112 of file local_task_model.h.
|
private |
Definition at line 113 of file local_task_model.h.