moveit2
The MoveIt Motion Planning Framework for ROS 2.
Public Member Functions | List of all members
moveit_ros_control_interface::Ros2ControlManager Class Reference

moveit_controller_manager::Ros2ControlManager sub class that interfaces one ros_control controller_manager instance. All services and names are relative to ns_. More...

Inheritance diagram for moveit_ros_control_interface::Ros2ControlManager:
Inheritance graph
[legend]
Collaboration diagram for moveit_ros_control_interface::Ros2ControlManager:
Collaboration graph
[legend]

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 ()
 

Detailed Description

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 94 of file controller_manager_plugin.cpp.

Constructor & Destructor Documentation

◆ Ros2ControlManager() [1/2]

moveit_ros_control_interface::Ros2ControlManager::Ros2ControlManager ( )
inline

The default constructor. Reads the namespace from ~ros_control_namespace param and defaults to /.

Definition at line 249 of file controller_manager_plugin.cpp.

◆ Ros2ControlManager() [2/2]

moveit_ros_control_interface::Ros2ControlManager::Ros2ControlManager ( const std::string &  ns)
inline

Configure interface with namespace.

Parameters
nsnamespace of ros_control node (without /controller_manager/)

Definition at line 259 of file controller_manager_plugin.cpp.

Here is the call graph for this function:

Member Function Documentation

◆ fixChainedControllers()

bool moveit_ros_control_interface::Ros2ControlManager::fixChainedControllers ( std::shared_ptr< controller_manager_msgs::srv::ListControllers::Response > &  result)
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 498 of file controller_manager_plugin.cpp.

Here is the call graph for this function:

◆ getActiveControllers()

void moveit_ros_control_interface::Ros2ControlManager::getActiveControllers ( std::vector< std::string > &  names)
inlineoverridevirtual

Refresh controller list and output all active, managed controllers.

Parameters
[out]nameslist of controllers (with namespace)

Implements moveit_controller_manager::MoveItControllerManager.

Definition at line 323 of file controller_manager_plugin.cpp.

◆ getControllerHandle()

moveit_controller_manager::MoveItControllerHandlePtr moveit_ros_control_interface::Ros2ControlManager::getControllerHandle ( const std::string &  name)
inlineoverridevirtual

Find and return the pre-allocated handle for the given controller.

Parameters
name
Returns

Implements moveit_controller_manager::MoveItControllerManager.

Definition at line 292 of file controller_manager_plugin.cpp.

◆ getControllerJoints()

void moveit_ros_control_interface::Ros2ControlManager::getControllerJoints ( const std::string &  name,
std::vector< std::string > &  joints 
)
inlineoverridevirtual

Read interface names required by each controller from the cached controller state info.

Parameters
[in]namename of controller (with namespace)
[out]joints

Implements moveit_controller_manager::MoveItControllerManager.

Definition at line 341 of file controller_manager_plugin.cpp.

◆ getControllersList()

void moveit_ros_control_interface::Ros2ControlManager::getControllersList ( std::vector< std::string > &  names)
inlineoverridevirtual

Refresh controller list and output all managed controllers.

Parameters
[out]nameslist of controllers (with namespace)

Implements moveit_controller_manager::MoveItControllerManager.

Definition at line 307 of file controller_manager_plugin.cpp.

◆ getControllerState()

ControllerState moveit_ros_control_interface::Ros2ControlManager::getControllerState ( const std::string &  name)
inlineoverridevirtual

Refresh controller state and output the state of the given one, only active_ will be set.

Parameters
[in]namename of controller (with namespace)
Returns
state

Implements moveit_controller_manager::MoveItControllerManager.

Definition at line 359 of file controller_manager_plugin.cpp.

◆ initialize()

void moveit_ros_control_interface::Ros2ControlManager::initialize ( const rclcpp::Node::SharedPtr &  node)
inlineoverridevirtual

Implements moveit_controller_manager::MoveItControllerManager.

Definition at line 265 of file controller_manager_plugin.cpp.

Here is the call graph for this function:

◆ switchControllers()

bool moveit_ros_control_interface::Ros2ControlManager::switchControllers ( const std::vector< std::string > &  activate_base,
const std::vector< std::string > &  deactivate_base 
)
inlineoverridevirtual

Filter lists for managed controller and computes switching set. Stopped list might be extended by unsupported controllers that claim needed resources.

Parameters
activatevector of controllers to be activated
deactivatevector of controllers to be deactivated
Returns
true if switching succeeded

Implements moveit_controller_manager::MoveItControllerManager.

Definition at line 380 of file controller_manager_plugin.cpp.


The documentation for this class was generated from the following file: