pick_place_tutorial.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2012, Willow Garage, Inc.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of Willow Garage, Inc. nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *********************************************************************/
00035 
00036 /* Author: Ioan Sucan */
00037 
00038 #include <ros/ros.h>
00039 
00040 // MoveIt!
00041 #include <moveit/planning_scene_monitor/planning_scene_monitor.h>
00042 #include <moveit/move_group_interface/move_group.h>
00043 #include <shape_tools/solid_primitive_dims.h>
00044 
00045 static const std::string ROBOT_DESCRIPTION="robot_description";
00046 
00047 void pick(moveit::planning_interface::MoveGroup &group)
00048 {
00049   std::vector<manipulation_msgs::Grasp> grasps;
00050 
00051   geometry_msgs::PoseStamped p;
00052   p.header.frame_id = "base_footprint";
00053   p.pose.position.x = 0.32;
00054   p.pose.position.y = -0.7;
00055   p.pose.position.z = 0.5;
00056   p.pose.orientation.x = 0;
00057   p.pose.orientation.y = 0;
00058   p.pose.orientation.z = 0;
00059   p.pose.orientation.w = 1;
00060   manipulation_msgs::Grasp g;
00061   g.grasp_pose = p;
00062 
00063   g.approach.direction.vector.x = 1.0;
00064   g.approach.direction.header.frame_id = "r_wrist_roll_link";
00065   g.approach.min_distance = 0.2;
00066   g.approach.desired_distance = 0.4;
00067 
00068   g.retreat.direction.header.frame_id = "base_footprint";
00069   g.retreat.direction.vector.z = 1.0;
00070   g.retreat.min_distance = 0.1;
00071   g.retreat.desired_distance = 0.25;
00072 
00073   g.pre_grasp_posture.name.resize(1, "r_gripper_joint");
00074   g.pre_grasp_posture.position.resize(1);
00075   g.pre_grasp_posture.position[0] = 1;
00076 
00077   g.grasp_posture.name.resize(1, "r_gripper_joint");
00078   g.grasp_posture.position.resize(1);
00079   g.grasp_posture.position[0] = 0;
00080 
00081   grasps.push_back(g);
00082   group.setSupportSurfaceName("table");
00083   group.pick("part", grasps);
00084 }
00085 
00086 void place(moveit::planning_interface::MoveGroup &group)
00087 {
00088   std::vector<manipulation_msgs::PlaceLocation> loc;
00089 
00090   geometry_msgs::PoseStamped p;
00091   p.header.frame_id = "base_footprint";
00092   p.pose.position.x = 0.7;
00093   p.pose.position.y = 0.0;
00094   p.pose.position.z = 0.5;
00095   p.pose.orientation.x = 0;
00096   p.pose.orientation.y = 0;
00097   p.pose.orientation.z = 0;
00098   p.pose.orientation.w = 1;
00099   manipulation_msgs::PlaceLocation g;
00100   g.place_pose = p;
00101 
00102   g.approach.direction.vector.z = -1.0;
00103   g.retreat.direction.vector.x = -1.0;
00104   g.retreat.direction.header.frame_id = "base_footprint";
00105   g.approach.direction.header.frame_id = "r_wrist_roll_link";
00106   g.approach.min_distance = 0.1;
00107   g.approach.desired_distance = 0.2;
00108   g.retreat.min_distance = 0.1;
00109   g.retreat.desired_distance = 0.25;
00110 
00111   g.post_place_posture.name.resize(1, "r_gripper_joint");
00112   g.post_place_posture.position.resize(1);
00113   g.post_place_posture.position[0] = 1;
00114 
00115   loc.push_back(g);
00116   group.setSupportSurfaceName("table");
00117 
00118 
00119   // add path constraints
00120   moveit_msgs::Constraints constr;
00121   constr.orientation_constraints.resize(1);
00122   moveit_msgs::OrientationConstraint &ocm = constr.orientation_constraints[0];
00123   ocm.link_name = "r_wrist_roll_link";
00124   ocm.header.frame_id = p.header.frame_id;
00125   ocm.orientation.x = 0.0;
00126   ocm.orientation.y = 0.0;
00127   ocm.orientation.z = 0.0;
00128   ocm.orientation.w = 1.0;
00129   ocm.absolute_x_axis_tolerance = 0.2;
00130   ocm.absolute_y_axis_tolerance = 0.2;
00131   ocm.absolute_z_axis_tolerance = M_PI;
00132   ocm.weight = 1.0;
00133   group.setPathConstraints(constr);
00134   group.setPlannerId("RRTConnectkConfigDefault");
00135 
00136   group.place("part", loc);
00137 }
00138 
00139 int main(int argc, char **argv)
00140 {
00141   ros::init (argc, argv, "right_arm_pick_place");
00142   ros::AsyncSpinner spinner(1);
00143   spinner.start();
00144 
00145   ros::NodeHandle nh;
00146   ros::Publisher pub_co = nh.advertise<moveit_msgs::CollisionObject>("collision_object", 10);
00147 
00148   ros::WallDuration(1.0).sleep();
00149 
00150   moveit::planning_interface::MoveGroup group("right_arm");
00151   group.setPlanningTime(45.0);
00152 
00153   moveit_msgs::CollisionObject co;
00154   co.header.stamp = ros::Time::now();
00155   co.header.frame_id = "base_footprint";
00156 
00157   // remove pole
00158   co.id = "pole";
00159   co.operation = moveit_msgs::CollisionObject::REMOVE;
00160   pub_co.publish(co);
00161 
00162   // add pole
00163   co.operation = moveit_msgs::CollisionObject::ADD;
00164   co.primitives.resize(1);
00165   co.primitives[0].type = shape_msgs::SolidPrimitive::BOX;
00166   co.primitives[0].dimensions.resize(shape_tools::SolidPrimitiveDimCount<shape_msgs::SolidPrimitive::BOX>::value);
00167   co.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = 0.3;
00168   co.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = 0.1;
00169   co.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = 1.0;
00170   co.primitive_poses.resize(1);
00171   co.primitive_poses[0].position.x = 0.7;
00172   co.primitive_poses[0].position.y = -0.4;
00173   co.primitive_poses[0].position.z = 0.85;
00174   co.primitive_poses[0].orientation.w = 1.0;
00175   pub_co.publish(co);
00176 
00177 
00178 
00179   // remove table
00180   co.id = "table";
00181   co.operation = moveit_msgs::CollisionObject::REMOVE;
00182   pub_co.publish(co);
00183 
00184   // add table
00185   co.operation = moveit_msgs::CollisionObject::ADD;
00186   co.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = 0.5;
00187   co.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = 1.5;
00188   co.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = 0.35;
00189   co.primitive_poses[0].position.x = 0.7;
00190   co.primitive_poses[0].position.y = -0.2;
00191   co.primitive_poses[0].position.z = 0.175;
00192   pub_co.publish(co);
00193 
00194 
00195 
00196   co.id = "part";
00197   co.operation = moveit_msgs::CollisionObject::REMOVE;
00198   pub_co.publish(co);
00199 
00200   co.operation = moveit_msgs::CollisionObject::ADD;
00201   co.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_X] = 0.15;
00202   co.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Y] = 0.1;
00203   co.primitives[0].dimensions[shape_msgs::SolidPrimitive::BOX_Z] = 0.3;
00204 
00205   co.primitive_poses[0].position.x = 0.6;
00206   co.primitive_poses[0].position.y = -0.7;
00207   co.primitive_poses[0].position.z = 0.5;
00208   pub_co.publish(co);
00209 
00210   // wait a bit for ros things to initialize
00211   ros::WallDuration(1.0).sleep();
00212 
00213   pick(group);
00214 
00215   ros::WallDuration(1.0).sleep();
00216 
00217   place(group);
00218 
00219   ros::waitForShutdown();
00220   return 0;
00221 }


pr2_moveit_tutorials
Author(s): Sachin Chitta
autogenerated on Mon Oct 6 2014 11:15:31