moveit2
The MoveIt Motion Planning Framework for ROS 2.
Signals | Public Member Functions | Protected Attributes | List of all members
moveit_setup::SetupStepWidget Class Referenceabstract

The GUI code for one SetupStep. More...

#include <setup_step_widget.hpp>

Inheritance diagram for moveit_setup::SetupStepWidget:
Inheritance graph
[legend]
Collaboration diagram for moveit_setup::SetupStepWidget:
Collaboration graph
[legend]

Signals

void dataUpdated ()
 When the underlying data has been updated (which can cause other steps to become "Ready") More...
 
void advanceRequest ()
 When this signal is received, the GUI should attempt to advance to the next step. More...
 
void setModalMode (bool isModal)
 Event for when the current screen is in modal view. Disables the left navigation. More...
 

Public Member Functions

void initialize (const rclcpp::Node::SharedPtr &parent_node, QWidget *parent_widget, RVizPanel *rviz_panel, const DataWarehousePtr &config_data)
 Called after construction to initialize the step. More...
 
virtual void onInit ()
 
virtual void focusGiven ()
 function called when widget is activated, allows to update/initialize GUI More...
 
virtual bool focusLost ()
 function called when widget loses focus, although switching away can be rejected More...
 
virtual SetupStepgetSetupStep ()=0
 Return a reference to the SetupStep object. More...
 
bool isReady ()
 

Protected Attributes

RVizPanelrviz_panel_
 
bool debug_
 

Detailed Description

The GUI code for one SetupStep.

Definition at line 48 of file setup_step_widget.hpp.

Member Function Documentation

◆ advanceRequest

void moveit_setup::SetupStepWidget::advanceRequest ( )
signal

When this signal is received, the GUI should attempt to advance to the next step.

◆ dataUpdated

void moveit_setup::SetupStepWidget::dataUpdated ( )
signal

When the underlying data has been updated (which can cause other steps to become "Ready")

◆ focusGiven()

virtual void moveit_setup::SetupStepWidget::focusGiven ( )
inlinevirtual

◆ focusLost()

virtual bool moveit_setup::SetupStepWidget::focusLost ( )
inlinevirtual

function called when widget loses focus, although switching away can be rejected

Returns
If the widget should not be switched away from, return false

Reimplemented in moveit_setup::simulation::SimulationWidget, and moveit_setup::app::PerceptionWidget.

Definition at line 85 of file setup_step_widget.hpp.

◆ getSetupStep()

virtual SetupStep& moveit_setup::SetupStepWidget::getSetupStep ( )
pure virtual

◆ initialize()

void moveit_setup::SetupStepWidget::initialize ( const rclcpp::Node::SharedPtr &  parent_node,
QWidget *  parent_widget,
RVizPanel rviz_panel,
const DataWarehousePtr &  config_data 
)
inline

Called after construction to initialize the step.

Parameters
parent_nodeShared pointer to the parent node
parent_widgetPointer to the parent gui element
rviz_panelPointer to the shared rviz panel
config_dataAll the data

Definition at line 59 of file setup_step_widget.hpp.

Here is the call graph for this function:

◆ isReady()

bool moveit_setup::SetupStepWidget::isReady ( )
inline

Definition at line 95 of file setup_step_widget.hpp.

Here is the call graph for this function:

◆ onInit()

virtual void moveit_setup::SetupStepWidget::onInit ( )
inlinevirtual

◆ setModalMode

void moveit_setup::SetupStepWidget::setModalMode ( bool  isModal)
signal

Event for when the current screen is in modal view. Disables the left navigation.

Here is the caller graph for this function:

Member Data Documentation

◆ debug_

bool moveit_setup::SetupStepWidget::debug_
protected

Definition at line 116 of file setup_step_widget.hpp.

◆ rviz_panel_

RVizPanel* moveit_setup::SetupStepWidget::rviz_panel_
protected

Definition at line 115 of file setup_step_widget.hpp.


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