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 #include "bayesian_grasp_planner/grasp_generator.h"
00036 #include <object_manipulation_msgs/GraspPlanning.h>
00037 #include <object_manipulator/tools/hand_description.h>
00038
00039 namespace bayesian_grasp_planner {
00040
00041 GraspGeneratorServiceCaller::GraspGeneratorServiceCaller(ros::NodeHandle &nh, const std::string service_name,
00042 const object_manipulation_msgs::GraspableObject &graspable_object,
00043 const std::string arm_name) :
00044 object_(graspable_object),arm_name_(arm_name),service_name_(service_name)
00045 {
00046 service_ = register_service<object_manipulation_msgs::GraspPlanning>(nh, service_name);
00047 }
00048
00049 void GraspGeneratorServiceCaller::generateGrasps()
00050 {
00051 object_manipulation_msgs::GraspPlanning planner_call;
00052
00053 ROS_INFO("calling grasp service %s", service_name_.c_str());
00054
00055
00056 planner_call.request.target = object_;
00057 planner_call.request.arm_name = arm_name_;
00058 service_.call(planner_call);
00059 if (planner_call.response.error_code.value != object_manipulation_msgs::GraspPlanningErrorCode::SUCCESS)
00060 {
00061 ROS_ERROR("Call to service-based planner failed!");
00062 }
00063 ROS_INFO("Got %zd grasps from the service-based planner", planner_call.response.grasps.size());
00064 appendMetadataToGrasps(planner_call.response.grasps, grasps_);
00065 }
00066
00067
00068 void GraspGeneratorServiceCaller::appendMetadataToGrasps(std::vector<object_manipulation_msgs::Grasp> &grasp_msgs,
00069 std::vector<GraspWM> &grasps)
00070 {
00071 grasps.reserve(grasps.size()+grasp_msgs.size());
00072
00073
00074 BOOST_FOREACH(object_manipulation_msgs::Grasp &grasp, grasp_msgs)
00075 {
00076 GraspWM grasp_with_metadata;
00077 grasp_with_metadata.grasp_ = grasp;
00078
00079 grasp_with_metadata.model_id_ = -1;
00080 grasp_with_metadata.grasp_id_ = -1;
00081
00082 grasp_with_metadata.object_pose_.setIdentity();
00083 grasp_with_metadata.object_pose_.frame_id_ = object_.cluster.header.frame_id;
00084 grasp_with_metadata.object_pose_.stamp_ = object_.cluster.header.stamp;
00085
00086 grasp_with_metadata.energy_function_score = grasp.success_probability;
00087
00088 tf::Pose grasp_in_base_frame;
00089 tf::poseMsgToTF(grasp.grasp_pose, grasp_in_base_frame);
00090
00091
00092
00093 tf::poseTFToMsg(grasp_in_base_frame,grasp_with_metadata.grasp_.grasp_pose);
00094
00095 double wrist_to_tool_point_offset_ = 0.13;
00096
00097 tf::Pose grasp_to_tool_point(btMatrix3x3::getIdentity(),btVector3(wrist_to_tool_point_offset_,0,0));
00098
00100 grasp_with_metadata.tool_point_pose_ = tf::Stamped<tf::Pose>(
00101 grasp_in_base_frame * grasp_to_tool_point, object_.cluster.header.stamp,
00102 object_.cluster.header.frame_id);
00103
00104 grasps.push_back(grasp_with_metadata);
00105 }
00106 }
00107
00108 GraspGeneratorDatabaseRetriever::GraspGeneratorDatabaseRetriever
00109 (boost::shared_ptr<household_objects_database::ObjectsDatabase> database,
00110 household_objects_database_msgs::DatabaseModelPose model, const std::string arm_name,
00111 bool cluster_reps) :
00112 database_(database),
00113 model_(model),
00114 arm_name_(arm_name),
00115 cluster_reps_(cluster_reps)
00116 {
00117 if (cluster_reps_) ROS_INFO("creating cluster reps GraspGeneratorDatabaseRetriever for model_id %d", model.model_id);
00118 else ROS_INFO("creating GraspGeneratorDatabaseRetriever for model_id %d", model.model_id);
00119 }
00120
00121 void GraspGeneratorDatabaseRetriever::generateGrasps()
00122 {
00123 std::vector<household_objects_database::DatabaseGraspPtr> db_grasps;
00124 ROS_INFO("generating grasps by pulling them from database for model %d", model_.model_id);
00125
00126
00127 bool result;
00128 if (cluster_reps_)
00129 {
00130 result = database_->getClusterRepGrasps(model_.model_id,
00131 object_manipulator::handDescription().handDatabaseName(arm_name_), db_grasps);
00132 }
00133 else
00134 {
00135 result = database_->getGrasps(model_.model_id,
00136 object_manipulator::handDescription().handDatabaseName(arm_name_), db_grasps);
00137 }
00138 if (!result) ROS_ERROR("Robust Database Grasp Planning Node: grasp retrieval error");
00139 ROS_WARN("Size from DB: %zd",db_grasps.size());
00140 appendMetadataToGrasps(db_grasps, grasps_);
00141 ROS_WARN("Size after appending: %zd",grasps_.size());
00142 }
00143
00144
00145 void GraspGeneratorDatabaseRetriever::appendMetadataToGrasps(
00146 const std::vector<household_objects_database::DatabaseGraspPtr> &db_grasps,
00147 std::vector<GraspWM> &grasps)
00148 {
00149 grasps.reserve(grasps.size()+db_grasps.size());
00150
00151 BOOST_FOREACH(household_objects_database::DatabaseGraspPtr db_grasp, db_grasps) {
00152 GraspWM grasp;
00153
00154 ROS_ASSERT( db_grasp->final_grasp_posture_.get().joint_angles_.size() ==
00155 db_grasp->pre_grasp_posture_.get().joint_angles_.size() );
00156 ROS_ASSERT(db_grasp->scaled_model_id_.get() == model_.model_id);
00157
00158 std::vector<std::string> joint_names = object_manipulator::handDescription().handJointNames(arm_name_);
00159 if (object_manipulator::handDescription().handDatabaseName(arm_name_) != "WILLOW_GRIPPER_2010")
00160 {
00161
00162
00163 if (joint_names.size() != db_grasp->final_grasp_posture_.get().joint_angles_.size())
00164 {
00165 ROS_ERROR("Database grasp specification does not match ROS description of hand. "
00166 "Hand is expected to have %zd joints, but database grasp specifies %zd values",
00167 joint_names.size(), db_grasp->final_grasp_posture_.get().joint_angles_.size());
00168 continue;
00169 }
00170
00171
00172 grasp.grasp_.pre_grasp_posture.name = joint_names;
00173 grasp.grasp_.grasp_posture.name = joint_names;
00174 grasp.grasp_.pre_grasp_posture.position = db_grasp->pre_grasp_posture_.get().joint_angles_;
00175 grasp.grasp_.grasp_posture.position = db_grasp->final_grasp_posture_.get().joint_angles_;
00176 }
00177 else
00178 {
00179
00180
00181 if ( joint_names.size() != 4 || db_grasp->final_grasp_posture_.get().joint_angles_.size() != 1)
00182 {
00183 ROS_ERROR("PR2 gripper specs and database grasp specs do not match expected values");
00184 continue;
00185 }
00186 grasp.grasp_.pre_grasp_posture.name = joint_names;
00187 grasp.grasp_.grasp_posture.name = joint_names;
00188
00189 grasp.grasp_.pre_grasp_posture.position.resize( joint_names.size(),
00190 db_grasp->pre_grasp_posture_.get().joint_angles_.at(0));
00191 grasp.grasp_.grasp_posture.position.resize( joint_names.size(),
00192 db_grasp->final_grasp_posture_.get().joint_angles_.at(0));
00193 }
00194
00195
00196
00197 grasp.grasp_.grasp_posture.effort.resize(joint_names.size(), 10000);
00198
00199 grasp.grasp_.success_probability = 0.0;
00200
00201
00202
00203
00204 grasp.energy_function_score = db_grasp->scaled_quality_.get();
00205 grasp.model_id_ = db_grasp->scaled_model_id_.get();
00206 grasp.grasp_id_ = db_grasp->id_.get();
00207
00208 tf::Stamped<tf::Pose> base_to_object;
00209
00210 tf::poseStampedMsgToTF(model_.pose,base_to_object);
00211
00212 tf::Pose object_to_grasp;
00213 tf::poseMsgToTF(db_grasp->final_grasp_pose_.get().pose_, object_to_grasp);
00214
00215
00216
00217 grasp.object_pose_ = base_to_object;
00218
00219
00220
00221 tf::Pose base_to_grasp(base_to_object * object_to_grasp);
00222
00223 tf::poseTFToMsg(base_to_grasp,grasp.grasp_.grasp_pose);
00224
00225
00226 double wrist_to_tool_point_offset_ = 0.13;
00227
00228 tf::Pose offset_tf(btMatrix3x3::getIdentity(),btVector3(wrist_to_tool_point_offset_,0,0));
00229
00231 grasp.tool_point_pose_ = tf::Stamped<tf::Pose>(base_to_grasp * offset_tf,
00232 grasp.object_pose_.stamp_, grasp.object_pose_.frame_id_);
00233
00234
00235 grasps.push_back(grasp);
00236 }
00237 }
00238
00239
00240 }