moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
MoveIt does not enforce how controllers are implemented. To make your controllers usable by MoveIt, this interface needs to be implemented. The main purpose of this interface is to expose the set of known controllers and potentially to allow activating and deactivating them, if multiple controllers are available. More...
#include <controller_manager.h>
Classes | |
struct | ControllerState |
Each controller known to MoveIt has a state. This structure describes that controller's state. More... | |
Public Member Functions | |
MoveItControllerManager () | |
Default constructor. This needs to have no arguments so that the plugin system can construct the object. More... | |
virtual | ~MoveItControllerManager () |
virtual void | initialize (const rclcpp::Node::SharedPtr &node)=0 |
virtual MoveItControllerHandlePtr | getControllerHandle (const std::string &name)=0 |
Return a given named controller. More... | |
virtual void | getControllersList (std::vector< std::string > &names)=0 |
Get the list of known controller names. More... | |
virtual void | getActiveControllers (std::vector< std::string > &names)=0 |
Get the list of active controllers. More... | |
virtual void | getControllerJoints (const std::string &name, std::vector< std::string > &joints)=0 |
Report the joints a controller operates on, given the controller name. More... | |
virtual ControllerState | getControllerState (const std::string &name)=0 |
Report the state of a controller, given its name. More... | |
virtual bool | switchControllers (const std::vector< std::string > &activate, const std::vector< std::string > &deactivate)=0 |
Activate and deactivate controllers. More... | |
MoveIt does not enforce how controllers are implemented. To make your controllers usable by MoveIt, this interface needs to be implemented. The main purpose of this interface is to expose the set of known controllers and potentially to allow activating and deactivating them, if multiple controllers are available.
Definition at line 157 of file controller_manager.h.
|
inline |
Default constructor. This needs to have no arguments so that the plugin system can construct the object.
Definition at line 178 of file controller_manager.h.
|
inlinevirtual |
Definition at line 182 of file controller_manager.h.
|
pure virtual |
Get the list of active controllers.
If there is only one controller in the system, this will be active. When multiple controllers exist, and they operate on overlapping sets of joints, not all controllers should be active at the same time.
Implemented in moveit_simple_controller_manager::MoveItSimpleControllerManager, moveit_ros_control_interface::Ros2ControlMultiManager, and moveit_ros_control_interface::Ros2ControlManager.
|
pure virtual |
Return a given named controller.
Implemented in moveit_simple_controller_manager::MoveItSimpleControllerManager, moveit_ros_control_interface::Ros2ControlMultiManager, and moveit_ros_control_interface::Ros2ControlManager.
|
pure virtual |
Report the joints a controller operates on, given the controller name.
In order to decide which controller to use, it is necessary to reason about the joints a controller operates on.
Implemented in moveit_simple_controller_manager::MoveItSimpleControllerManager, moveit_ros_control_interface::Ros2ControlMultiManager, and moveit_ros_control_interface::Ros2ControlManager.
|
pure virtual |
Get the list of known controller names.
Implemented in moveit_simple_controller_manager::MoveItSimpleControllerManager, moveit_ros_control_interface::Ros2ControlMultiManager, and moveit_ros_control_interface::Ros2ControlManager.
|
pure virtual |
Report the state of a controller, given its name.
Implemented in moveit_simple_controller_manager::MoveItSimpleControllerManager, moveit_ros_control_interface::Ros2ControlMultiManager, and moveit_ros_control_interface::Ros2ControlManager.
|
pure virtual |
|
pure virtual |
Activate and deactivate controllers.
Implemented in moveit_ros_control_interface::Ros2ControlManager, moveit_ros_control_interface::Ros2ControlMultiManager, and moveit_simple_controller_manager::MoveItSimpleControllerManager.