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

Contains all of the non-GUI code necessary for doing one "screen" worth of setup. More...

#include <setup_step.hpp>

Inheritance diagram for moveit_setup::SetupStep:
Inheritance graph
[legend]

Public Member Functions

 SetupStep ()=default
 
 SetupStep (const SetupStep &)=default
 
 SetupStep (SetupStep &&)=default
 
SetupStepoperator= (const SetupStep &)=default
 
SetupStepoperator= (SetupStep &&)=default
 
virtual ~SetupStep ()=default
 
void initialize (const rclcpp::Node::SharedPtr &parent_node, const DataWarehousePtr &config_data)
 Called after construction to initialize the step. More...
 
virtual void onInit ()
 Overridable initialization method. More...
 
virtual std::string getName () const =0
 Returns the name of the setup step. More...
 
virtual bool isReady () const
 Return true if the data necessary to proceed with this step has been configured. More...
 
const rclcpp::Logger & getLogger () const
 Makes a namespaced logger for this step available to the widget. More...
 

Protected Attributes

DataWarehousePtr config_data_
 
rclcpp::Node::SharedPtr parent_node_
 
std::shared_ptr< rclcpp::Logger > logger_
 

Detailed Description

Contains all of the non-GUI code necessary for doing one "screen" worth of setup.

Definition at line 46 of file setup_step.hpp.

Constructor & Destructor Documentation

◆ SetupStep() [1/3]

moveit_setup::SetupStep::SetupStep ( )
default

◆ SetupStep() [2/3]

moveit_setup::SetupStep::SetupStep ( const SetupStep )
default

◆ SetupStep() [3/3]

moveit_setup::SetupStep::SetupStep ( SetupStep &&  )
default

◆ ~SetupStep()

virtual moveit_setup::SetupStep::~SetupStep ( )
virtualdefault

Member Function Documentation

◆ getLogger()

const rclcpp::Logger& moveit_setup::SetupStep::getLogger ( ) const
inline

Makes a namespaced logger for this step available to the widget.

Definition at line 91 of file setup_step.hpp.

Here is the caller graph for this function:

◆ getName()

virtual std::string moveit_setup::SetupStep::getName ( ) const
pure virtual

◆ initialize()

void moveit_setup::SetupStep::initialize ( const rclcpp::Node::SharedPtr &  parent_node,
const DataWarehousePtr &  config_data 
)
inline

Called after construction to initialize the step.

Parameters
parent_nodeShared pointer to the parent node

Definition at line 60 of file setup_step.hpp.

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

◆ isReady()

virtual bool moveit_setup::SetupStep::isReady ( ) const
inlinevirtual

◆ onInit()

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

◆ operator=() [1/2]

SetupStep& moveit_setup::SetupStep::operator= ( const SetupStep )
default

◆ operator=() [2/2]

SetupStep& moveit_setup::SetupStep::operator= ( SetupStep &&  )
default

Member Data Documentation

◆ config_data_

DataWarehousePtr moveit_setup::SetupStep::config_data_
protected

Definition at line 97 of file setup_step.hpp.

◆ logger_

std::shared_ptr<rclcpp::Logger> moveit_setup::SetupStep::logger_
protected

Definition at line 99 of file setup_step.hpp.

◆ parent_node_

rclcpp::Node::SharedPtr moveit_setup::SetupStep::parent_node_
protected

Definition at line 98 of file setup_step.hpp.


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