publish_simple_scene.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 ## workaround until https://github.com/ros-planning/moveit/pull/581 is released
4 import sys
5 sys.modules["pyassimp"] = sys
6 import pyassimp
7 
8 from geometry_msgs.msg import PoseStamped
9 from moveit_msgs.msg import PlanningScene, PlanningSceneComponents, MoveGroupAction
10 from moveit_msgs.srv import GetPlanningScene
11 
12 import rospy
13 import moveit_commander
14 import actionlib
15 
16 # workaround for core dump whenever exiting Python MoveIt script (https://github.com/ros-planning/moveit_commander/issues/15#issuecomment-34441531)
17 import atexit, os
18 atexit.register(lambda : os._exit(0))
19 
20 # init rospy
21 rospy.init_node("publish_simple_scene")
22 
23 # init moveit_commander
24 ac = actionlib.SimpleActionClient('move_group', MoveGroupAction)
25 ac.wait_for_server()
26 moveit_commander.MoveGroupCommander('manipulator')
27 scene_interface = moveit_commander.PlanningSceneInterface()
28 # get_planning_scene
29 try:
30  rospy.wait_for_service('/get_planning_scene', timeout=20);
31  get_planning_scene = rospy.ServiceProxy("/get_planning_scene", GetPlanningScene)
32 except:
33  get_planning_scene = None
34 
35 # done
36 rate = rospy.Rate(1)
37 while not rospy.is_shutdown():
38  pose = PoseStamped()
39  pose.header.frame_id = 'BASE'
40  pose.pose.position.x = 0.3
41  pose.pose.position.y =-0.35
42  pose.pose.position.z = 0.5
43  pose.pose.orientation.w = 1.0
44  scene_interface.add_box('simple_object_1', pose, (0.2,0.5,0.04))
45  pose.pose.position.x = 0.3
46  pose.pose.position.y =-0.12
47  pose.pose.position.z = 0.72
48  scene_interface.add_box('simple_object_2', pose, (0.2,0.04,0.4))
49  pose.pose.position.x =-0.2
50  pose.pose.position.y = 0.0
51  pose.pose.position.z = 0.7
52  scene_interface.add_box('simple_object_3', pose, (0.04,1.0,0.2))
53 
54  rate.sleep()
55 
56  print len(get_planning_scene(PlanningSceneComponents(components=PlanningSceneComponents.WORLD_OBJECT_NAMES)).scene.world.collision_objects)
57  if get_planning_scene and len(get_planning_scene(PlanningSceneComponents(components=PlanningSceneComponents.WORLD_OBJECT_NAMES)).scene.world.collision_objects) >= 3:
58  break
59 


vs060
Author(s): Ryohei Ueda
autogenerated on Mon Jun 10 2019 13:13:22