5 sys.modules[
"pyassimp"] = sys
8 from geometry_msgs.msg
import PoseStamped
9 from moveit_msgs.msg
import PlanningScene, PlanningSceneComponents, MoveGroupAction
10 from moveit_msgs.srv
import GetPlanningScene
13 import moveit_commander
18 atexit.register(
lambda : os._exit(0))
21 rospy.init_node(
"publish_simple_scene")
26 moveit_commander.MoveGroupCommander(
'manipulator')
27 scene_interface = moveit_commander.PlanningSceneInterface()
30 rospy.wait_for_service(
'/get_planning_scene', timeout=20);
31 get_planning_scene = rospy.ServiceProxy(
"/get_planning_scene", GetPlanningScene)
33 get_planning_scene =
None 37 while not rospy.is_shutdown():
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))
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: