simple_grasps.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, University of Colorado, Boulder
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Univ of CO, Boulder nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 #include <moveit_simple_grasps/simple_grasps.h>
00036 
00037 namespace moveit_simple_grasps
00038 {
00039 
00040 // Constructor
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 // Deconstructor
00049 SimpleGrasps::~SimpleGrasps()
00050 {
00051 }
00052 
00053 // Create all possible grasp positions for a object
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   // Calculate grasps in two axis in both directions
00059   generateAxisGrasps( object_pose, X_AXIS, DOWN, HALF, 0, grasp_data, possible_grasps); // got no grasps with this alone
00060   generateAxisGrasps( object_pose, X_AXIS, UP,   HALF, 0, grasp_data, possible_grasps); // gives some grasps... looks ugly
00061   generateAxisGrasps( object_pose, Y_AXIS, DOWN, HALF, 0, grasp_data, possible_grasps); // GOOD ONES!
00062   generateAxisGrasps( object_pose, Y_AXIS, UP,   HALF, 0, grasp_data, possible_grasps); // gave a grasp from top... bad
00063 
00064   return true;
00065 }
00066 
00067 // Create grasp positions in one axis
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   // Create a transform from the object's frame (center of object) to /base_link
00079   tf::poseMsgToEigen(object_pose, object_global_transform_);
00080 
00081   // ---------------------------------------------------------------------------------------------
00082   // Grasp parameters
00083 
00084   // Create re-usable approach motion
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_; // The distance the origin of a robot link needs to travel
00088   pre_grasp_approach.min_distance = grasp_data.approach_retreat_min_dist_; // half of the desired? Untested.
00089 
00090   // Create re-usable retreat motion
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_; // The distance the origin of a robot link needs to travel
00094   post_grasp_retreat.min_distance = grasp_data.approach_retreat_min_dist_; // half of the desired? Untested.
00095 
00096   // Create re-usable blank pose
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   // Angle calculations
00103   double radius = grasp_data.grasp_depth_; //0.12
00104   double xb;
00105   double yb = 0.0; // stay in the y plane of the object
00106   double zb;
00107   double theta1 = 0.0; // Where the point is located around the object
00108   double theta2 = 0.0; // UP 'direction'
00109 
00110   // Gripper direction (UP/DOWN) rotation. UP set by default
00111   if( direction == DOWN )
00112   {
00113     theta2 = M_PI;
00114   }
00115 
00116   // ---------------------------------------------------------------------------------------------
00117   // ---------------------------------------------------------------------------------------------
00118   // Begin Grasp Generator Loop
00119   // ---------------------------------------------------------------------------------------------
00120   // ---------------------------------------------------------------------------------------------
00121 
00122   /* Developer Note:
00123    * Create angles 180 degrees around the chosen axis at given resolution
00124    * We create the grasps in the reference frame of the object, then later convert it to the base link
00125    */
00126   for(int i = 0; i <= grasp_data.angle_resolution_; ++i)
00127   {
00128     // Create a Grasp message
00129     moveit_msgs::Grasp new_grasp;
00130 
00131     // Calculate grasp pose
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()); // Flip 'direction'
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()); // Flip 'direction'
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     /* The estimated probability of success for this grasp, or some other measure of how "good" it is.
00163      * Here we base bias the score based on how far the wrist is from the surface, preferring a greater
00164      * distance to prevent wrist/end effector collision with the table
00165      */
00166     double score = sin(theta1);
00167     new_grasp.grasp_quality = std::max(score,0.1); // don't allow score to drop below 0.1 b/c all grasps are ok
00168 
00169     // Calculate the theta1 for next time
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     // A name for this grasp
00178     static int grasp_id = 0;
00179     new_grasp.id = "Grasp" + boost::lexical_cast<std::string>(grasp_id);
00180     ++grasp_id;
00181 
00182     // PreGrasp and Grasp Postures --------------------------------------------------------------------------
00183 
00184     // The internal posture of the hand for the pre-grasp only positions are used
00185     new_grasp.pre_grasp_posture = grasp_data.pre_grasp_posture_;
00186 
00187     // The internal posture of the hand for the grasp positions and efforts are used
00188     new_grasp.grasp_posture = grasp_data.grasp_posture_;
00189 
00190     // Grasp ------------------------------------------------------------------------------------------------
00191 
00192 
00193     // DEBUG - show original grasp pose before tranform to gripper frame
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     // Optionally roll wrist with respect to object pose
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     // Change grasp to frame of reference of this custom end effector
00208 
00209     // Convert to Eigen
00210     Eigen::Affine3d eef_conversion_pose;
00211     tf::poseMsgToEigen(grasp_data.grasp_pose_to_eef_pose_, eef_conversion_pose);
00212 
00213     // Transform the grasp pose
00214     grasp_pose = grasp_pose * eef_conversion_pose;
00215 
00216     // ------------------------------------------------------------------------
00217     // Convert pose to global frame (base_link)
00218     tf::poseEigenToMsg(object_global_transform_ * grasp_pose, grasp_pose_msg.pose);
00219 
00220     // The position of the end-effector for the grasp relative to a reference frame (that is always specified elsewhere, not in this message)
00221     new_grasp.grasp_pose = grasp_pose_msg;
00222 
00223     // Other ------------------------------------------------------------------------------------------------
00224 
00225     // the maximum contact force to use while grasping (<=0 to disable)
00226     new_grasp.max_contact_force = 0;
00227 
00228     // -------------------------------------------------------------------------------------------------------
00229     // -------------------------------------------------------------------------------------------------------
00230     // Approach and retreat
00231     // -------------------------------------------------------------------------------------------------------
00232     // -------------------------------------------------------------------------------------------------------
00233 
00234     // Straight down ---------------------------------------------------------------------------------------
00235     // With respect to the base link/world frame
00236 
00237     // Approach
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; // Approach direction (negative z axis)  // TODO: document this assumption
00242     new_grasp.pre_grasp_approach = pre_grasp_approach;
00243 
00244     // Retreat
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; // Retreat direction (pos z axis)
00249     new_grasp.post_grasp_retreat = post_grasp_retreat;
00250 
00251     // Add to vector
00252     possible_grasps.push_back(new_grasp);
00253 
00254     // Angled with pose -------------------------------------------------------------------------------------
00255     // Approach with respect to end effector orientation
00256 
00257     // Approach
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     // Retreat
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     // Add to vector
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   // Grasp Pose Variables
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   // Get pre-grasp pose first
00289   geometry_msgs::PoseStamped pre_grasp_pose;
00290   Eigen::Affine3d pre_grasp_pose_eigen = grasp_pose_eigen; // Copy original grasp pose to pre-grasp pose
00291 
00292   // Approach direction variables
00293   Eigen::Vector3d pre_grasp_approach_direction_local;
00294 
00295   // The direction of the pre-grasp
00296   // Calculate the current animation position based on the percent
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   // Decide if we need to change the approach_direction to the local frame of the end effector orientation
00304   if( grasp.pre_grasp_approach.direction.header.frame_id == ee_parent_link )
00305   {
00306     // Apply/compute the approach_direction vector in the local frame of the grasp_pose orientation
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; //grasp_pose_eigen.rotation() * pre_grasp_approach_direction;
00312   }
00313 
00314   // Update the grasp matrix usign the new locally-framed approach_direction
00315   pre_grasp_pose_eigen.translation() += pre_grasp_approach_direction_local;
00316 
00317   // Convert eigen pre-grasp position back to regular message
00318   tf::poseEigenToMsg(pre_grasp_pose_eigen, pre_grasp_pose.pose);
00319 
00320   // Copy original header to new grasp
00321   pre_grasp_pose.header = grasp_pose.header;
00322 
00323   return pre_grasp_pose;
00324 }
00325 
00326 
00327 
00328 } // namespace


moveit_simple_grasps
Author(s): Dave Coleman
autogenerated on Fri Aug 28 2015 11:36:01