moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Slots | Public Member Functions | Protected Member Functions | List of all members
moveit_rviz_plugin::MotionPlanningFrameJointsWidget Class Reference

#include <motion_planning_frame_joints_widget.h>

Inheritance diagram for moveit_rviz_plugin::MotionPlanningFrameJointsWidget:
Inheritance graph
[legend]
Collaboration diagram for moveit_rviz_plugin::MotionPlanningFrameJointsWidget:
Collaboration graph
[legend]

Public Slots

void queryStartStateChanged ()
 
void queryGoalStateChanged ()
 
void jogNullspace (double value)
 

Public Member Functions

 MotionPlanningFrameJointsWidget (const MotionPlanningFrameJointsWidget &)=delete
 
 MotionPlanningFrameJointsWidget (MotionPlanningDisplay *display, QWidget *parent=nullptr)
 
 ~MotionPlanningFrameJointsWidget () override
 
void clearRobotModel ()
 
void changePlanningGroup (const std::string &group_name, const robot_interaction::InteractionHandlerPtr &start_state_handler, const robot_interaction::InteractionHandlerPtr &goal_state_handler)
 

Protected Member Functions

void setActiveModel (JMGItemModel *model)
 
void triggerUpdate (JMGItemModel *model)
 
void updateNullspaceSliders ()
 
QSlider * createNSSlider (int i)
 

Detailed Description

Definition at line 120 of file motion_planning_frame_joints_widget.h.

Constructor & Destructor Documentation

◆ MotionPlanningFrameJointsWidget() [1/2]

moveit_rviz_plugin::MotionPlanningFrameJointsWidget::MotionPlanningFrameJointsWidget ( const MotionPlanningFrameJointsWidget )
delete

◆ MotionPlanningFrameJointsWidget() [2/2]

moveit_rviz_plugin::MotionPlanningFrameJointsWidget::MotionPlanningFrameJointsWidget ( MotionPlanningDisplay display,
QWidget *  parent = nullptr 
)

Definition at line 193 of file motion_planning_frame_joints_widget.cpp.

◆ ~MotionPlanningFrameJointsWidget()

moveit_rviz_plugin::MotionPlanningFrameJointsWidget::~MotionPlanningFrameJointsWidget ( )
override

Definition at line 203 of file motion_planning_frame_joints_widget.cpp.

Member Function Documentation

◆ changePlanningGroup()

void moveit_rviz_plugin::MotionPlanningFrameJointsWidget::changePlanningGroup ( const std::string &  group_name,
const robot_interaction::InteractionHandlerPtr &  start_state_handler,
const robot_interaction::InteractionHandlerPtr &  goal_state_handler 
)

Definition at line 217 of file motion_planning_frame_joints_widget.cpp.

Here is the call graph for this function:

◆ clearRobotModel()

void moveit_rviz_plugin::MotionPlanningFrameJointsWidget::clearRobotModel ( )

Definition at line 208 of file motion_planning_frame_joints_widget.cpp.

Here is the caller graph for this function:

◆ createNSSlider()

QSlider * moveit_rviz_plugin::MotionPlanningFrameJointsWidget::createNSSlider ( int  i)
protected

Definition at line 363 of file motion_planning_frame_joints_widget.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ jogNullspace

void moveit_rviz_plugin::MotionPlanningFrameJointsWidget::jogNullspace ( double  value)
slot

Definition at line 374 of file motion_planning_frame_joints_widget.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ queryGoalStateChanged

void moveit_rviz_plugin::MotionPlanningFrameJointsWidget::queryGoalStateChanged ( )
slot

Definition at line 255 of file motion_planning_frame_joints_widget.cpp.

Here is the call graph for this function:

◆ queryStartStateChanged

void moveit_rviz_plugin::MotionPlanningFrameJointsWidget::queryStartStateChanged ( )
slot

Definition at line 244 of file motion_planning_frame_joints_widget.cpp.

Here is the call graph for this function:

◆ setActiveModel()

void moveit_rviz_plugin::MotionPlanningFrameJointsWidget::setActiveModel ( JMGItemModel model)
protected

Definition at line 266 of file motion_planning_frame_joints_widget.cpp.

Here is the caller graph for this function:

◆ triggerUpdate()

void moveit_rviz_plugin::MotionPlanningFrameJointsWidget::triggerUpdate ( JMGItemModel model)
protected

Definition at line 273 of file motion_planning_frame_joints_widget.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ updateNullspaceSliders()

void moveit_rviz_plugin::MotionPlanningFrameJointsWidget::updateNullspaceSliders ( )
protected

Definition at line 312 of file motion_planning_frame_joints_widget.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

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