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 <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 GraspMarkerPublisher;
00052
00053 class GraspTester;
00054 class GraspTesterFast;
00055 class GraspPerformer;
00056 class PlaceTester;
00057 class PlacePerformer;
00058
00059 class GraspContainer
00060 {
00061 private:
00062 std::vector<manipulation_msgs::Grasp> grasps_;
00063 boost::mutex mutex_;
00064
00065 public:
00066 size_t size()
00067 {
00068 boost::mutex::scoped_lock lock(mutex_);
00069 return grasps_.size();
00070 }
00071
00072 std::vector<manipulation_msgs::Grasp> getGrasps(size_t start)
00073 {
00074 boost::mutex::scoped_lock lock(mutex_);
00075 std::vector<manipulation_msgs::Grasp> ret_grasps;
00076 if (start >= grasps_.size()) return ret_grasps;
00077 std::vector<manipulation_msgs::Grasp>::iterator it = grasps_.begin();
00078 for(size_t i=0; i<start; i++) it++;
00079 ret_grasps.insert(ret_grasps.begin(), it, grasps_.end());
00080 return ret_grasps;
00081 }
00082
00083 void addGrasps(const std::vector<manipulation_msgs::Grasp> &new_grasps)
00084 {
00085 boost::mutex::scoped_lock lock(mutex_);
00086 if (new_grasps.size() <= grasps_.size())
00087 {
00088 ROS_WARN("No new grasps to add to container");
00089 }
00090 std::vector<manipulation_msgs::Grasp>::const_iterator it = new_grasps.begin();
00091 for (size_t i=0; i<grasps_.size(); i++) it++;
00092 grasps_.insert(grasps_.end(), it, new_grasps.end());
00093 }
00094
00095 void clear()
00096 {
00097 boost::mutex::scoped_lock lock(mutex_);
00098 grasps_.clear();
00099 }
00100
00101 void popFrontGrasps(size_t n)
00102 {
00103 if (n==0) return;
00104 boost::mutex::scoped_lock lock(mutex_);
00105 if (n>grasps_.size())
00106 {
00107 ROS_WARN("Grasp container requested to pop more grasps than it has");
00108 grasps_.clear();
00109 return;
00110 }
00111 std::vector<manipulation_msgs::Grasp>::iterator it = grasps_.begin();
00112 for(size_t i=0; i<n; i++) it++;
00113 grasps_.erase(grasps_.begin(), it);
00114 }
00115 };
00116
00118
00121 class ObjectManipulator
00122 {
00123 private:
00125 ros::NodeHandle priv_nh_;
00126
00128 ros::NodeHandle root_nh_;
00129
00131
00133 MultiArmActionWrapper<manipulation_msgs::GraspPlanningAction> grasp_planning_actions_;
00134
00136 GraspMarkerPublisher *marker_pub_;
00137
00139 bool randomize_grasps_;
00140
00142 std::string kinematics_plugin_name_;
00143
00144 GraspTester* grasp_tester_with_approach_;
00145 GraspTester* unsafe_grasp_tester_;
00146 GraspTesterFast* grasp_tester_fast_;
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 std::string default_database_planner_;
00156
00158 std::string default_cluster_planner_;
00159
00161 std::string default_probabilistic_planner_;
00162 bool use_probabilistic_planner_;
00163
00165 GraspContainer grasp_container_;
00166
00167 public:
00169 ObjectManipulator();
00170
00171 ~ObjectManipulator();
00172
00174 void pickup(const object_manipulation_msgs::PickupGoal::ConstPtr &pickup_goal,
00175 actionlib::SimpleActionServer<object_manipulation_msgs::PickupAction> *action_server);
00176
00178 void place(const object_manipulation_msgs::PlaceGoal::ConstPtr &place_goal,
00179 actionlib::SimpleActionServer<object_manipulation_msgs::PlaceAction> *action_server);
00180
00182 void graspFeedback(actionlib::SimpleActionServer<object_manipulation_msgs::PickupAction> *action_server,
00183 size_t tested_grasps, size_t current_grasp);
00184
00186 void placeFeedback(actionlib::SimpleActionServer<object_manipulation_msgs::PlaceAction> *action_server,
00187 size_t tested_places, size_t total_places, size_t current_place);
00188
00190 void graspPlanningFeedbackCallback(const manipulation_msgs::GraspPlanningFeedbackConstPtr &feedback);
00191
00193 void graspPlanningDoneCallback(const actionlib::SimpleClientGoalState& state,
00194 const manipulation_msgs::GraspPlanningResultConstPtr &result);
00195
00196 };
00197
00198 }