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

#include <motion_planning_frame_joints_widget.h>

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

Public Member Functions

int columnCount (const QModelIndex &parent=QModelIndex()) const override
 
QVariant data (const QModelIndex &index, int role) const override
 
Qt::ItemFlags flags (const QModelIndex &index) const override
 
const moveit::core::JointModelGroupgetJointModelGroup () const
 
moveit::core::RobotStategetRobotState ()
 
const moveit::core::RobotStategetRobotState () const
 
QVariant headerData (int section, Qt::Orientation orientation, int role) const override
 
 JMGItemModel (const moveit::core::RobotState &robot_state, const std::string &group_name, QObject *parent=nullptr)
 
int rowCount (const QModelIndex &parent=QModelIndex()) const override
 
bool setData (const QModelIndex &index, const QVariant &value, int role) override
 
void updateRobotState (const moveit::core::RobotState &state)
 call this on any external change of the RobotState More...
 

Private Member Functions

const moveit::core::JointModelgetJointModel (const QModelIndex &index) const
 retrieve the JointModel corresponding to the variable referenced by index More...
 
const moveit::core::VariableBoundsgetVariableBounds (const moveit::core::JointModel *jm, const QModelIndex &index) const
 retrieve the variable bounds referenced by variable index More...
 

Private Attributes

const moveit::core::JointModelGroupjmg_
 
moveit::core::RobotState robot_state_
 

Detailed Description

TableModel to display joint values of a referenced RobotState.

Unfortunately we cannot store the RobotStatePtr (and thus ensure existence of the state during the lifetime of this class instance), because RobotInteraction (which is the initial use case) allocates internally a new RobotState if any other copy is held somewhere else. Hence, we also store an (unsafe) raw pointer. Lifetime of this raw pointer needs to be ensured.

Definition at line 67 of file motion_planning_frame_joints_widget.h.

Constructor & Destructor Documentation

◆ JMGItemModel()

moveit_rviz_plugin::JMGItemModel::JMGItemModel ( const moveit::core::RobotState robot_state,
const std::string &  group_name,
QObject *  parent = nullptr 
)

Definition at line 80 of file motion_planning_frame_joints_widget.cpp.

Member Function Documentation

◆ columnCount()

int moveit_rviz_plugin::JMGItemModel::columnCount ( const QModelIndex &  parent = QModelIndex()) const
override

Definition at line 95 of file motion_planning_frame_joints_widget.cpp.

◆ data()

QVariant moveit_rviz_plugin::JMGItemModel::data ( const QModelIndex &  index,
int  role 
) const
override

Definition at line 115 of file motion_planning_frame_joints_widget.cpp.

◆ flags()

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

Definition at line 100 of file motion_planning_frame_joints_widget.cpp.

◆ getJointModel()

const moveit::core::JointModel * moveit_rviz_plugin::JMGItemModel::getJointModel ( const QModelIndex &  index) const
private

retrieve the JointModel corresponding to the variable referenced by index

Definition at line 206 of file motion_planning_frame_joints_widget.cpp.

◆ getJointModelGroup()

const moveit::core::JointModelGroup* moveit_rviz_plugin::JMGItemModel::getJointModelGroup ( ) const
inline

Definition at line 95 of file motion_planning_frame_joints_widget.h.

◆ getRobotState() [1/2]

moveit::core::RobotState& moveit_rviz_plugin::JMGItemModel::getRobotState ( )
inline

Definition at line 87 of file motion_planning_frame_joints_widget.h.

◆ getRobotState() [2/2]

const moveit::core::RobotState& moveit_rviz_plugin::JMGItemModel::getRobotState ( ) const
inline

Definition at line 91 of file motion_planning_frame_joints_widget.h.

◆ getVariableBounds()

const moveit::core::VariableBounds * moveit_rviz_plugin::JMGItemModel::getVariableBounds ( const moveit::core::JointModel jm,
const QModelIndex &  index 
) const
private

retrieve the variable bounds referenced by variable index

Definition at line 214 of file motion_planning_frame_joints_widget.cpp.

◆ headerData()

QVariant moveit_rviz_plugin::JMGItemModel::headerData ( int  section,
Qt::Orientation  orientation,
int  role 
) const
override

Definition at line 170 of file motion_planning_frame_joints_widget.cpp.

◆ rowCount()

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

Definition at line 87 of file motion_planning_frame_joints_widget.cpp.

◆ setData()

bool moveit_rviz_plugin::JMGItemModel::setData ( const QModelIndex &  index,
const QVariant &  value,
int  role 
)
override

Definition at line 177 of file motion_planning_frame_joints_widget.cpp.

◆ updateRobotState()

void moveit_rviz_plugin::JMGItemModel::updateRobotState ( const moveit::core::RobotState state)

call this on any external change of the RobotState

Definition at line 225 of file motion_planning_frame_joints_widget.cpp.

Member Data Documentation

◆ jmg_

const moveit::core::JointModelGroup* moveit_rviz_plugin::JMGItemModel::jmg_
private

Definition at line 71 of file motion_planning_frame_joints_widget.h.

◆ robot_state_

moveit::core::RobotState moveit_rviz_plugin::JMGItemModel::robot_state_
private

Definition at line 70 of file motion_planning_frame_joints_widget.h.


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


visualization
Author(s): Ioan Sucan , Dave Coleman , Sachin Chitta
autogenerated on Thu Feb 27 2025 03:29:15