#include <action_based_controller_handle.h>
Public Member Functions | |
ActionBasedControllerHandle (const std::string &name, const std::string &ns) | |
virtual void | addJoint (const std::string &name) |
virtual bool | cancelExecution () |
virtual void | getJoints (std::vector< std::string > &joints) |
virtual moveit_controller_manager::ExecutionStatus | getLastExecutionStatus () |
bool | isConnected () const |
virtual bool | waitForExecution (const ros::Duration &timeout=ros::Duration(0)) |
Public Member Functions inherited from moveit_simple_controller_manager::ActionBasedControllerHandleBase | |
ActionBasedControllerHandleBase (const std::string &name) | |
Public Member Functions inherited from moveit_controller_manager::MoveItControllerHandle | |
const std::string & | getName () const |
MoveItControllerHandle (const std::string &name) | |
virtual bool | sendTrajectory (const moveit_msgs::RobotTrajectory &trajectory)=0 |
virtual | ~MoveItControllerHandle () |
Protected Member Functions | |
void | finishControllerExecution (const actionlib::SimpleClientGoalState &state) |
std::string | getActionName (void) const |
Protected Attributes | |
std::shared_ptr< actionlib::SimpleActionClient< T > > | controller_action_client_ |
bool | done_ |
std::vector< std::string > | joints_ |
moveit_controller_manager::ExecutionStatus | last_exec_ |
std::string | namespace_ |
ros::NodeHandle | nh_ |
Protected Attributes inherited from moveit_controller_manager::MoveItControllerHandle | |
std::string | name_ |
Definition at line 68 of file action_based_controller_handle.h.
|
inline |
Definition at line 71 of file action_based_controller_handle.h.
|
inlinevirtual |
Implements moveit_simple_controller_manager::ActionBasedControllerHandleBase.
Definition at line 135 of file action_based_controller_handle.h.
|
inlinevirtual |
Implements moveit_controller_manager::MoveItControllerHandle.
Definition at line 109 of file action_based_controller_handle.h.
|
inlineprotected |
Definition at line 155 of file action_based_controller_handle.h.
|
inlineprotected |
Definition at line 147 of file action_based_controller_handle.h.
|
inlinevirtual |
Implements moveit_simple_controller_manager::ActionBasedControllerHandleBase.
Definition at line 140 of file action_based_controller_handle.h.
|
inlinevirtual |
Implements moveit_controller_manager::MoveItControllerHandle.
Definition at line 130 of file action_based_controller_handle.h.
|
inline |
Definition at line 104 of file action_based_controller_handle.h.
|
inlinevirtual |
Implements moveit_controller_manager::MoveItControllerHandle.
Definition at line 123 of file action_based_controller_handle.h.
|
protected |
Definition at line 182 of file action_based_controller_handle.h.
|
protected |
Definition at line 172 of file action_based_controller_handle.h.
|
protected |
Definition at line 179 of file action_based_controller_handle.h.
|
protected |
Definition at line 171 of file action_based_controller_handle.h.
|
protected |
Definition at line 176 of file action_based_controller_handle.h.
|
protected |
Definition at line 146 of file action_based_controller_handle.h.