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 #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 GraspTesterFast;
00059
00060 class GraspTester;
00061 class GraspPerformer;
00062 class PlaceTester;
00063 class PlacePerformer;
00064
00065 class GraspContainer
00066 {
00067 private:
00068 std::vector<object_manipulation_msgs::Grasp> grasps_;
00069 boost::mutex mutex_;
00070
00071 public:
00072 size_t size()
00073 {
00074 boost::mutex::scoped_lock lock(mutex_);
00075 return grasps_.size();
00076 }
00077
00078 std::vector<object_manipulation_msgs::Grasp> getGrasps(size_t start)
00079 {
00080 boost::mutex::scoped_lock lock(mutex_);
00081 std::vector<object_manipulation_msgs::Grasp> ret_grasps;
00082 if (start >= grasps_.size()) return ret_grasps;
00083 std::vector<object_manipulation_msgs::Grasp>::iterator it = grasps_.begin();
00084 for(size_t i=0; i<start; i++) it++;
00085 ret_grasps.insert(ret_grasps.begin(), it, grasps_.end());
00086 return ret_grasps;
00087 }
00088
00089 void addGrasps(const std::vector<object_manipulation_msgs::Grasp> &new_grasps)
00090 {
00091 boost::mutex::scoped_lock lock(mutex_);
00092 if (new_grasps.size() <= grasps_.size())
00093 {
00094 ROS_WARN("No new grasps to add to container");
00095 }
00096 std::vector<object_manipulation_msgs::Grasp>::const_iterator it = new_grasps.begin();
00097 for (size_t i=0; i<grasps_.size(); i++) it++;
00098 grasps_.insert(grasps_.end(), it, new_grasps.end());
00099 }
00100
00101 void clear()
00102 {
00103 boost::mutex::scoped_lock lock(mutex_);
00104 grasps_.clear();
00105 }
00106
00107 void popFrontGrasps(size_t n)
00108 {
00109 if (n==0) return;
00110 boost::mutex::scoped_lock lock(mutex_);
00111 if (n>grasps_.size())
00112 {
00113 ROS_WARN("Grasp container requested to pop more grasps than it has");
00114 grasps_.clear();
00115 return;
00116 }
00117 std::vector<object_manipulation_msgs::Grasp>::iterator it = grasps_.begin();
00118 for(size_t i=0; i<n; i++) it++;
00119 grasps_.erase(grasps_.begin(), it);
00120 }
00121 };
00122
00124
00127 class ObjectManipulator
00128 {
00129 private:
00131 ros::NodeHandle priv_nh_;
00132
00134 ros::NodeHandle root_nh_;
00135
00137
00139 MultiArmActionWrapper<object_manipulation_msgs::GraspPlanningAction> grasp_planning_actions_;
00140
00142 GraspMarkerPublisher *marker_pub_;
00143
00145 bool randomize_grasps_;
00146
00148 std::string kinematics_plugin_name_;
00149
00150 GraspTester* grasp_tester_with_approach_;
00151 GraspTester* unsafe_grasp_tester_;
00152 GraspTesterFast* grasp_tester_fast_;
00153 GraspPerformer* standard_grasp_performer_;
00154 GraspPerformer* reactive_grasp_performer_;
00155 GraspPerformer* unsafe_grasp_performer_;
00156 PlaceTester* standard_place_tester_;
00157 PlacePerformer* standard_place_performer_;
00158 PlacePerformer* reactive_place_performer_;
00159
00161 GraspExecutorWithApproach* grasp_executor_with_approach_;
00162
00164 ReactiveGraspExecutor* reactive_grasp_executor_;
00165
00167 UnsafeGraspExecutor* unsafe_grasp_executor_;
00168
00170 PlaceExecutor* place_executor_;
00171
00173 ReactivePlaceExecutor* reactive_place_executor_;
00174
00176 std::string default_database_planner_;
00177
00179 std::string default_cluster_planner_;
00180
00182 std::string default_probabilistic_planner_;
00183 bool use_probabilistic_planner_;
00184
00186 GraspContainer grasp_container_;
00187
00188 public:
00190 ObjectManipulator();
00191
00192 ~ObjectManipulator();
00193
00195 void pickup(const object_manipulation_msgs::PickupGoal::ConstPtr &pickup_goal,
00196 actionlib::SimpleActionServer<object_manipulation_msgs::PickupAction> *action_server);
00197
00199 void place(const object_manipulation_msgs::PlaceGoal::ConstPtr &place_goal,
00200 actionlib::SimpleActionServer<object_manipulation_msgs::PlaceAction> *action_server);
00201
00203 void graspFeedback(actionlib::SimpleActionServer<object_manipulation_msgs::PickupAction> *action_server,
00204 size_t tested_grasps, size_t current_grasp);
00205
00207 void placeFeedback(actionlib::SimpleActionServer<object_manipulation_msgs::PlaceAction> *action_server,
00208 size_t tested_places, size_t total_places, size_t current_place);
00209
00211 void graspPlanningFeedbackCallback(const object_manipulation_msgs::GraspPlanningFeedbackConstPtr &feedback);
00212
00214 void graspPlanningDoneCallback(const actionlib::SimpleClientGoalState& state,
00215 const object_manipulation_msgs::GraspPlanningResultConstPtr &result);
00216
00217 };
00218
00219 }