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 #ifndef _DESCEND_RETREAT_PLACE_
00035 #define _DESCEND_RETREAT_PLACE_
00036
00037 #include <ros/ros.h>
00038
00039 #include <tf/transform_listener.h>
00040
00041 #include <object_manipulation_msgs/PlaceLocationResult.h>
00042 #include <object_manipulation_msgs/PlaceGoal.h>
00043
00044 #include <trajectory_msgs/JointTrajectory.h>
00045
00046 #include "object_manipulator/tools/grasp_marker_publisher.h"
00047
00048 namespace object_manipulator {
00049
00052 struct PlaceExecutionInfo {
00053 trajectory_msgs::JointTrajectory descend_trajectory_;
00054 trajectory_msgs::JointTrajectory retreat_trajectory_;
00055 geometry_msgs::PoseStamped gripper_place_pose_;
00056 object_manipulation_msgs::PlaceLocationResult result_;
00057 int marker_id_;
00058 };
00059
00060
00061
00064 class PlaceTester {
00065 protected:
00067 tf::TransformListener listener_;
00068
00070 geometry_msgs::PoseStamped computeGripperPose(geometry_msgs::PoseStamped place_location,
00071 geometry_msgs::Pose grasp_pose,
00072 std::string frame_id);
00073
00075 virtual void testPlace(const object_manipulation_msgs::PlaceGoal &place_goal,
00076 const geometry_msgs::PoseStamped &place_location,
00077 PlaceExecutionInfo &execution_info) = 0;
00078
00080 GraspMarkerPublisher *marker_publisher_;
00081
00084 boost::function<void(size_t)> feedback_function_;
00085
00087 boost::function<bool()> interrupt_function_;
00088
00089 public:
00090 PlaceTester() : marker_publisher_(NULL) {}
00091
00093 virtual void testPlaces(const object_manipulation_msgs::PlaceGoal &place_goal,
00094 const std::vector<geometry_msgs::PoseStamped> &place_locations,
00095 std::vector<PlaceExecutionInfo> &execution_info,
00096 bool return_on_first_hit);
00097
00099 void setMarkerPublisher(GraspMarkerPublisher *pub){marker_publisher_ = pub;}
00100
00102 void setFeedbackFunction(boost::function<void(size_t)> f){feedback_function_ = f;}
00103
00105 void setInterruptFunction(boost::function<bool()> f){interrupt_function_ = f;}
00106
00108 object_manipulation_msgs::PlaceLocationResult Result(int result_code, bool continuation)
00109 {
00110 object_manipulation_msgs::PlaceLocationResult result;
00111 result.result_code = result_code;
00112 result.continuation_possible = continuation;
00113 return result;
00114 }
00115 };
00116
00119 class PlacePerformer {
00120 protected:
00122 virtual void performPlace(const object_manipulation_msgs::PlaceGoal &place_goal,
00123 const geometry_msgs::PoseStamped &place_location,
00124 PlaceExecutionInfo &execution_info) = 0;
00125
00127 GraspMarkerPublisher *marker_publisher_;
00128
00131 boost::function<void(size_t)> feedback_function_;
00132
00134 boost::function<bool()> interrupt_function_;
00135
00136 public:
00137 PlacePerformer() : marker_publisher_(NULL) {}
00138
00140 virtual void performPlaces(const object_manipulation_msgs::PlaceGoal &place_goal,
00141 const std::vector<geometry_msgs::PoseStamped> &place_locations,
00142 std::vector<PlaceExecutionInfo> &execution_info);
00143
00145 void setMarkerPublisher(GraspMarkerPublisher *pub){marker_publisher_ = pub;}
00146
00148 void setFeedbackFunction(boost::function<void(size_t)> f){feedback_function_ = f;}
00149
00151 void setInterruptFunction(boost::function<bool()> f){interrupt_function_ = f;}
00152
00154 object_manipulation_msgs::PlaceLocationResult Result(int result_code, bool continuation)
00155 {
00156 object_manipulation_msgs::PlaceLocationResult result;
00157 result.result_code = result_code;
00158 result.continuation_possible = continuation;
00159 return result;
00160 }
00161 };
00162
00163
00164
00165 class StandardPlaceTester : public PlaceTester
00166 {
00167 protected:
00169 virtual void testPlace(const object_manipulation_msgs::PlaceGoal &place_goal,
00170 const geometry_msgs::PoseStamped &place_location,
00171 PlaceExecutionInfo &execution_info);
00172
00174 static float EPS;
00175 };
00176
00177
00178
00179 class StandardPlacePerformer : public PlacePerformer
00180 {
00182 object_manipulation_msgs::PlaceLocationResult
00183 retreat(const object_manipulation_msgs::PlaceGoal &place_goal);
00184
00186 bool constraintsUnderstandable(const arm_navigation_msgs::Constraints &constraints);
00187
00189 virtual object_manipulation_msgs::PlaceLocationResult
00190 placeApproach(const object_manipulation_msgs::PlaceGoal &place_goal,
00191 const PlaceExecutionInfo &execution_info);
00192
00194 virtual void performPlace(const object_manipulation_msgs::PlaceGoal &place_goal,
00195 const geometry_msgs::PoseStamped &place_location,
00196 PlaceExecutionInfo &execution_info);
00197 };
00198
00200
00203 class ReactivePlacePerformer : public StandardPlacePerformer
00204 {
00205 protected:
00207 virtual object_manipulation_msgs::PlaceLocationResult
00208 placeApproach(const object_manipulation_msgs::PlaceGoal &place_goal,
00209 const PlaceExecutionInfo &execution_info);
00210 };
00211
00212
00213 }
00214
00215
00216 #endif