Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #ifndef _GRASP_EXECUTOR_H_
00037 #define _GRASP_EXECUTOR_H_
00038
00039 #include <ros/ros.h>
00040
00041 #include "object_manipulation_msgs/GraspResult.h"
00042 #include "object_manipulation_msgs/PickupGoal.h"
00043
00044 #include "object_manipulator/tools/mechanism_interface.h"
00045 #include "object_manipulator/tools/grasp_marker_publisher.h"
00046
00047 namespace object_manipulator {
00048
00050
00053 class GraspExecutor
00054 {
00055 public:
00056 object_manipulation_msgs::GraspResult Result(int result_code, bool continuation)
00057 {
00058 object_manipulation_msgs::GraspResult result;
00059 result.result_code = result_code;
00060 result.continuation_possible = continuation;
00061 return result;
00062 }
00063
00064 protected:
00065
00067 GraspMarkerPublisher *marker_publisher_;
00068
00070 unsigned int marker_id_;
00071
00073 trajectory_msgs::JointTrajectory interpolated_lift_trajectory_;
00074
00076 object_manipulation_msgs::GraspResult
00077 getInterpolatedIKForLift(const object_manipulation_msgs::PickupGoal &pickup_goal,
00078 const object_manipulation_msgs::Grasp &grasp,
00079 const std::vector<double> &grasp_joint_angles,
00080 trajectory_msgs::JointTrajectory &lift_trajectory);
00081
00083 motion_planning_msgs::OrderedCollisionOperations
00084 collisionOperationsForLift(const object_manipulation_msgs::PickupGoal &pickup_goal);
00085
00087 std::vector<motion_planning_msgs::LinkPadding>
00088 linkPaddingForLift(const object_manipulation_msgs::PickupGoal &pickup_goal);
00089
00091 std::vector<motion_planning_msgs::LinkPadding>
00092 fingertipPadding(const object_manipulation_msgs::PickupGoal &pickup_goal, double pad);
00093
00095 virtual object_manipulation_msgs::GraspResult
00096 prepareGrasp(const object_manipulation_msgs::PickupGoal &pickup_goal,
00097 const object_manipulation_msgs::Grasp &grasp) = 0;
00098
00100
00101 virtual object_manipulation_msgs::GraspResult
00102 executeGrasp(const object_manipulation_msgs::PickupGoal &pickup_goal,
00103 const object_manipulation_msgs::Grasp &grasp) = 0;
00104
00105 public:
00106
00108 GraspExecutor(GraspMarkerPublisher *pub) : marker_publisher_(pub)
00109 {}
00110 virtual ~GraspExecutor() {}
00111
00113
00114
00115
00116
00117
00118
00119 object_manipulation_msgs::GraspResult
00120 checkAndExecuteGrasp(const object_manipulation_msgs::PickupGoal &pickup_goal,
00121 const object_manipulation_msgs::Grasp &grasp);
00122
00124
00127 virtual object_manipulation_msgs::GraspResult
00128 retreat(const object_manipulation_msgs::PickupGoal &pickup_goal)
00129 {
00130 ROS_WARN("This grasp executor has no retreat capability");
00131 return Result(object_manipulation_msgs::GraspResult::RETREAT_FAILED, false);
00132 }
00133
00135
00140 virtual object_manipulation_msgs::GraspResult lift(const object_manipulation_msgs::PickupGoal &pickup_goal);
00141 };
00142
00143 }
00144
00145 #endif