Go to the documentation of this file.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
00036
00037
00038 #include <ros/ros.h>
00039
00040
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 = "arm_link_5";
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, "gripper_finger_joint_r");
00074 g.pre_grasp_posture.position.resize(1);
00075 g.pre_grasp_posture.position[0] = 1;
00076
00077 g.grasp_posture.name.resize(1, "gripper_finger_joint_r");
00078 g.grasp_posture.position.resize(1);
00079 g.grasp_posture.position[0] = 0;
00080
00081 grasps.push_back(g);
00082 group.setSupportSurfaceName("plane_0");
00083 group.pick("object_3", 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 = "arm_link_5";
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, "gripper_finger_joint_r");
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("plane_0");
00117
00118
00119
00120
00121
00122
00123
00124
00125
00126
00127
00128
00129
00130
00131
00132
00133
00134 group.setPlannerId("RRTConnectkConfigDefault");
00135
00136 group.place("object_3", loc);
00137 }
00138
00139 int main(int argc, char **argv)
00140 {
00141 ros::init (argc, argv, "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("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
00158
00159
00160
00161
00162
00163
00164
00165
00166
00167
00168
00169
00170
00171
00172
00173
00174
00175
00176
00177
00178
00179
00180
00181
00182
00183
00184
00185
00186
00187
00188
00189
00190
00191
00192
00193
00194
00195
00196
00197
00198
00199
00200
00201
00202
00203
00204
00205
00206
00207
00208
00209
00210
00211
00212
00213 ros::WallDuration(1.0).sleep();
00214
00215 pick(group);
00216
00217 ros::WallDuration(1.0).sleep();
00218
00219 place(group);
00220
00221 ros::waitForShutdown();
00222 return 0;
00223 }
00224