load_scene_example.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00004 #
00005 # Licensed under the Apache License, Version 2.0 (the "License");
00006 # you may not use this file except in compliance with the License.
00007 # You may obtain a copy of the License at
00008 #
00009 #   http://www.apache.org/licenses/LICENSE-2.0
00010 #
00011 # Unless required by applicable law or agreed to in writing, software
00012 # distributed under the License is distributed on an "AS IS" BASIS,
00013 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00014 # See the License for the specific language governing permissions and
00015 # limitations under the License.
00016 
00017 
00018 import rospy
00019 from tf.transformations import *
00020 from simple_moveit_interface import *
00021 
00022 
00023 def gen_pose(frame_id="/odom_combined", pos=[0,0,0], euler=[0,0,0]):
00024         pose = PoseStamped()
00025         pose.header.frame_id = frame_id
00026         pose.header.stamp = rospy.Time.now()
00027         pose.pose.position.x, pose.pose.position.y, pose.pose.position.z = pos
00028         pose.pose.orientation.x, pose.pose.orientation.y, pose.pose.orientation.z, pose.pose.orientation.w = quaternion_from_euler(*euler)
00029         return pose
00030 
00031 if __name__ == '__main__':
00032         rospy.init_node('load_scene')
00033         while rospy.get_time() == 0.0: pass
00034 
00035         psi = get_planning_scene_interface()
00036         rospy.sleep(1.0)
00037 
00038         ### Add a floor
00039         add_ground()
00040 
00041         ### Add primitives (box, sphere, cylinder)
00042         pose = gen_pose(pos=[-0.9, 0.8, 0.5])
00043         psi.add_box("box", pose, size=(0.3, 0.5, 0.7))
00044 
00045         pose = gen_pose(pos=[0.0, 0.0, 2.5])
00046         psi.add_sphere("sphere", pose, radius=(0.3))
00047 
00048         # CollisionChecking with cylinder primitives does not work correctly, thus this is not supported! Use a mesh instead!
00049 
00050         ### ADDING A MESH
00051         #ToDo: use rospack to find package
00052         #ToDo: meshes cannot be scaled yet
00053         pose = gen_pose(pos=[0.6, 0.0, 0.9], euler=[-1.57, 0, 3.14])
00054         filename = '/opt/ros/groovy/stacks/simulator_gazebo/gazebo_worlds/Media/models/mug-test.stl'
00055         psi.add_mesh("mug", pose, filename)
00056 
00057         rospy.sleep(1.0)
00058 
00059         ### ADDING DETECT and URDF not supported anymore
00060         #ToDo: Add if needed
00061 
00062         ### ATTACHING AN OBJECT
00063         #ToDo: attach without creating objects again
00064         pose = gen_pose(pos=[0.4, 0.1, 1.0])
00065         psi.attach_box("tray_link", "box2", pose, (0.1,0.1,0.1))
00066 
00067         pose = gen_pose(pos=[0.5, -0.9, 0.9], euler=[-1.57, 0, 3.14])
00068         filename = '/opt/ros/groovy/stacks/simulator_gazebo/gazebo_worlds/Media/models/mug-test.stl'
00069         touch_links = ["sdh_grasp_link", "sdh_palm_link", "sdh_finger_11_link", "sdh_finger_12_link", "sdh_finger_13_link", "sdh_finger_21_link", "sdh_finger_22_link", "sdh_finger_23_link", "sdh_thumb_1_link", "sdh_thumb_2_link", "sdh_thumb_3_link"]
00070         psi.attach_mesh("arm_7_link", "mug", pose, filename, touch_links)
00071 
00072         rospy.sleep(1.0)
00073 
00074         ### DETACHING AN OBJECT
00075         #ToDo: detach without stating link?
00076         psi.remove_attached_object("arm_7_link", "mug")
00077 
00078         rospy.sleep(1.0)
00079 
00080         ### REMOVING AN OBJECT
00081         psi.remove_world_object("sphere")
00082 
00083         ### CLEAR ALL OBJECTS
00084         #ToDo: attached objects are not removed
00085         clear_objects()
00086 


cob_moveit_interface
Author(s): Felix Messmer
autogenerated on Thu Jun 6 2019 21:23:08