51 return "ROS 2 Controllers";
56 config_data_->registerType(
"ros2_controllers",
"moveit_setup::controllers::ROS2ControllersConfig");
57 config_data_->registerType(
"control_xacro",
"moveit_setup::controllers::ControlXacroConfig");
64 return "Configure ros2_controllers. By default, ros2_control fake_components are used to create a simple "
70 return "Auto Add &JointTrajectoryController \n Controllers For Each Planning Group";
75 return {
"joint_trajectory_controller/JointTrajectoryController",
"position_controllers/GripperActionController" };
80 return "joint_trajectory_controller/JointTrajectoryController";
DataWarehousePtr config_data_
std::shared_ptr< SRDFConfig > srdf_config_
std::shared_ptr< ControllersConfig > controllers_config_
std::string getDefaultType() const override
std::string getName() const override
Returns the name of the setup step.
void onInit() override
Overridable initialization method.
std::vector< std::string > getAvailableTypes() const override
std::string getInstructions() const override
std::string getButtonText() const override