moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Contains all of the non-GUI code necessary for doing one "screen" worth of setup. More...
#include <setup_step.hpp>
Public Member Functions | |
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 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_ |
Contains all of the non-GUI code necessary for doing one "screen" worth of setup.
Definition at line 46 of file setup_step.hpp.
|
default |
|
default |
|
default |
|
virtualdefault |
|
inline |
Makes a namespaced logger for this step available to the widget.
Definition at line 91 of file setup_step.hpp.
|
pure virtual |
Returns the name of the setup step.
Implemented in moveit_setup::srdf_setup::VirtualJoints, moveit_setup::srdf_setup::RobotPoses, moveit_setup::srdf_setup::PlanningGroups, moveit_setup::srdf_setup::PassiveJoints, moveit_setup::srdf_setup::EndEffectors, moveit_setup::srdf_setup::DefaultCollisions, moveit_setup::simulation::Simulation, moveit_setup::core::StartScreen, moveit_setup::core::ConfigurationFiles, moveit_setup::core::AuthorInformation, moveit_setup::controllers::UrdfModifications, moveit_setup::controllers::ROS2Controllers, moveit_setup::controllers::MoveItControllers, moveit_setup::app::Perception, and moveit_setup::app::Launches.
|
inline |
Called after construction to initialize the step.
parent_node | Shared pointer to the parent node |
Definition at line 60 of file setup_step.hpp.
|
inlinevirtual |
Return true if the data necessary to proceed with this step has been configured.
Reimplemented in moveit_setup::srdf_setup::SRDFStep, moveit_setup::srdf_setup::RobotPoses, moveit_setup::srdf_setup::EndEffectors, moveit_setup::simulation::Simulation, moveit_setup::core::AuthorInformation, moveit_setup::controllers::UrdfModifications, moveit_setup::controllers::Controllers, moveit_setup::app::Perception, and moveit_setup::app::Launches.
Definition at line 83 of file setup_step.hpp.
|
inlinevirtual |
Overridable initialization method.
Reimplemented in moveit_setup::srdf_setup::VirtualJoints, moveit_setup::srdf_setup::SRDFStep, moveit_setup::srdf_setup::RobotPoses, moveit_setup::srdf_setup::PlanningGroups, moveit_setup::srdf_setup::EndEffectors, moveit_setup::simulation::Simulation, moveit_setup::core::StartScreen, moveit_setup::core::ConfigurationFiles, moveit_setup::core::AuthorInformation, moveit_setup::controllers::UrdfModifications, moveit_setup::controllers::ROS2Controllers, moveit_setup::controllers::MoveItControllers, moveit_setup::app::Perception, and moveit_setup::app::Launches.
Definition at line 71 of file setup_step.hpp.
|
protected |
Definition at line 97 of file setup_step.hpp.
|
protected |
Definition at line 99 of file setup_step.hpp.
|
protected |
Definition at line 98 of file setup_step.hpp.