Public Member Functions | Protected Attributes
moveit_controller_manager::MoveItControllerHandle Class Reference

MoveIt sends commands to a controller via a handle that satisfies this interface. More...

#include <controller_manager.h>

List of all members.

Public Member Functions

virtual bool cancelExecution ()=0
 Cancel the execution of any motion using this controller. Report false if canceling is not possible. If there is no execution in progress, this function is a no-op and returns true.
virtual ExecutionStatus getLastExecutionStatus ()=0
 Return the execution status of the last trajectory sent to the controller.
const std::string & getName () const
 Get the name of the controller this handle can send commands to.
 MoveItControllerHandle (const std::string &name)
 Each controller has a name. The handle is initialized with that name.
virtual bool sendTrajectory (const moveit_msgs::RobotTrajectory &trajectory)=0
 Send a trajectory to the controller. The controller is expected to execute the trajectory, but this function call should not block. Blocking is achievable by calling waitForExecution(). Return false when the controller cannot accept the trajectory.
virtual bool waitForExecution (const ros::Duration &timeout=ros::Duration(0))=0
 Wait for the current execution to complete, or until the timeout is reached. Return true if the execution is complete (whether successful or not). Return false if timeout was reached. If timeout is 0 (default argument), wait until the execution is complete (no timeout).
virtual ~MoveItControllerHandle ()

Protected Attributes

std::string name_

Detailed Description

MoveIt sends commands to a controller via a handle that satisfies this interface.

Definition at line 97 of file controller_manager.h.


Constructor & Destructor Documentation

Each controller has a name. The handle is initialized with that name.

Definition at line 102 of file controller_manager.h.

Definition at line 106 of file controller_manager.h.


Member Function Documentation

Cancel the execution of any motion using this controller. Report false if canceling is not possible. If there is no execution in progress, this function is a no-op and returns true.

Return the execution status of the last trajectory sent to the controller.

const std::string& moveit_controller_manager::MoveItControllerHandle::getName ( ) const [inline]

Get the name of the controller this handle can send commands to.

Definition at line 111 of file controller_manager.h.

virtual bool moveit_controller_manager::MoveItControllerHandle::sendTrajectory ( const moveit_msgs::RobotTrajectory &  trajectory) [pure virtual]

Send a trajectory to the controller. The controller is expected to execute the trajectory, but this function call should not block. Blocking is achievable by calling waitForExecution(). Return false when the controller cannot accept the trajectory.

Wait for the current execution to complete, or until the timeout is reached. Return true if the execution is complete (whether successful or not). Return false if timeout was reached. If timeout is 0 (default argument), wait until the execution is complete (no timeout).


Member Data Documentation

Definition at line 130 of file controller_manager.h.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Mon Oct 6 2014 02:24:48