Go to the documentation of this file.00001 import roslib
00002 roslib.load_manifest('laser_interface')
00003 import rospy
00004
00005 from visualization_msgs.msg import Marker
00006
00007 rospy.init_node('marker_publish')
00008 pub = rospy.Publisher('test_marker', Marker)
00009
00010 m = Marker()
00011 m.header.frame_id = '/wide_stereo_optical'
00012 m.header.stamp = rospy.get_rostime()
00013 m.ns = 'test_shapes'
00014 m.id = 0
00015 m.type = Marker.SPHERE
00016 m.action = Marker.ADD
00017 m.pose.position.x = 0.0
00018 m.pose.position.y = 0.0
00019 m.pose.position.z = 0.0
00020 m.pose.orientation.x = 0.0
00021 m.pose.orientation.y = 0.0
00022 m.pose.orientation.z = 0.0
00023 m.pose.orientation.w = 1.0
00024 m.scale.x = 1.0
00025 m.scale.y = 1.0
00026 m.scale.z = 1.0
00027 m.color.r = 0.0
00028 m.color.g = 1.0
00029 m.color.b = 0.0
00030 m.color.a = 1.0
00031 m.lifetime = rospy.Duration()
00032
00033 while not rospy.is_shutdown():
00034 pub.publish(m)
00035 rospy.sleep(1.0)
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045