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 import roslib; roslib.load_manifest('arm_navigation_tutorials')
00032 import sys
00033 import rospy
00034
00035 from mapping_msgs.msg import CollisionObject
00036 from mapping_msgs.msg import CollisionObjectOperation
00037 from geometric_shapes_msgs.msg import Shape
00038 from geometry_msgs.msg import Pose
00039
00040
00041 def add_cylinder(id, bottom, radius, height, frameid):
00042 cylinder_object = CollisionObject()
00043 cylinder_object.id = id
00044 cylinder_object.operation.operation = CollisionObjectOperation.ADD
00045 cylinder_object.header.frame_id = frameid
00046 cylinder_object.header.stamp = rospy.Time.now()
00047
00048 shp = Shape()
00049 shp.type = Shape.CYLINDER
00050 shp.dimensions = [0, 0]
00051 shp.dimensions[0] = radius
00052 shp.dimensions[1] = height
00053
00054 pose = Pose()
00055 pose.position.x = bottom[0]
00056 pose.position.y = bottom[1]
00057 pose.position.z = bottom[2] + height/2.
00058 pose.orientation.x = 0
00059 pose.orientation.y = 0
00060 pose.orientation.z = 0
00061 pose.orientation.w = 1
00062 cylinder_object.shapes.append(shp)
00063 cylinder_object.poses.append(pose)
00064
00065 pub.publish(cylinder_object)
00066
00067
00068 if __name__ == '__main__':
00069 rospy.init_node('add_cylinder_python')
00070
00071 pub = rospy.Publisher('collision_object', CollisionObject)
00072 rospy.sleep(2.)
00073
00074 add_cylinder('pole', (0.6, -0.6, 0.), 0.1, 0.75, 'base_link')
00075 rospy.loginfo('Should have published')
00076 rospy.sleep(2.)
00077
00078
00079