$search

object_manipulator::GraspExecutor Class Reference

Base class, interface and common functionality for grasp execution. More...

#include <grasp_executor.h>

Inheritance diagram for object_manipulator::GraspExecutor:
Inheritance graph
[legend]

List of all members.

Public Member Functions

object_manipulation_msgs::GraspResult checkAndExecuteGrasp (const object_manipulation_msgs::PickupGoal &pickup_goal, const object_manipulation_msgs::Grasp &grasp)
 Checks if the grasp is feasible, then executes it.
 GraspExecutor (GraspMarkerPublisher *pub)
 Also sets the marker publisher that is to be used; pass NULL to disable marker publishing.
virtual
object_manipulation_msgs::GraspResult 
lift (const object_manipulation_msgs::PickupGoal &pickup_goal)
 Lifts the object after grasping.
object_manipulation_msgs::GraspResult Result (int result_code, bool continuation)
virtual
object_manipulation_msgs::GraspResult 
retreat (const object_manipulation_msgs::PickupGoal &pickup_goal)
 Called if the grasp fails to retreat the gripper.
virtual ~GraspExecutor ()

Protected Member Functions

motion_planning_msgs::OrderedCollisionOperations collisionOperationsForLift (const object_manipulation_msgs::PickupGoal &pickup_goal)
 Collision operations to be used when planning the lift motion.
virtual
object_manipulation_msgs::GraspResult 
executeGrasp (const object_manipulation_msgs::PickupGoal &pickup_goal, const object_manipulation_msgs::Grasp &grasp)=0
 Implementation of the actual execution stage of the grasp.
std::vector
< motion_planning_msgs::LinkPadding > 
fingertipPadding (const object_manipulation_msgs::PickupGoal &pickup_goal, double pad)
 Helper function for setting padding on fingertips.
object_manipulation_msgs::GraspResult getInterpolatedIKForLift (const object_manipulation_msgs::PickupGoal &pickup_goal, const object_manipulation_msgs::Grasp &grasp, const std::vector< double > &grasp_joint_angles, trajectory_msgs::JointTrajectory &lift_trajectory)
 Calls the interpolated IK service to find a path from the grasp to lift the object.
std::vector
< motion_planning_msgs::LinkPadding > 
linkPaddingForLift (const object_manipulation_msgs::PickupGoal &pickup_goal)
 Dynamic link padding to be used when planning the lift motion.
virtual
object_manipulation_msgs::GraspResult 
prepareGrasp (const object_manipulation_msgs::PickupGoal &pickup_goal, const object_manipulation_msgs::Grasp &grasp)=0
 Performs an initial check to see if the grasp is valid and generates information needed to execute it.

Protected Attributes

trajectory_msgs::JointTrajectory interpolated_lift_trajectory_
 The result of interpolated IK from grasp to lift.
unsigned int marker_id_
 The marker id of this grasp, retrieved from the publisher.
GraspMarkerPublishermarker_publisher_
 The marker publisher that will be used; NULL is marker publishing is disabled.

Detailed Description

Base class, interface and common functionality for grasp execution.

Defines the interface for a grasp executor:

Definition at line 53 of file grasp_executor.h.


Constructor & Destructor Documentation

object_manipulator::GraspExecutor::GraspExecutor ( GraspMarkerPublisher pub  )  [inline]

Also sets the marker publisher that is to be used; pass NULL to disable marker publishing.

Definition at line 108 of file grasp_executor.h.

virtual object_manipulator::GraspExecutor::~GraspExecutor (  )  [inline, virtual]

Definition at line 110 of file grasp_executor.h.


Member Function Documentation

GraspResult object_manipulator::GraspExecutor::checkAndExecuteGrasp ( const object_manipulation_msgs::PickupGoal &  pickup_goal,
const object_manipulation_msgs::Grasp &  grasp 
)

Checks if the grasp is feasible, then executes it.

Definition at line 148 of file grasp_executor.cpp.

motion_planning_msgs::OrderedCollisionOperations object_manipulator::GraspExecutor::collisionOperationsForLift ( const object_manipulation_msgs::PickupGoal &  pickup_goal  )  [protected]

Collision operations to be used when planning the lift motion.

Disables collision between gripper and target

Definition at line 49 of file grasp_executor.cpp.

virtual object_manipulation_msgs::GraspResult object_manipulator::GraspExecutor::executeGrasp ( const object_manipulation_msgs::PickupGoal &  pickup_goal,
const object_manipulation_msgs::Grasp &  grasp 
) [protected, pure virtual]

Implementation of the actual execution stage of the grasp.

Can use information generated during prepareGrasp

Implemented in object_manipulator::GraspExecutorWithApproach, object_manipulator::ReactiveGraspExecutor, and object_manipulator::SimpleGraspExecutor.

std::vector<motion_planning_msgs::LinkPadding> object_manipulator::GraspExecutor::fingertipPadding ( const object_manipulation_msgs::PickupGoal &  pickup_goal,
double  pad 
) [protected]

Helper function for setting padding on fingertips.

GraspResult object_manipulator::GraspExecutor::getInterpolatedIKForLift ( const object_manipulation_msgs::PickupGoal &  pickup_goal,
const object_manipulation_msgs::Grasp &  grasp,
const std::vector< double > &  grasp_joint_angles,
trajectory_msgs::JointTrajectory lift_trajectory 
) [protected]

Calls the interpolated IK service to find a path from the grasp to lift the object.

Definition at line 76 of file grasp_executor.cpp.

GraspResult object_manipulator::GraspExecutor::lift ( const object_manipulation_msgs::PickupGoal &  pickup_goal  )  [virtual]

Lifts the object after grasping.

Generally returns SUCCESS if full lift was achieved, UNFEASIBLE if no movement was performed and FAILED if some movement was achieved but it fell short of a full lift.

Will often use information that was pre-generated during grasp execution, so this should always be called after executeGrasp() has succeeded.

Reimplemented in object_manipulator::ReactiveGraspExecutor.

Definition at line 134 of file grasp_executor.cpp.

std::vector< motion_planning_msgs::LinkPadding > object_manipulator::GraspExecutor::linkPaddingForLift ( const object_manipulation_msgs::PickupGoal &  pickup_goal  )  [protected]

Dynamic link padding to be used when planning the lift motion.

Zero padding on fingertip links

Definition at line 69 of file grasp_executor.cpp.

virtual object_manipulation_msgs::GraspResult object_manipulator::GraspExecutor::prepareGrasp ( const object_manipulation_msgs::PickupGoal &  pickup_goal,
const object_manipulation_msgs::Grasp &  grasp 
) [protected, pure virtual]

Performs an initial check to see if the grasp is valid and generates information needed to execute it.

Implemented in object_manipulator::GraspExecutorWithApproach, and object_manipulator::SimpleGraspExecutor.

object_manipulation_msgs::GraspResult object_manipulator::GraspExecutor::Result ( int  result_code,
bool  continuation 
) [inline]

Definition at line 56 of file grasp_executor.h.

virtual object_manipulation_msgs::GraspResult object_manipulator::GraspExecutor::retreat ( const object_manipulation_msgs::PickupGoal &  pickup_goal  )  [inline, virtual]

Called if the grasp fails to retreat the gripper.

By default, a grasp executor does not know how to do this. Generally returns UNFEASIBLE if no movement has been performed at all, SUCCESS if a full retreat was achieved and FAILED is some movement was performed but it fell short of a full retreat.

Reimplemented in object_manipulator::GraspExecutorWithApproach.

Definition at line 128 of file grasp_executor.h.


Member Data Documentation

The result of interpolated IK from grasp to lift.

Definition at line 73 of file grasp_executor.h.

The marker id of this grasp, retrieved from the publisher.

Definition at line 70 of file grasp_executor.h.

The marker publisher that will be used; NULL is marker publishing is disabled.

Definition at line 67 of file grasp_executor.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


katana_object_manipulator
Author(s): Henning Deeken
autogenerated on Thu Jan 3 13:17:59 2013