Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
moveit_rviz_plugin::RemoteTaskModel Class Reference

#include <remote_task_model.h>

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

Classes

struct  Node
 

Public Member Functions

QVariant data (const QModelIndex &index, int role=Qt::DisplayRole) 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...
 
QModelIndex parent (const QModelIndex &index) const override
 
DisplaySolutionPtr processSolutionMessage (const moveit_task_constructor_msgs::Solution &msg)
 
void processStageDescriptions (const moveit_task_constructor_msgs::TaskDescription::_stages_type &msg)
 
void processStageStatistics (const moveit_task_constructor_msgs::TaskStatistics::_stages_type &msg)
 
 RemoteTaskModel (ros::NodeHandle &nh, const std::string &service_name, const planning_scene::PlanningSceneConstPtr &scene, rviz::DisplayContext *display_context, QObject *parent=nullptr)
 
int rowCount (const QModelIndex &parent=QModelIndex()) const override
 
bool setData (const QModelIndex &index, const QVariant &value, int role=Qt::EditRole) override
 
 ~RemoteTaskModel () override
 
- 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
 
virtual void setStageFactory (const StageFactoryPtr &)
 
unsigned int taskFlags () const
 

Private Member Functions

RemoteSolutionModelgetSolutionModel (uint32_t stage_id) const
 
QModelIndex index (const Node *n) const
 
Nodenode (const QModelIndex &index) const
 
Nodenode (uint32_t stage_id) const
 
void setSolutionData (const moveit_task_constructor_msgs::SolutionInfo &info)
 

Private Attributes

ros::ServiceClient get_solution_client_
 
std::map< uint32_t, DisplaySolutionPtr > id_to_solution_
 
std::map< uint32_t, Node * > id_to_stage_
 
Node *const root_
 

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 }
 
- Static Public Member Functions inherited from moveit_rviz_plugin::BaseTaskModel
static QVariant flowIcon (moveit::task_constructor::InterfaceFlags f)
 
- Protected Attributes inherited from moveit_rviz_plugin::BaseTaskModel
rviz::DisplayContextdisplay_context_
 
unsigned int flags_ = 0
 
planning_scene::PlanningSceneConstPtr scene_
 

Detailed Description

Model representing a remote task

filled via TaskDescription + TaskStatistics messages

Definition at line 84 of file remote_task_model.h.

Constructor & Destructor Documentation

◆ RemoteTaskModel()

moveit_rviz_plugin::RemoteTaskModel::RemoteTaskModel ( ros::NodeHandle nh,
const std::string &  service_name,
const planning_scene::PlanningSceneConstPtr &  scene,
rviz::DisplayContext display_context,
QObject *  parent = nullptr 
)

Definition at line 183 of file remote_task_model.cpp.

◆ ~RemoteTaskModel()

moveit_rviz_plugin::RemoteTaskModel::~RemoteTaskModel ( )
override

Definition at line 192 of file remote_task_model.cpp.

Member Function Documentation

◆ data()

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

Definition at line 233 of file remote_task_model.cpp.

◆ getPropertyModel()

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

get property model for given stage index

Implements moveit_rviz_plugin::BaseTaskModel.

Definition at line 438 of file remote_task_model.cpp.

◆ getSolution()

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

get solution for given solution index

Implements moveit_rviz_plugin::BaseTaskModel.

Definition at line 411 of file remote_task_model.cpp.

◆ getSolutionModel() [1/2]

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

get solution model for given stage index

Implements moveit_rviz_plugin::BaseTaskModel.

Definition at line 404 of file remote_task_model.cpp.

◆ getSolutionModel() [2/2]

RemoteSolutionModel * moveit_rviz_plugin::RemoteTaskModel::getSolutionModel ( uint32_t  stage_id) const
inlineprivate

Definition at line 399 of file remote_task_model.cpp.

◆ index() [1/2]

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

Definition at line 169 of file remote_task_model.cpp.

◆ index() [2/2]

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

Definition at line 207 of file remote_task_model.cpp.

◆ indexFromStageId()

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

retrieve model index associated with given stage id

Implements moveit_rviz_plugin::BaseTaskModel.

Definition at line 275 of file remote_task_model.cpp.

◆ node() [1/2]

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

Definition at line 147 of file remote_task_model.cpp.

◆ node() [2/2]

RemoteTaskModel::Node * moveit_rviz_plugin::RemoteTaskModel::node ( uint32_t  stage_id) const
private

Definition at line 163 of file remote_task_model.cpp.

◆ parent()

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

Definition at line 220 of file remote_task_model.cpp.

◆ processSolutionMessage()

DisplaySolutionPtr moveit_rviz_plugin::RemoteTaskModel::processSolutionMessage ( const moveit_task_constructor_msgs::Solution &  msg)

Definition at line 366 of file remote_task_model.cpp.

◆ processStageDescriptions()

void moveit_rviz_plugin::RemoteTaskModel::processStageDescriptions ( const moveit_task_constructor_msgs::TaskDescription::_stages_type &  msg)

Definition at line 280 of file remote_task_model.cpp.

◆ processStageStatistics()

void moveit_rviz_plugin::RemoteTaskModel::processStageStatistics ( const moveit_task_constructor_msgs::TaskStatistics::_stages_type &  msg)

Definition at line 339 of file remote_task_model.cpp.

◆ rowCount()

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

Definition at line 196 of file remote_task_model.cpp.

◆ setData()

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

Definition at line 265 of file remote_task_model.cpp.

◆ setSolutionData()

void moveit_rviz_plugin::RemoteTaskModel::setSolutionData ( const moveit_task_constructor_msgs::SolutionInfo &  info)
private

Definition at line 359 of file remote_task_model.cpp.

Member Data Documentation

◆ get_solution_client_

ros::ServiceClient moveit_rviz_plugin::RemoteTaskModel::get_solution_client_
private

Definition at line 89 of file remote_task_model.h.

◆ id_to_solution_

std::map<uint32_t, DisplaySolutionPtr> moveit_rviz_plugin::RemoteTaskModel::id_to_solution_
private

Definition at line 92 of file remote_task_model.h.

◆ id_to_stage_

std::map<uint32_t, Node*> moveit_rviz_plugin::RemoteTaskModel::id_to_stage_
private

Definition at line 91 of file remote_task_model.h.

◆ root_

Node* const moveit_rviz_plugin::RemoteTaskModel::root_
private

Definition at line 87 of file remote_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