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 #include <ros/ros.h>
00037
00038 #include <boost/thread/mutex.hpp>
00039
00040 #include <actionlib/server/simple_action_server.h>
00041
00042 #include <object_manipulation_msgs/PickupAction.h>
00043 #include <object_manipulation_msgs/PlaceAction.h>
00044 #include <object_manipulation_msgs/GraspPlanningAction.h>
00045
00046 #include "object_manipulator/tools/service_action_wrappers.h"
00047 #include "object_manipulator/tools/mechanism_interface.h"
00048
00049 namespace object_manipulator{
00050
00051 class PlaceExecutor;
00052 class ReactivePlaceExecutor;
00053 class ReactiveGraspExecutor;
00054 class GraspExecutorWithApproach;
00055 class UnsafeGraspExecutor;
00056 class GraspMarkerPublisher;
00057
00058 class GraspTester;
00059 class GraspPerformer;
00060 class PlaceTester;
00061 class PlacePerformer;
00062
00063 class GraspContainer
00064 {
00065 private:
00066 std::vector<object_manipulation_msgs::Grasp> grasps_;
00067 boost::mutex mutex_;
00068
00069 public:
00070 size_t size()
00071 {
00072 boost::mutex::scoped_lock lock(mutex_);
00073 return grasps_.size();
00074 }
00075
00076 std::vector<object_manipulation_msgs::Grasp> getGrasps(size_t start)
00077 {
00078 boost::mutex::scoped_lock lock(mutex_);
00079 std::vector<object_manipulation_msgs::Grasp> ret_grasps;
00080 if (start >= grasps_.size()) return ret_grasps;
00081 std::vector<object_manipulation_msgs::Grasp>::iterator it = grasps_.begin();
00082 for(size_t i=0; i<start; i++) it++;
00083 ret_grasps.insert(ret_grasps.begin(), it, grasps_.end());
00084 return ret_grasps;
00085 }
00086
00087 void addGrasps(const std::vector<object_manipulation_msgs::Grasp> &new_grasps)
00088 {
00089 boost::mutex::scoped_lock lock(mutex_);
00090 if (new_grasps.size() <= grasps_.size())
00091 {
00092 ROS_WARN("No new grasps to add to container");
00093 }
00094 std::vector<object_manipulation_msgs::Grasp>::const_iterator it = new_grasps.begin();
00095 for (size_t i=0; i<grasps_.size(); i++) it++;
00096 grasps_.insert(grasps_.end(), it, new_grasps.end());
00097 }
00098
00099 void clear()
00100 {
00101 boost::mutex::scoped_lock lock(mutex_);
00102 grasps_.clear();
00103 }
00104
00105 void popFrontGrasps(size_t n)
00106 {
00107 if (n==0) return;
00108 boost::mutex::scoped_lock lock(mutex_);
00109 if (n>grasps_.size())
00110 {
00111 ROS_WARN("Grasp container requested to pop more grasps than it has");
00112 grasps_.clear();
00113 return;
00114 }
00115 std::vector<object_manipulation_msgs::Grasp>::iterator it = grasps_.begin();
00116 for(size_t i=0; i<n; i++) it++;
00117 grasps_.erase(grasps_.begin(), it);
00118 }
00119 };
00120
00122
00125 class ObjectManipulator
00126 {
00127 private:
00129 ros::NodeHandle priv_nh_;
00130
00132 ros::NodeHandle root_nh_;
00133
00135
00137 MultiArmActionWrapper<object_manipulation_msgs::GraspPlanningAction> grasp_planning_actions_;
00138
00140 GraspMarkerPublisher *marker_pub_;
00141
00143 bool randomize_grasps_;
00144
00145 GraspTester* grasp_tester_with_approach_;
00146 GraspTester* unsafe_grasp_tester_;
00147 GraspPerformer* standard_grasp_performer_;
00148 GraspPerformer* reactive_grasp_performer_;
00149 GraspPerformer* unsafe_grasp_performer_;
00150 PlaceTester* standard_place_tester_;
00151 PlacePerformer* standard_place_performer_;
00152 PlacePerformer* reactive_place_performer_;
00153
00155 GraspExecutorWithApproach* grasp_executor_with_approach_;
00156
00158 ReactiveGraspExecutor* reactive_grasp_executor_;
00159
00161 UnsafeGraspExecutor* unsafe_grasp_executor_;
00162
00164 PlaceExecutor* place_executor_;
00165
00167 ReactivePlaceExecutor* reactive_place_executor_;
00168
00170 std::string default_database_planner_;
00171
00173 std::string default_cluster_planner_;
00174
00176 std::string default_probabilistic_planner_;
00177 bool use_probabilistic_planner_;
00178
00180 GraspContainer grasp_container_;
00181
00182 public:
00184 ObjectManipulator();
00185
00186 ~ObjectManipulator();
00187
00189 void pickup(const object_manipulation_msgs::PickupGoal::ConstPtr &pickup_goal,
00190 actionlib::SimpleActionServer<object_manipulation_msgs::PickupAction> *action_server);
00191
00193 void place(const object_manipulation_msgs::PlaceGoal::ConstPtr &place_goal,
00194 actionlib::SimpleActionServer<object_manipulation_msgs::PlaceAction> *action_server);
00195
00197 void graspFeedback(actionlib::SimpleActionServer<object_manipulation_msgs::PickupAction> *action_server,
00198 size_t tested_grasps, size_t current_grasp);
00199
00201 void placeFeedback(actionlib::SimpleActionServer<object_manipulation_msgs::PlaceAction> *action_server,
00202 size_t tested_places, size_t total_places, size_t current_place);
00203
00205 void graspPlanningFeedbackCallback(const object_manipulation_msgs::GraspPlanningFeedbackConstPtr &feedback);
00206
00208 void graspPlanningDoneCallback(const actionlib::SimpleClientGoalState& state,
00209 const object_manipulation_msgs::GraspPlanningResultConstPtr &result);
00210
00211 };
00212
00213 }