The GUI code for one SetupStep.
More...
#include <setup_step_widget.hpp>
|
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...
|
|
|
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 SetupStep & | getSetupStep ()=0 |
| Return a reference to the SetupStep object. More...
|
|
bool | isReady () |
|
The GUI code for one SetupStep.
Definition at line 48 of file setup_step_widget.hpp.
◆ 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 |
function called when widget is activated, allows to update/initialize GUI
Reimplemented in moveit_setup::srdf_setup::VirtualJointsWidget, moveit_setup::srdf_setup::RobotPosesWidget, moveit_setup::srdf_setup::PlanningGroupsWidget, moveit_setup::srdf_setup::PassiveJointsWidget, moveit_setup::srdf_setup::EndEffectorsWidget, moveit_setup::simulation::SimulationWidget, moveit_setup::core::StartScreenWidget, moveit_setup::core::ConfigurationFilesWidget, moveit_setup::core::AuthorInformationWidget, moveit_setup::controllers::UrdfModificationsWidget, moveit_setup::controllers::ControllersWidget, moveit_setup::app::PerceptionWidget, and moveit_setup::app::LaunchesWidget.
Definition at line 76 of file setup_step_widget.hpp.
◆ focusLost()
virtual bool moveit_setup::SetupStepWidget::focusLost |
( |
| ) |
|
|
inlinevirtual |
◆ getSetupStep()
virtual SetupStep& moveit_setup::SetupStepWidget::getSetupStep |
( |
| ) |
|
|
pure virtual |
Return a reference to the SetupStep object.
Implemented in moveit_setup::srdf_setup::VirtualJointsWidget, moveit_setup::srdf_setup::RobotPosesWidget, moveit_setup::srdf_setup::PlanningGroupsWidget, moveit_setup::srdf_setup::PassiveJointsWidget, moveit_setup::srdf_setup::EndEffectorsWidget, moveit_setup::srdf_setup::DefaultCollisionsWidget, moveit_setup::simulation::SimulationWidget, moveit_setup::core::StartScreenWidget, moveit_setup::core::ConfigurationFilesWidget, moveit_setup::core::AuthorInformationWidget, moveit_setup::controllers::UrdfModificationsWidget, moveit_setup::controllers::ControllersWidget, moveit_setup::app::PerceptionWidget, and moveit_setup::app::LaunchesWidget.
◆ 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_node | Shared pointer to the parent node |
parent_widget | Pointer to the parent gui element |
rviz_panel | Pointer to the shared rviz panel |
config_data | All the data |
Definition at line 59 of file setup_step_widget.hpp.
◆ isReady()
bool moveit_setup::SetupStepWidget::isReady |
( |
| ) |
|
|
inline |
◆ onInit()
virtual void moveit_setup::SetupStepWidget::onInit |
( |
| ) |
|
|
inlinevirtual |
Reimplemented in moveit_setup::srdf_setup::VirtualJointsWidget, moveit_setup::srdf_setup::RobotPosesWidget, moveit_setup::srdf_setup::PlanningGroupsWidget, moveit_setup::srdf_setup::PassiveJointsWidget, moveit_setup::srdf_setup::EndEffectorsWidget, moveit_setup::srdf_setup::DefaultCollisionsWidget, moveit_setup::simulation::SimulationWidget, moveit_setup::core::StartScreenWidget, moveit_setup::core::ConfigurationFilesWidget, moveit_setup::core::AuthorInformationWidget, moveit_setup::controllers::UrdfModificationsWidget, moveit_setup::controllers::ControllersWidget, moveit_setup::app::PerceptionWidget, and moveit_setup::app::LaunchesWidget.
Definition at line 69 of file setup_step_widget.hpp.
◆ setModalMode
void moveit_setup::SetupStepWidget::setModalMode |
( |
bool |
isModal | ) |
|
|
signal |
Event for when the current screen is in modal view. Disables the left navigation.
◆ debug_
bool moveit_setup::SetupStepWidget::debug_ |
|
protected |
◆ rviz_panel_
RVizPanel* moveit_setup::SetupStepWidget::rviz_panel_ |
|
protected |
The documentation for this class was generated from the following file: