pick_server.cpp
Go to the documentation of this file.
00001 #include <ros/ros.h>
00002 #include <moveit/move_group_interface/move_group.h>
00003 #include <actionlib/server/simple_action_server.h>
00004 #include <shape_msgs/SolidPrimitive.h>
00005 #include <shape_tools/shape_extents.h>
00006 #include <calvin_msgs/PickAndStoreAction.h>
00007 #include <tf/tf.h>
00008 #include <moveit_msgs/Grasp.h>
00009 #include <visualization_msgs/Marker.h>
00010 #include <visualization_msgs/MarkerArray.h>
00011 
00012 #include <cmath>
00013 
00014 class PickServer {
00015   protected:
00016     ros::NodeHandle nh;
00017     actionlib::SimpleActionServer<calvin_msgs::PickAndStoreAction> *actionserver;
00018     moveit::planning_interface::MoveGroup *group;
00019     ros::Publisher grasps_marker;
00020 
00021     void publish_grasps_as_markerarray(std::vector<moveit_msgs::Grasp> grasps)
00022     {
00023       visualization_msgs::MarkerArray markers;
00024       int i = 0;
00025 
00026       for(std::vector<moveit_msgs::Grasp>::iterator it = grasps.begin(); it != grasps.end(); ++it) {
00027         visualization_msgs::Marker marker;
00028         marker.header.stamp = ros::Time::now();
00029         marker.header.frame_id = "base_footprint";
00030         marker.id = i;
00031         marker.type = 1;
00032         marker.ns = "graspmarker";
00033         marker.pose = it->grasp_pose.pose;
00034         marker.scale.x = 0.02;
00035         marker.scale.y = 0.02;
00036         marker.scale.z = 0.2;
00037         marker.color.b = 1.0;
00038         marker.color.a = 1.0;
00039         markers.markers.push_back(marker);
00040         i++;
00041       }
00042 
00043       grasps_marker.publish(markers);
00044     }
00045 
00046     moveit_msgs::Grasp build_grasp(tf::Transform t, const double close_width)
00047     {
00048       // distance between finger tip and joint
00049       static const double FINGER_LENGTH = 0.078;
00050 
00051       // assert (0 <= close_width && close_width < 2*FINGER_LENGTH );
00052       // angle to set for grasp to produce grasp width 'close_width'
00053       const double close_angle = asin( ( close_width/2 ) / FINGER_LENGTH ) - 0.44;
00054 
00055       static int i = 0;
00056 
00057       moveit_msgs::Grasp grasp;
00058       geometry_msgs::PoseStamped pose;
00059 
00060       tf::Vector3& origin = t.getOrigin();
00061       tf::Quaternion rotation = t.getRotation();
00062 
00063       tf::quaternionTFToMsg(rotation, pose.pose.orientation);
00064 
00065       pose.header.frame_id = "base_footprint";
00066       pose.header.stamp = ros::Time::now();
00067       pose.pose.position.x = origin.m_floats[0];
00068       pose.pose.position.y = origin.m_floats[1];
00069       pose.pose.position.z = origin.m_floats[2];
00070       grasp.grasp_pose = pose;
00071 
00072       grasp.id = boost::lexical_cast<std::string>(i);
00073 
00074       grasp.pre_grasp_approach.direction.vector.z = 1.0;
00075       grasp.pre_grasp_approach.direction.header.stamp = ros::Time::now();
00076       grasp.pre_grasp_approach.direction.header.frame_id = "katana_gripper_tool_frame";
00077       grasp.pre_grasp_approach.min_distance = 0.03;
00078       grasp.pre_grasp_approach.desired_distance = 0.07;
00079 
00080       grasp.post_grasp_retreat.direction.vector.z = 1.0;
00081       grasp.post_grasp_retreat.direction.header.stamp = ros::Time::now();
00082       grasp.post_grasp_retreat.direction.header.frame_id = "base_footprint";
00083       grasp.post_grasp_retreat.min_distance = 0.03;
00084       grasp.post_grasp_retreat.desired_distance = 0.07;
00085 
00086       grasp.pre_grasp_posture.joint_names.push_back("katana_l_finger_joint");
00087       grasp.pre_grasp_posture.joint_names.push_back("katana_r_finger_joint");
00088       grasp.pre_grasp_posture.points.resize(1);
00089       grasp.pre_grasp_posture.points[0].positions.push_back(0.3);
00090       grasp.pre_grasp_posture.points[0].positions.push_back(0.3);
00091 
00092       grasp.grasp_posture.joint_names.push_back("katana_l_finger_joint");
00093       grasp.grasp_posture.joint_names.push_back("katana_r_finger_joint");
00094       grasp.grasp_posture.points.resize(1);
00095       grasp.grasp_posture.points[0].positions.push_back(close_angle);
00096       grasp.grasp_posture.points[0].positions.push_back(close_angle);
00097 
00098       i++;
00099       return grasp;
00100     }
00101 
00106     std::vector<moveit_msgs::Grasp> generate_grasps(double x, double y, double z, const double width)
00107     {
00108       static const double ANGLE_INC = M_PI / 16;
00109       static const double STRAIGHT_ANGLE_MIN = 0.0 + ANGLE_INC;  // + ANGLE_INC, because 0 is already covered by side grasps
00110       static const double ANGLE_MAX = M_PI / 2;
00111 
00112       // how far from the grasp center should the wrist be?
00113       static const double STANDOFF = -0.01;
00114 
00115       std::vector<moveit_msgs::Grasp> grasps;
00116 
00117       tf::Transform transform;
00118 
00119       tf::Transform standoff_trans;
00120       standoff_trans.setOrigin(tf::Vector3(STANDOFF, 0.0, 0.0));
00121       standoff_trans.setRotation(tf::Quaternion(0.0, sqrt(2)/2, 0.0, sqrt(2)/2));
00122 
00123       // ----- side grasps
00124       //
00125       //  1. side grasp (xy-planes of `katana_motor5_wrist_roll_link` and of `katana_base_link` are parallel):
00126       //     - standard: `rpy = (0, 0, *)` (orientation of `katana_motor5_wrist_roll_link` in `katana_base_link` frame)
00127       //     - overhead: `rpy = (pi, 0, *)`
00128       transform.setOrigin(tf::Vector3(x, y, z));
00129 
00130       for (double roll = 0.0; roll <= M_PI; roll += M_PI)
00131       {
00132         double pitch = 0.0;
00133 
00134         // add yaw = 0 first, then +ANGLE_INC, -ANGLE_INC, 2*ANGLE_INC, ...
00135         // reason: grasps with yaw near 0 mean that the approach is from the
00136         // direction of the arm; it is usually easier to place the object back like
00137         // this
00138         for (double yaw = ANGLE_INC; yaw <= ANGLE_MAX; yaw += ANGLE_INC)
00139         {
00140           // + atan2 to center the grasps around the vector from arm to object
00141           transform.setRotation(tf::createQuaternionFromRPY(roll, pitch, yaw + atan2(y, x)));
00142           grasps.push_back(build_grasp(transform * standoff_trans, width));
00143 
00144           if (yaw != 0.0)
00145           {
00146             transform.setRotation(tf::createQuaternionFromRPY(roll, pitch, -yaw + atan2(y, x)));
00147             grasps.push_back(build_grasp(transform * standoff_trans, width));
00148           }
00149         }
00150       }
00151 
00152       // ----- straight grasps
00153       //
00154       //  2. straight grasp (xz-plane of `katana_motor5_wrist_roll_link` contains z axis of `katana_base_link`)
00155       //     - standard: `rpy = (0, *, atan2(y_w, x_w))`   (x_w, y_w = position of `katana_motor5_wrist_roll_link` in `katana_base_link` frame)
00156       //     - overhead: `rpy = (pi, *, atan2(y_w, x_w))`
00157       for (double roll = 0.0; roll <= M_PI; roll += M_PI)
00158       {
00159         for (double pitch = STRAIGHT_ANGLE_MIN; pitch <= ANGLE_MAX; pitch += ANGLE_INC)
00160         {
00161           double yaw = atan2(y, x);
00162           transform.setOrigin(tf::Vector3(x, y, z));
00163           transform.setRotation(tf::createQuaternionFromRPY(roll, pitch, yaw));
00164 
00165           grasps.push_back(build_grasp(transform * standoff_trans, width));
00166         }
00167       }
00168 
00169       return grasps;
00170     }
00171   public:
00172     PickServer(std::string name) {
00173       group = new moveit::planning_interface::MoveGroup("arm");
00174       group->setPlanningTime(120.0);
00175       actionserver = new actionlib::SimpleActionServer<calvin_msgs::PickAndStoreAction>(nh, ros::names::resolve(name), boost::bind(&PickServer::pick, this, _1), false);
00176       grasps_marker = nh.advertise<visualization_msgs::MarkerArray>("grasps_marker", 10);
00177       actionserver->start();
00178     }
00179     ~PickServer() {
00180       delete actionserver;
00181       delete group;
00182     }
00183     void pick(const calvin_msgs::PickAndStoreGoalConstPtr &goal) {
00184       // maximum width of grasp (can't grasp anything bigger than this)
00185       static const double MAX_GRASP_WIDTH = 0.10;
00186 
00187       static const double SQUEEZE_FACTOR = 0.55;
00188 
00189       if(goal->co.primitive_poses.size() != 1 || goal->co.primitives.size() != 1){
00190         ROS_ERROR("PickAndStore requires a CollisionObject with exactly one SolidPrimitive. Aborting.");
00191         actionserver->setAborted();
00192         return;
00193       }
00194 
00195       double x = goal->co.primitive_poses[0].position.x;
00196       double y = goal->co.primitive_poses[0].position.y;
00197       double z = goal->co.primitive_poses[0].position.z;
00198 
00199       double width = 0.0;
00200       if( goal->close_gripper_partially ){
00201         // compute object 'width'
00202         // TODO: This ignores different object sizes from different approach directions and uses the front width for all of them
00203         double object_width, dx, dz;
00204         shape_tools::getShapeExtents(goal->co.primitives[0], dx, object_width, dz);
00205 
00206         width= SQUEEZE_FACTOR * object_width;
00207         if(0.0 > width || width > MAX_GRASP_WIDTH){
00208           width= std::min( MAX_GRASP_WIDTH, std::max(0.0, width) );
00209           ROS_WARN("Trying to pick an object which is too big to grasp (%fm), trying to pick with grasp width %fm", object_width, width);
00210         }
00211       }
00212 
00213       std::string id = goal->co.id;
00214       ROS_INFO("Trying to pick object %s at %f, %f, %f.", id.c_str(), x, y, z);
00215       bool result = group->pick(id, generate_grasps(x, y, z, width));
00216       if(result) {
00217           ROS_INFO("Pick Action succeeded. Trying to Place.");
00218           bool result = place(id);
00219           if(result) {
00220               ROS_INFO("Place Action succeeded.");
00221               actionserver->setSucceeded();
00222           }
00223           else {
00224               ROS_WARN("Place Action failed. Aborting.");
00225               actionserver->setAborted();
00226           }
00227       }
00228       else {
00229           ROS_WARN("Pick Action failed. Aborting.");
00230           actionserver->setAborted();
00231       }
00232     }
00233     bool place(std::string id) {
00234       static const double ANGLE_INC = M_PI / 16;
00235 
00236       std::vector<moveit_msgs::PlaceLocation> loc;
00237 
00238       for (double yaw = -M_PI; yaw < M_PI; yaw += ANGLE_INC)
00239       {
00240         geometry_msgs::PoseStamped p;
00241         p.header.frame_id = "base_footprint";
00242         p.pose.position.x = 0.21;
00243         p.pose.position.y = 0.115;
00244         p.pose.position.z = 0.78;
00245         tf::quaternionTFToMsg(tf::createQuaternionFromRPY(0.0, 0.0, yaw), p.pose.orientation);
00246 
00247         moveit_msgs::PlaceLocation g;
00248         g.place_pose = p;
00249 
00250         g.pre_place_approach.direction.vector.z = -1.0;
00251         g.pre_place_approach.direction.header.frame_id = "base_link";
00252         g.pre_place_approach.min_distance = 0.03;
00253         g.pre_place_approach.desired_distance = 0.07;
00254         g.post_place_retreat.direction.vector.z = 1.0;
00255         g.post_place_retreat.direction.header.frame_id = "base_link";
00256         g.post_place_retreat.min_distance = 0.03;
00257         g.post_place_retreat.desired_distance = 0.07;
00258 
00259         g.post_place_posture.joint_names.push_back("katana_l_finger_joint");
00260         g.post_place_posture.joint_names.push_back("katana_r_finger_joint");
00261         g.post_place_posture.points.resize(1);
00262         g.post_place_posture.points[0].positions.push_back(0.3);
00263         g.post_place_posture.points[0].positions.push_back(0.3);
00264 
00265         loc.push_back(g);
00266       }
00267 
00268       group->setSupportSurfaceName("cup");
00269 
00270       return group->place(id, loc);
00271     }
00272 };
00273 
00274 int main(int argc, char **argv) {
00275   ros::init (argc, argv, "calvin_pick_server");
00276   PickServer pickserver("calvin_pick_and_store");
00277   ros::spin();
00278   return 0;
00279 }


calvin_pick_server
Author(s): Michael Stypa
autogenerated on Thu Aug 27 2015 12:38:56