moveit_controller_manager::MoveItControllerManager sub class that interfaces one ros_control controller_manager instance. All services and names are relative to ns_.
More...
|
| typedef std::map< std::string, ControllerHandleAllocatorPtr > | AllocatorsMap |
| |
| typedef std::map< std::string, controller_manager_msgs::ControllerState > | ControllersMap |
| |
| typedef std::map< std::string, moveit_controller_manager::MoveItControllerHandlePtr > | HandleMap |
| |
|
| void | allocate (const std::string &name, const controller_manager_msgs::ControllerState &controller) |
| | Allocates a MoveItControllerHandle instance for the given controller Might create allocator object first. More...
|
| |
| void | discover (bool force=false) |
| | Call list_controllers and populate managed_controllers_ and active_controllers_. Allocates handles if needed. Throttled down to 1 Hz, controllers_mutex_ must be locked externally. More...
|
| |
| std::string | getAbsName (const std::string &name) |
| | get fully qualified name More...
|
| |
|
| static bool | isActive (const controller_manager_msgs::ControllerState &s) |
| | Check if given controller is active. More...
|
| |
moveit_controller_manager::MoveItControllerManager sub class that interfaces one ros_control controller_manager instance. All services and names are relative to ns_.
Definition at line 116 of file controller_manager_plugin.cpp.
◆ AllocatorsMap
◆ ControllersMap
◆ HandleMap
◆ MoveItControllerManager() [1/2]
| moveit_ros_control_interface::MoveItControllerManager::MoveItControllerManager |
( |
| ) |
|
|
inline |
◆ MoveItControllerManager() [2/2]
| moveit_ros_control_interface::MoveItControllerManager::MoveItControllerManager |
( |
const std::string & |
ns | ) |
|
|
inline |
Configure interface with namespace.
- Parameters
-
| ns | namespace of ros_control node (without /controller_manager/) |
Definition at line 234 of file controller_manager_plugin.cpp.
◆ allocate()
| void moveit_ros_control_interface::MoveItControllerManager::allocate |
( |
const std::string & |
name, |
|
|
const controller_manager_msgs::ControllerState & |
controller |
|
) |
| |
|
inlineprivate |
Allocates a MoveItControllerHandle instance for the given controller Might create allocator object first.
- Parameters
-
| name | fully qualified name of the controller |
| controller | controller information |
Definition at line 181 of file controller_manager_plugin.cpp.
◆ discover()
| void moveit_ros_control_interface::MoveItControllerManager::discover |
( |
bool |
force = false | ) |
|
|
inlineprivate |
Call list_controllers and populate managed_controllers_ and active_controllers_. Allocates handles if needed. Throttled down to 1 Hz, controllers_mutex_ must be locked externally.
- Parameters
-
Definition at line 148 of file controller_manager_plugin.cpp.
◆ getAbsName()
| std::string moveit_ros_control_interface::MoveItControllerManager::getAbsName |
( |
const std::string & |
name | ) |
|
|
inlineprivate |
get fully qualified name
- Parameters
-
| name | name to be resolved to an absolute name |
- Returns
- resolved name
Definition at line 214 of file controller_manager_plugin.cpp.
◆ getActiveControllers()
| void moveit_ros_control_interface::MoveItControllerManager::getActiveControllers |
( |
std::vector< std::string > & |
names | ) |
|
|
inlineoverridevirtual |
◆ getControllerHandle()
| moveit_controller_manager::MoveItControllerHandlePtr moveit_ros_control_interface::MoveItControllerManager::getControllerHandle |
( |
const std::string & |
name | ) |
|
|
inlineoverridevirtual |
◆ getControllerJoints()
| void moveit_ros_control_interface::MoveItControllerManager::getControllerJoints |
( |
const std::string & |
name, |
|
|
std::vector< std::string > & |
joints |
|
) |
| |
|
inlineoverridevirtual |
◆ getControllersList()
| void moveit_ros_control_interface::MoveItControllerManager::getControllersList |
( |
std::vector< std::string > & |
names | ) |
|
|
inlineoverridevirtual |
◆ getControllerState()
| ControllerState moveit_ros_control_interface::MoveItControllerManager::getControllerState |
( |
const std::string & |
name | ) |
|
|
inlineoverridevirtual |
◆ isActive()
| static bool moveit_ros_control_interface::MoveItControllerManager::isActive |
( |
const controller_manager_msgs::ControllerState & |
s | ) |
|
|
inlinestaticprivate |
◆ switchControllers()
| bool moveit_ros_control_interface::MoveItControllerManager::switchControllers |
( |
const std::vector< std::string > & |
activate, |
|
|
const std::vector< std::string > & |
deactivate |
|
) |
| |
|
inlineoverridevirtual |
◆ active_controllers_
| ControllersMap moveit_ros_control_interface::MoveItControllerManager::active_controllers_ |
|
private |
◆ allocators_
| AllocatorsMap moveit_ros_control_interface::MoveItControllerManager::allocators_ |
|
private |
◆ controllers_mutex_
| boost::mutex moveit_ros_control_interface::MoveItControllerManager::controllers_mutex_ |
|
private |
◆ controllers_stamp_
| ros::Time moveit_ros_control_interface::MoveItControllerManager::controllers_stamp_ |
|
private |
◆ handles_
| HandleMap moveit_ros_control_interface::MoveItControllerManager::handles_ |
|
private |
◆ loader_
◆ managed_controllers_
| ControllersMap moveit_ros_control_interface::MoveItControllerManager::managed_controllers_ |
|
private |
◆ ns_
| const std::string moveit_ros_control_interface::MoveItControllerManager::ns_ |
|
private |
The documentation for this class was generated from the following file: