#include <motion_planning_frame_joints_widget.h>
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::JointModelGroup * | getJointModelGroup () const |
moveit::core::RobotState & | getRobotState () |
const moveit::core::RobotState & | getRobotState () 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::JointModel * | getJointModel (const QModelIndex &index) const |
retrieve the JointModel corresponding to the variable referenced by index More... | |
const moveit::core::VariableBounds * | getVariableBounds (const moveit::core::JointModel *jm, const QModelIndex &index) const |
retrieve the variable bounds referenced by variable index More... | |
Private Attributes | |
const moveit::core::JointModelGroup * | jmg_ |
moveit::core::RobotState | robot_state_ |
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.
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.
|
override |
Definition at line 95 of file motion_planning_frame_joints_widget.cpp.
|
override |
Definition at line 115 of file motion_planning_frame_joints_widget.cpp.
|
override |
Definition at line 100 of file motion_planning_frame_joints_widget.cpp.
|
private |
retrieve the JointModel corresponding to the variable referenced by index
Definition at line 206 of file motion_planning_frame_joints_widget.cpp.
|
inline |
Definition at line 95 of file motion_planning_frame_joints_widget.h.
|
inline |
Definition at line 87 of file motion_planning_frame_joints_widget.h.
|
inline |
Definition at line 91 of file motion_planning_frame_joints_widget.h.
|
private |
retrieve the variable bounds referenced by variable index
Definition at line 214 of file motion_planning_frame_joints_widget.cpp.
|
override |
Definition at line 170 of file motion_planning_frame_joints_widget.cpp.
|
override |
Definition at line 87 of file motion_planning_frame_joints_widget.cpp.
|
override |
Definition at line 177 of file motion_planning_frame_joints_widget.cpp.
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.
|
private |
Definition at line 71 of file motion_planning_frame_joints_widget.h.
|
private |
Definition at line 70 of file motion_planning_frame_joints_widget.h.