#include <ControllerHandle.h>
Public Member Functions | |
virtual moveit_controller_manager::MoveItControllerHandlePtr | alloc (const std::string &name, const std::vector< std::string > &resources)=0 |
virtual | ~ControllerHandleAllocator () |
Base class for MoveItControllerHandle allocators
Definition at line 50 of file ControllerHandle.h.
virtual moveit_ros_control_interface::ControllerHandleAllocator::~ControllerHandleAllocator | ( | ) | [inline, virtual] |
Definition at line 55 of file ControllerHandle.h.
virtual moveit_controller_manager::MoveItControllerHandlePtr moveit_ros_control_interface::ControllerHandleAllocator::alloc | ( | const std::string & | name, |
const std::vector< std::string > & | resources | ||
) | [pure virtual] |
Implemented in moveit_ros_control_interface::JointTrajectoryControllerAllocator.