moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
moveit_controller_manager::Ros2ControlManager sub class that interfaces one ros_control controller_manager instance. All services and names are relative to ns_. More...
Public Member Functions | |
Ros2ControlManager () | |
The default constructor. Reads the namespace from ~ros_control_namespace param and defaults to /. More... | |
Ros2ControlManager (const std::string &ns) | |
Configure interface with namespace. More... | |
void | initialize (const rclcpp::Node::SharedPtr &node) override |
moveit_controller_manager::MoveItControllerHandlePtr | getControllerHandle (const std::string &name) override |
Find and return the pre-allocated handle for the given controller. More... | |
void | getControllersList (std::vector< std::string > &names) override |
Refresh controller list and output all managed controllers. More... | |
void | getActiveControllers (std::vector< std::string > &names) override |
Refresh controller list and output all active, managed controllers. More... | |
void | getControllerJoints (const std::string &name, std::vector< std::string > &joints) override |
Read interface names required by each controller from the cached controller state info. More... | |
ControllerState | getControllerState (const std::string &name) override |
Refresh controller state and output the state of the given one, only active_ will be set. More... | |
bool | switchControllers (const std::vector< std::string > &activate_base, const std::vector< std::string > &deactivate_base) override |
Filter lists for managed controller and computes switching set. Stopped list might be extended by unsupported controllers that claim needed resources. More... | |
bool | fixChainedControllers (std::shared_ptr< controller_manager_msgs::srv::ListControllers::Response > &result) |
fixChainedControllers modifies ListControllers service response if it contains chained controllers. Since chained controllers cannot be written to directly, they are removed from the response and their interfaces are propagated back to the first controller with a non-chained input More... | |
Public Member Functions inherited from moveit_controller_manager::MoveItControllerManager | |
MoveItControllerManager () | |
Default constructor. This needs to have no arguments so that the plugin system can construct the object. More... | |
virtual | ~MoveItControllerManager () |
moveit_controller_manager::Ros2ControlManager sub class that interfaces one ros_control controller_manager instance. All services and names are relative to ns_.
Definition at line 85 of file controller_manager_plugin.cpp.
|
inline |
The default constructor. Reads the namespace from ~ros_control_namespace param and defaults to /.
Definition at line 238 of file controller_manager_plugin.cpp.
|
inline |
Configure interface with namespace.
ns | namespace of ros_control node (without /controller_manager/) |
Definition at line 248 of file controller_manager_plugin.cpp.
|
inline |
fixChainedControllers modifies ListControllers service response if it contains chained controllers. Since chained controllers cannot be written to directly, they are removed from the response and their interfaces are propagated back to the first controller with a non-chained input
Definition at line 474 of file controller_manager_plugin.cpp.
|
inlineoverridevirtual |
Refresh controller list and output all active, managed controllers.
[out] | names | list of controllers (with namespace) |
Implements moveit_controller_manager::MoveItControllerManager.
Definition at line 317 of file controller_manager_plugin.cpp.
|
inlineoverridevirtual |
Find and return the pre-allocated handle for the given controller.
name |
Implements moveit_controller_manager::MoveItControllerManager.
Definition at line 286 of file controller_manager_plugin.cpp.
|
inlineoverridevirtual |
Read interface names required by each controller from the cached controller state info.
[in] | name | name of controller (with namespace) |
[out] | joints |
Implements moveit_controller_manager::MoveItControllerManager.
Definition at line 335 of file controller_manager_plugin.cpp.
|
inlineoverridevirtual |
Refresh controller list and output all managed controllers.
[out] | names | list of controllers (with namespace) |
Implements moveit_controller_manager::MoveItControllerManager.
Definition at line 301 of file controller_manager_plugin.cpp.
|
inlineoverridevirtual |
Refresh controller state and output the state of the given one, only active_ will be set.
[in] | name | name of controller (with namespace) |
Implements moveit_controller_manager::MoveItControllerManager.
Definition at line 353 of file controller_manager_plugin.cpp.
|
inlineoverridevirtual |
Implements moveit_controller_manager::MoveItControllerManager.
Definition at line 253 of file controller_manager_plugin.cpp.
|
inlineoverridevirtual |
Filter lists for managed controller and computes switching set. Stopped list might be extended by unsupported controllers that claim needed resources.
activate | |
deactivate |
Implements moveit_controller_manager::MoveItControllerManager.
Definition at line 374 of file controller_manager_plugin.cpp.