Classes | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
pr2_moveit_controller_manager::Pr2MoveItControllerManager Class Reference
Inheritance diagram for pr2_moveit_controller_manager::Pr2MoveItControllerManager:
Inheritance graph
[legend]

Classes

struct  ControllerInformation
 

Public Member Functions

virtual void getActiveControllers (std::vector< std::string > &names)
 
virtual moveit_controller_manager::MoveItControllerHandlePtr getControllerHandle (const std::string &name)
 
virtual void getControllerJoints (const std::string &name, std::vector< std::string > &joints)
 
virtual void getControllersList (std::vector< std::string > &names)
 
virtual moveit_controller_manager::MoveItControllerManager::ControllerState getControllerState (const std::string &name)
 
 Pr2MoveItControllerManager ()
 
virtual bool switchControllers (const std::vector< std::string > &activate, const std::vector< std::string > &deactivate)
 
virtual ~Pr2MoveItControllerManager ()
 
- Public Member Functions inherited from moveit_controller_manager::MoveItControllerManager
 MoveItControllerManager ()
 
virtual ~MoveItControllerManager ()
 

Protected Member Functions

moveit_controller_manager::MoveItControllerHandlePtr getControllerHandleHelper (const std::string &name, const std::string &ns)
 
const pr2_mechanism_msgs::ListControllers::Response & getListControllerServiceResponse ()
 

Protected Attributes

pr2_mechanism_msgs::ListControllers::Response cached_lister_response_
 
std::string controller_manager_name_
 
std::map< std::string, moveit_controller_manager::MoveItControllerHandlePtr > handle_cache_
 
ros::Time last_lister_response_
 
ros::ServiceClient lister_service_
 
ros::ServiceClient loader_service_
 
ros::NodeHandle node_handle_
 
std::map< std::string, ControllerInformationpossibly_unloaded_controllers_
 
ros::NodeHandle root_node_handle_
 
ros::ServiceClient switcher_service_
 
bool use_controller_manager_
 

Detailed Description

Definition at line 305 of file pr2_moveit_controller_manager.cpp.

Constructor & Destructor Documentation

◆ Pr2MoveItControllerManager()

pr2_moveit_controller_manager::Pr2MoveItControllerManager::Pr2MoveItControllerManager ( )
inline

Definition at line 308 of file pr2_moveit_controller_manager.cpp.

◆ ~Pr2MoveItControllerManager()

virtual pr2_moveit_controller_manager::Pr2MoveItControllerManager::~Pr2MoveItControllerManager ( )
inlinevirtual

Definition at line 428 of file pr2_moveit_controller_manager.cpp.

Member Function Documentation

◆ getActiveControllers()

virtual void pr2_moveit_controller_manager::Pr2MoveItControllerManager::getActiveControllers ( std::vector< std::string > &  names)
inlinevirtual

◆ getControllerHandle()

virtual moveit_controller_manager::MoveItControllerHandlePtr pr2_moveit_controller_manager::Pr2MoveItControllerManager::getControllerHandle ( const std::string &  name)
inlinevirtual

◆ getControllerHandleHelper()

moveit_controller_manager::MoveItControllerHandlePtr pr2_moveit_controller_manager::Pr2MoveItControllerManager::getControllerHandleHelper ( const std::string &  name,
const std::string &  ns 
)
inlineprotected

Definition at line 614 of file pr2_moveit_controller_manager.cpp.

◆ getControllerJoints()

virtual void pr2_moveit_controller_manager::Pr2MoveItControllerManager::getControllerJoints ( const std::string &  name,
std::vector< std::string > &  joints 
)
inlinevirtual

◆ getControllersList()

virtual void pr2_moveit_controller_manager::Pr2MoveItControllerManager::getControllersList ( std::vector< std::string > &  names)
inlinevirtual

◆ getControllerState()

virtual moveit_controller_manager::MoveItControllerManager::ControllerState pr2_moveit_controller_manager::Pr2MoveItControllerManager::getControllerState ( const std::string &  name)
inlinevirtual

◆ getListControllerServiceResponse()

const pr2_mechanism_msgs::ListControllers::Response& pr2_moveit_controller_manager::Pr2MoveItControllerManager::getListControllerServiceResponse ( )
inlineprotected

Definition at line 598 of file pr2_moveit_controller_manager.cpp.

◆ switchControllers()

virtual bool pr2_moveit_controller_manager::Pr2MoveItControllerManager::switchControllers ( const std::vector< std::string > &  activate,
const std::vector< std::string > &  deactivate 
)
inlinevirtual

Member Data Documentation

◆ cached_lister_response_

pr2_mechanism_msgs::ListControllers::Response pr2_moveit_controller_manager::Pr2MoveItControllerManager::cached_lister_response_
protected

Definition at line 644 of file pr2_moveit_controller_manager.cpp.

◆ controller_manager_name_

std::string pr2_moveit_controller_manager::Pr2MoveItControllerManager::controller_manager_name_
protected

Definition at line 637 of file pr2_moveit_controller_manager.cpp.

◆ handle_cache_

std::map<std::string, moveit_controller_manager::MoveItControllerHandlePtr> pr2_moveit_controller_manager::Pr2MoveItControllerManager::handle_cache_
protected

Definition at line 646 of file pr2_moveit_controller_manager.cpp.

◆ last_lister_response_

ros::Time pr2_moveit_controller_manager::Pr2MoveItControllerManager::last_lister_response_
protected

Definition at line 643 of file pr2_moveit_controller_manager.cpp.

◆ lister_service_

ros::ServiceClient pr2_moveit_controller_manager::Pr2MoveItControllerManager::lister_service_
protected

Definition at line 641 of file pr2_moveit_controller_manager.cpp.

◆ loader_service_

ros::ServiceClient pr2_moveit_controller_manager::Pr2MoveItControllerManager::loader_service_
protected

Definition at line 639 of file pr2_moveit_controller_manager.cpp.

◆ node_handle_

ros::NodeHandle pr2_moveit_controller_manager::Pr2MoveItControllerManager::node_handle_
protected

Definition at line 634 of file pr2_moveit_controller_manager.cpp.

◆ possibly_unloaded_controllers_

std::map<std::string, ControllerInformation> pr2_moveit_controller_manager::Pr2MoveItControllerManager::possibly_unloaded_controllers_
protected

Definition at line 658 of file pr2_moveit_controller_manager.cpp.

◆ root_node_handle_

ros::NodeHandle pr2_moveit_controller_manager::Pr2MoveItControllerManager::root_node_handle_
protected

Definition at line 635 of file pr2_moveit_controller_manager.cpp.

◆ switcher_service_

ros::ServiceClient pr2_moveit_controller_manager::Pr2MoveItControllerManager::switcher_service_
protected

Definition at line 640 of file pr2_moveit_controller_manager.cpp.

◆ use_controller_manager_

bool pr2_moveit_controller_manager::Pr2MoveItControllerManager::use_controller_manager_
protected

Definition at line 638 of file pr2_moveit_controller_manager.cpp.


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


pr2_moveit_plugins
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Feb 28 2022 22:51:25