moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Public Member Functions | Protected Attributes | List of all members
moveit_setup::core::StartScreen Class Reference

#include <start_screen.hpp>

Inheritance diagram for moveit_setup::core::StartScreen:
Inheritance graph
[legend]
Collaboration diagram for moveit_setup::core::StartScreen:
Collaboration graph
[legend]

Public Member Functions

std::string getName () const override
 Returns the name of the setup step.
 
void onInit () override
 Overridable initialization method.
 
std::filesystem::path getURDFPath ()
 
std::string getXacroArgs ()
 
std::filesystem::path getPackagePath ()
 
bool isXacroFile ()
 
void loadURDFFile (const std::filesystem::path &urdf_file_path, const std::string &xacro_args)
 
void loadExisting (const std::filesystem::path &package_path)
 
- Public Member Functions inherited from moveit_setup::SetupStep
 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.
 
virtual bool isReady () const
 Return true if the data necessary to proceed with this step has been configured.
 
const rclcpp::Logger & getLogger () const
 Makes a namespaced logger for this step available to the widget.
 

Protected Attributes

std::shared_ptr< PackageSettingsConfigpackage_settings_
 
std::shared_ptr< SRDFConfigsrdf_config_
 
std::shared_ptr< URDFConfigurdf_config_
 
- Protected Attributes inherited from moveit_setup::SetupStep
DataWarehousePtr config_data_
 
rclcpp::Node::SharedPtr parent_node_
 
std::shared_ptr< rclcpp::Logger > logger_
 

Detailed Description

Definition at line 45 of file start_screen.hpp.

Member Function Documentation

◆ getName()

std::string moveit_setup::core::StartScreen::getName ( ) const
inlineoverridevirtual

Returns the name of the setup step.

Implements moveit_setup::SetupStep.

Definition at line 48 of file start_screen.hpp.

◆ getPackagePath()

std::filesystem::path moveit_setup::core::StartScreen::getPackagePath ( )

Definition at line 66 of file start_screen.cpp.

Here is the caller graph for this function:

◆ getURDFPath()

std::filesystem::path moveit_setup::core::StartScreen::getURDFPath ( )

Definition at line 56 of file start_screen.cpp.

Here is the caller graph for this function:

◆ getXacroArgs()

std::string moveit_setup::core::StartScreen::getXacroArgs ( )

Definition at line 61 of file start_screen.cpp.

◆ isXacroFile()

bool moveit_setup::core::StartScreen::isXacroFile ( )

Definition at line 76 of file start_screen.cpp.

◆ loadExisting()

void moveit_setup::core::StartScreen::loadExisting ( const std::filesystem::path &  package_path)

Definition at line 71 of file start_screen.cpp.

◆ loadURDFFile()

void moveit_setup::core::StartScreen::loadURDFFile ( const std::filesystem::path &  urdf_file_path,
const std::string &  xacro_args 
)

Definition at line 50 of file start_screen.cpp.

Here is the call graph for this function:

◆ onInit()

void moveit_setup::core::StartScreen::onInit ( )
overridevirtual

Overridable initialization method.

Reimplemented from moveit_setup::SetupStep.

Definition at line 43 of file start_screen.cpp.

Member Data Documentation

◆ package_settings_

std::shared_ptr<PackageSettingsConfig> moveit_setup::core::StartScreen::package_settings_
protected

Definition at line 66 of file start_screen.hpp.

◆ srdf_config_

std::shared_ptr<SRDFConfig> moveit_setup::core::StartScreen::srdf_config_
protected

Definition at line 67 of file start_screen.hpp.

◆ urdf_config_

std::shared_ptr<URDFConfig> moveit_setup::core::StartScreen::urdf_config_
protected

Definition at line 68 of file start_screen.hpp.


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