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 <moveit_simple_grasps/simple_grasps.h>
00036
00037 namespace moveit_simple_grasps
00038 {
00039
00040
00041 SimpleGrasps::SimpleGrasps(moveit_visual_tools::VisualToolsPtr visual_tools, bool verbose) :
00042 visual_tools_(visual_tools),
00043 verbose_(verbose)
00044 {
00045 ROS_DEBUG_STREAM_NAMED("grasps","Loaded simple grasp generator");
00046 }
00047
00048
00049 SimpleGrasps::~SimpleGrasps()
00050 {
00051 }
00052
00053
00054 bool SimpleGrasps::generateBlockGrasps(const geometry_msgs::Pose& object_pose, const GraspData& grasp_data,
00055 std::vector<moveit_msgs::Grasp>& possible_grasps)
00056 {
00057
00058
00059 generateAxisGrasps( object_pose, X_AXIS, DOWN, HALF, 0, grasp_data, possible_grasps);
00060 generateAxisGrasps( object_pose, X_AXIS, UP, HALF, 0, grasp_data, possible_grasps);
00061 generateAxisGrasps( object_pose, Y_AXIS, DOWN, HALF, 0, grasp_data, possible_grasps);
00062 generateAxisGrasps( object_pose, Y_AXIS, UP, HALF, 0, grasp_data, possible_grasps);
00063
00064 return true;
00065 }
00066
00067
00068 bool SimpleGrasps::generateAxisGrasps(
00069 const geometry_msgs::Pose& object_pose,
00070 grasp_axis_t axis,
00071 grasp_direction_t direction,
00072 grasp_rotation_t rotation,
00073 double hand_roll,
00074 const GraspData& grasp_data,
00075 std::vector<moveit_msgs::Grasp>& possible_grasps)
00076 {
00077
00078
00079 tf::poseMsgToEigen(object_pose, object_global_transform_);
00080
00081
00082
00083
00084
00085 moveit_msgs::GripperTranslation pre_grasp_approach;
00086 pre_grasp_approach.direction.header.stamp = ros::Time::now();
00087 pre_grasp_approach.desired_distance = grasp_data.approach_retreat_desired_dist_;
00088 pre_grasp_approach.min_distance = grasp_data.approach_retreat_min_dist_;
00089
00090
00091 moveit_msgs::GripperTranslation post_grasp_retreat;
00092 post_grasp_retreat.direction.header.stamp = ros::Time::now();
00093 post_grasp_retreat.desired_distance = grasp_data.approach_retreat_desired_dist_;
00094 post_grasp_retreat.min_distance = grasp_data.approach_retreat_min_dist_;
00095
00096
00097 geometry_msgs::PoseStamped grasp_pose_msg;
00098 grasp_pose_msg.header.stamp = ros::Time::now();
00099 grasp_pose_msg.header.frame_id = grasp_data.base_link_;
00100
00101
00102
00103 double radius = grasp_data.grasp_depth_;
00104 double xb;
00105 double yb = 0.0;
00106 double zb;
00107 double theta1 = 0.0;
00108 double theta2 = 0.0;
00109
00110
00111 if( direction == DOWN )
00112 {
00113 theta2 = M_PI;
00114 }
00115
00116
00117
00118
00119
00120
00121
00122
00123
00124
00125
00126 for(int i = 0; i <= grasp_data.angle_resolution_; ++i)
00127 {
00128
00129 moveit_msgs::Grasp new_grasp;
00130
00131
00132 xb = radius*cos(theta1);
00133 zb = radius*sin(theta1);
00134
00135 Eigen::Affine3d grasp_pose;
00136
00137 switch(axis)
00138 {
00139 case X_AXIS:
00140 grasp_pose = Eigen::AngleAxisd(theta1, Eigen::Vector3d::UnitX())
00141 * Eigen::AngleAxisd(-0.5*M_PI, Eigen::Vector3d::UnitZ())
00142 * Eigen::AngleAxisd(theta2, Eigen::Vector3d::UnitX());
00143
00144 grasp_pose.translation() = Eigen::Vector3d( yb, xb ,zb);
00145
00146 break;
00147 case Y_AXIS:
00148 grasp_pose =
00149 Eigen::AngleAxisd(M_PI - theta1, Eigen::Vector3d::UnitY())
00150 *Eigen::AngleAxisd(theta2, Eigen::Vector3d::UnitX());
00151
00152 grasp_pose.translation() = Eigen::Vector3d( xb, yb ,zb);
00153
00154 break;
00155 case Z_AXIS:
00156 ROS_ERROR_STREAM_NAMED("grasp","Z Axis not implemented!");
00157 return false;
00158
00159 break;
00160 }
00161
00162
00163
00164
00165
00166 double score = sin(theta1);
00167 new_grasp.grasp_quality = std::max(score,0.1);
00168
00169
00170 if (rotation == HALF)
00171 theta1 += M_PI / grasp_data.angle_resolution_;
00172 else
00173 {
00174 theta1 += 2*M_PI / grasp_data.angle_resolution_;
00175 }
00176
00177
00178 static int grasp_id = 0;
00179 new_grasp.id = "Grasp" + boost::lexical_cast<std::string>(grasp_id);
00180 ++grasp_id;
00181
00182
00183
00184
00185 new_grasp.pre_grasp_posture = grasp_data.pre_grasp_posture_;
00186
00187
00188 new_grasp.grasp_posture = grasp_data.grasp_posture_;
00189
00190
00191
00192
00193
00194 if( verbose_ )
00195 {
00196 tf::poseEigenToMsg(object_global_transform_ * grasp_pose, grasp_pose_msg.pose);
00197 visual_tools_->publishArrow(grasp_pose_msg.pose, moveit_visual_tools::GREEN);
00198 }
00199
00200
00201
00202 Eigen::Affine3d roll_gripper;
00203 roll_gripper = Eigen::AngleAxisd(hand_roll, Eigen::Vector3d::UnitX());
00204 grasp_pose = grasp_pose * roll_gripper;
00205
00206
00207
00208
00209
00210 Eigen::Affine3d eef_conversion_pose;
00211 tf::poseMsgToEigen(grasp_data.grasp_pose_to_eef_pose_, eef_conversion_pose);
00212
00213
00214 grasp_pose = grasp_pose * eef_conversion_pose;
00215
00216
00217
00218 tf::poseEigenToMsg(object_global_transform_ * grasp_pose, grasp_pose_msg.pose);
00219
00220
00221 new_grasp.grasp_pose = grasp_pose_msg;
00222
00223
00224
00225
00226 new_grasp.max_contact_force = 0;
00227
00228
00229
00230
00231
00232
00233
00234
00235
00236
00237
00238 pre_grasp_approach.direction.header.frame_id = grasp_data.base_link_;
00239 pre_grasp_approach.direction.vector.x = 0;
00240 pre_grasp_approach.direction.vector.y = 0;
00241 pre_grasp_approach.direction.vector.z = -1;
00242 new_grasp.pre_grasp_approach = pre_grasp_approach;
00243
00244
00245 post_grasp_retreat.direction.header.frame_id = grasp_data.base_link_;
00246 post_grasp_retreat.direction.vector.x = 0;
00247 post_grasp_retreat.direction.vector.y = 0;
00248 post_grasp_retreat.direction.vector.z = 1;
00249 new_grasp.post_grasp_retreat = post_grasp_retreat;
00250
00251
00252 possible_grasps.push_back(new_grasp);
00253
00254
00255
00256
00257
00258 pre_grasp_approach.direction.header.frame_id = grasp_data.ee_parent_link_;
00259 pre_grasp_approach.direction.vector.x = 0;
00260 pre_grasp_approach.direction.vector.y = 0;
00261 pre_grasp_approach.direction.vector.z = 1;
00262 new_grasp.pre_grasp_approach = pre_grasp_approach;
00263
00264
00265 post_grasp_retreat.direction.header.frame_id = grasp_data.ee_parent_link_;
00266 post_grasp_retreat.direction.vector.x = 0;
00267 post_grasp_retreat.direction.vector.y = 0;
00268 post_grasp_retreat.direction.vector.z = -1;
00269 new_grasp.post_grasp_retreat = post_grasp_retreat;
00270
00271
00272 possible_grasps.push_back(new_grasp);
00273
00274 }
00275
00276 ROS_INFO_STREAM_NAMED("grasp", "Generated " << possible_grasps.size() << " grasps." );
00277
00278 return true;
00279 }
00280
00281 geometry_msgs::PoseStamped SimpleGrasps::getPreGraspPose(const moveit_msgs::Grasp &grasp, const std::string &ee_parent_link)
00282 {
00283
00284 geometry_msgs::PoseStamped grasp_pose = grasp.grasp_pose;
00285 Eigen::Affine3d grasp_pose_eigen;
00286 tf::poseMsgToEigen(grasp_pose.pose, grasp_pose_eigen);
00287
00288
00289 geometry_msgs::PoseStamped pre_grasp_pose;
00290 Eigen::Affine3d pre_grasp_pose_eigen = grasp_pose_eigen;
00291
00292
00293 Eigen::Vector3d pre_grasp_approach_direction_local;
00294
00295
00296
00297 Eigen::Vector3d pre_grasp_approach_direction = Eigen::Vector3d(
00298 -1 * grasp.pre_grasp_approach.direction.vector.x * grasp.pre_grasp_approach.desired_distance,
00299 -1 * grasp.pre_grasp_approach.direction.vector.y * grasp.pre_grasp_approach.desired_distance,
00300 -1 * grasp.pre_grasp_approach.direction.vector.z * grasp.pre_grasp_approach.desired_distance
00301 );
00302
00303
00304 if( grasp.pre_grasp_approach.direction.header.frame_id == ee_parent_link )
00305 {
00306
00307 pre_grasp_approach_direction_local = grasp_pose_eigen.rotation() * pre_grasp_approach_direction;
00308 }
00309 else
00310 {
00311 pre_grasp_approach_direction_local = pre_grasp_approach_direction;
00312 }
00313
00314
00315 pre_grasp_pose_eigen.translation() += pre_grasp_approach_direction_local;
00316
00317
00318 tf::poseEigenToMsg(pre_grasp_pose_eigen, pre_grasp_pose.pose);
00319
00320
00321 pre_grasp_pose.header = grasp_pose.header;
00322
00323 return pre_grasp_pose;
00324 }
00325
00326
00327
00328 }