moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <start_screen.hpp>
Public Member Functions | |
std::string | getName () const override |
Returns the name of the setup step. More... | |
void | onInit () override |
Overridable initialization method. More... | |
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 | |
SetupStep & | operator= (const SetupStep &)=default |
SetupStep & | operator= (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 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 | |
std::shared_ptr< PackageSettingsConfig > | package_settings_ |
std::shared_ptr< SRDFConfig > | srdf_config_ |
std::shared_ptr< URDFConfig > | urdf_config_ |
Protected Attributes inherited from moveit_setup::SetupStep | |
DataWarehousePtr | config_data_ |
rclcpp::Node::SharedPtr | parent_node_ |
std::shared_ptr< rclcpp::Logger > | logger_ |
Definition at line 45 of file start_screen.hpp.
|
inlineoverridevirtual |
Returns the name of the setup step.
Implements moveit_setup::SetupStep.
Definition at line 48 of file start_screen.hpp.
std::filesystem::path moveit_setup::core::StartScreen::getPackagePath | ( | ) |
std::filesystem::path moveit_setup::core::StartScreen::getURDFPath | ( | ) |
std::string moveit_setup::core::StartScreen::getXacroArgs | ( | ) |
Definition at line 61 of file start_screen.cpp.
bool moveit_setup::core::StartScreen::isXacroFile | ( | ) |
Definition at line 76 of file start_screen.cpp.
void moveit_setup::core::StartScreen::loadExisting | ( | const std::filesystem::path & | package_path | ) |
Definition at line 71 of file start_screen.cpp.
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.
|
overridevirtual |
Overridable initialization method.
Reimplemented from moveit_setup::SetupStep.
Definition at line 43 of file start_screen.cpp.
|
protected |
Definition at line 66 of file start_screen.hpp.
|
protected |
Definition at line 67 of file start_screen.hpp.
|
protected |
Definition at line 68 of file start_screen.hpp.