Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
moveit_rviz_plugin::LocalTaskModel Class Reference

#include <local_task_model.h>

Inheritance diagram for moveit_rviz_plugin::LocalTaskModel:
Inheritance graph
[legend]

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::PropertyTreeModelgetPropertyModel (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...
 
- Public Member Functions inherited from moveit_rviz_plugin::BaseTaskModel
 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
 
- Public Member Functions inherited from moveit::task_constructor::Task
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
 
StagefindChild (const std::string &name) const
 
const moveit::core::RobotModelConstPtr & getRobotModel () const
 
void init ()
 
void insert (Stage::pointer &&stage, int before=-1) override
 
Introspectionintrospection ()
 
void loadRobotModel (const std::string &robot_description="robot_description")
 
const std::string & name () const
 
size_t numSolutions () const
 
Taskoperator= (Task &&other)
 
Stageoperator[] (int index) const
 
moveit::core::MoveItErrorCode plan (size_t max_solutions=0)
 
void preempt ()
 
void printState (std::ostream &os=std::cout) const
 
PropertyMapproperties ()
 
const PropertyMapproperties () 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
 
ContainerBasestages ()
 
const ContainerBasestages () 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
 
Nodenode (const QModelIndex &index) const
 

Private Attributes

std::map< Node *, rviz::PropertyTreeModel * > properties_
 
Noderoot_
 
StageFactoryPtr stage_factory_
 

Additional Inherited Members

- Public Types inherited from moveit_rviz_plugin::BaseTaskModel
enum  TaskModelFlag : uint8_t { LOCAL_MODEL = 0x01, IS_DESTROYED = 0x02, IS_INITIALIZED = 0x04, IS_RUNNING = 0x08 }
 
- Public Types inherited from moveit::task_constructor::Task
typedef std::function< void(const Task &t)> TaskCallback
 
typedef std::list< TaskCallbackTaskCallbackList
 
- Static Public Member Functions inherited from moveit_rviz_plugin::BaseTaskModel
static QVariant flowIcon (moveit::task_constructor::InterfaceFlags f)
 
- Protected Types inherited from moveit::task_constructor::ContainerBase
typedef std::unique_ptr< ContainerBasepointer
 
typedef std::function< bool(const Stage &, unsigned int)> StageCallback
 
- Protected Types inherited from moveit::task_constructor::Stage
typedef std::unique_ptr< Stagepointer
 
enum  PropertyInitializerSource
 
typedef std::function< void(const SolutionBase &)> SolutionCallback
 
typedef std::list< SolutionCallbackSolutionCallbackList
 
- Protected Member Functions inherited from moveit::task_constructor::Task
bool canCompute () const override
 
void compute () override
 
void onNewSolution (const SolutionBase &s) override
 
- Protected Member Functions inherited from moveit::task_constructor::WrapperBase
 WrapperBase (WrapperBasePrivate *impl, Stage::pointer &&child=Stage::pointer())
 
bool canCompute () const override
 
void compute () override
 
void insert (Stage::pointer &&stage, int before=-1) override
 
Stagewrapped ()
 
const Stagewrapped () const
 
 WrapperBase (const std::string &name="wrapper", Stage::pointer &&child=Stage::pointer())
 
- Protected Member Functions inherited from moveit::task_constructor::ParallelContainerBase
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")
 
- Protected Member Functions inherited from moveit::task_constructor::ContainerBase
 ContainerBase (ContainerBasePrivate *impl)
 
void add (Stage::pointer &&stage)
 
StagefindChild (const std::string &name) const
 
void init (const moveit::core::RobotModelConstPtr &robot_model) override
 
size_t numChildren () const
 
Stageoperator[] (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
 
- Protected Member Functions inherited from moveit::task_constructor::Stage
 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
 
Introspectionintrospection () const
 
uint32_t introspectionId () const
 
const std::string & markerNS ()
 
const std::string & name () const
 
size_t numFailures () const
 
const ContainerBaseparent () const
 
PropertyMapproperties ()
 
const PropertyMapproperties () 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 ()
 
- Protected Attributes inherited from moveit_rviz_plugin::BaseTaskModel
rviz::DisplayContextdisplay_context_
 
unsigned int flags_ = 0
 
planning_scene::PlanningSceneConstPtr scene_
 
- Protected Attributes inherited from moveit::task_constructor::Stage
StagePrivate * pimpl_
 
 DEFAULT
 
 INTERFACE
 
 MANUAL
 
 PARENT
 

Detailed Description

Definition at line 76 of file local_task_model.h.

Member Typedef Documentation

◆ Node

Definition at line 111 of file local_task_model.h.

Constructor & Destructor Documentation

◆ LocalTaskModel()

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.

Member Function Documentation

◆ data()

QVariant moveit_rviz_plugin::LocalTaskModel::data ( const QModelIndex &  index,
int  role = Qt::DisplayRole 
) const
override

Definition at line 142 of file local_task_model.cpp.

◆ dropMimeData()

bool moveit_rviz_plugin::LocalTaskModel::dropMimeData ( const QMimeData *  data,
Qt::DropAction  action,
int  row,
int  column,
const QModelIndex &  parent 
)
override

Definition at line 199 of file local_task_model.cpp.

◆ flags()

Qt::ItemFlags moveit_rviz_plugin::LocalTaskModel::flags ( const QModelIndex &  index) const
override

Definition at line 131 of file local_task_model.cpp.

◆ getPropertyModel()

rviz::PropertyTreeModel * moveit_rviz_plugin::LocalTaskModel::getPropertyModel ( const QModelIndex &  index)
overridevirtual

get property model for given stage index

Implements moveit_rviz_plugin::BaseTaskModel.

Definition at line 238 of file local_task_model.cpp.

◆ getSolution()

DisplaySolutionPtr moveit_rviz_plugin::LocalTaskModel::getSolution ( const QModelIndex &  index)
overridevirtual

get solution for given solution index

Implements moveit_rviz_plugin::BaseTaskModel.

Definition at line 233 of file local_task_model.cpp.

◆ getSolutionModel()

QAbstractItemModel * moveit_rviz_plugin::LocalTaskModel::getSolutionModel ( const QModelIndex &  index)
overridevirtual

get solution model for given stage index

Implements moveit_rviz_plugin::BaseTaskModel.

Definition at line 228 of file local_task_model.cpp.

◆ index() [1/2]

QModelIndex moveit_rviz_plugin::LocalTaskModel::index ( int  row,
int  column,
const QModelIndex &  parent = QModelIndex() 
) const
override

Definition at line 98 of file local_task_model.cpp.

◆ index() [2/2]

QModelIndex moveit_rviz_plugin::LocalTaskModel::index ( Node n) const
private

Definition at line 61 of file local_task_model.cpp.

◆ indexFromStageId()

QModelIndex moveit_rviz_plugin::LocalTaskModel::indexFromStageId ( size_t  id) const
overridevirtual

retrieve model index associated with given stage id

Implements moveit_rviz_plugin::BaseTaskModel.

Definition at line 223 of file local_task_model.cpp.

◆ node()

LocalTaskModel::Node * moveit_rviz_plugin::LocalTaskModel::node ( const QModelIndex &  index) const
inlineprivate

Definition at line 51 of file local_task_model.cpp.

◆ parent()

QModelIndex moveit_rviz_plugin::LocalTaskModel::parent ( const QModelIndex &  index) const
override

Definition at line 121 of file local_task_model.cpp.

◆ removeRows()

bool moveit_rviz_plugin::LocalTaskModel::removeRows ( int  row,
int  count,
const QModelIndex &  parent 
)
override

Definition at line 177 of file local_task_model.cpp.

◆ rowCount()

int moveit_rviz_plugin::LocalTaskModel::rowCount ( const QModelIndex &  parent = QModelIndex()) const
override

Definition at line 87 of file local_task_model.cpp.

◆ setData()

bool moveit_rviz_plugin::LocalTaskModel::setData ( const QModelIndex &  index,
const QVariant &  value,
int  role = Qt::EditRole 
)
override

Definition at line 163 of file local_task_model.cpp.

◆ setStageFactory()

void moveit_rviz_plugin::LocalTaskModel::setStageFactory ( const StageFactoryPtr factory)
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.

Member Data Documentation

◆ properties_

std::map<Node*, rviz::PropertyTreeModel*> moveit_rviz_plugin::LocalTaskModel::properties_
private

Definition at line 114 of file local_task_model.h.

◆ root_

Node* moveit_rviz_plugin::LocalTaskModel::root_
private

Definition at line 112 of file local_task_model.h.

◆ stage_factory_

StageFactoryPtr moveit_rviz_plugin::LocalTaskModel::stage_factory_
private

Definition at line 113 of file local_task_model.h.


The documentation for this class was generated from the following files:


visualization
Author(s): Robert Haschke
autogenerated on Thu Feb 27 2025 03:39:51