moveit2
The MoveIt Motion Planning Framework for ROS 2.
pick.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2013, Willow Garage, Inc.
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without
9 # modification, are permitted provided that the following conditions
10 # are met:
11 #
12 # * Redistributions of source code must retain the above copyright
13 # notice, this list of conditions and the following disclaimer.
14 # * Redistributions in binary form must reproduce the above
15 # copyright notice, this list of conditions and the following
16 # disclaimer in the documentation and/or other materials provided
17 # with the distribution.
18 # * Neither the name of Willow Garage, Inc. nor the names of its
19 # contributors may be used to endorse or promote products derived
20 # from this software without specific prior written permission.
21 #
22 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 # POSSIBILITY OF SUCH DAMAGE.
34 #
35 # Author: Ioan Sucan
36 
37 import sys
38 import rospy
39 from moveit_commander import (
40  RobotCommander,
41  PlanningSceneInterface,
42  roscpp_initialize,
43  roscpp_shutdown,
44 )
45 from geometry_msgs.msg import PoseStamped
46 
47 if __name__ == "__main__":
48 
49  roscpp_initialize(sys.argv)
50  rospy.init_node("moveit_py_demo", anonymous=True)
51 
53  robot = RobotCommander()
54  rospy.sleep(1)
55 
56  # clean the scene
57  scene.remove_world_object("pole")
58  scene.remove_world_object("table")
59  scene.remove_world_object("part")
60 
61  # publish a demo scene
62  p = PoseStamped()
63  p.header.frame_id = robot.get_planning_frame()
64  p.pose.position.x = 0.7
65  p.pose.position.y = -0.4
66  p.pose.position.z = 0.85
67  p.pose.orientation.w = 1.0
68  scene.add_box("pole", p, (0.3, 0.1, 1.0))
69 
70  p.pose.position.y = -0.2
71  p.pose.position.z = 0.175
72  scene.add_box("table", p, (0.5, 1.5, 0.35))
73 
74  p.pose.position.x = 0.6
75  p.pose.position.y = -0.7
76  p.pose.position.z = 0.5
77  scene.add_box("part", p, (0.15, 0.1, 0.3))
78 
79  rospy.sleep(1)
80 
81  # pick an object
82  robot.right_arm.pick("part")
83 
84  rospy.spin()