overlay_sample.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 try:
00003   from jsk_rviz_plugins.msg import *
00004 except:
00005   import roslib;roslib.load_manifest("jsk_rviz_plugins")
00006   from jsk_rviz_plugins.msg import *
00007 
00008 from std_msgs.msg import ColorRGBA, Float32
00009 import rospy
00010 import math
00011 rospy.init_node("overlay_sample")
00012 
00013 text_pub = rospy.Publisher("text_sample", OverlayText)
00014 value_pub = rospy.Publisher("value_sample", Float32)
00015 counter = 0
00016 rate = 2
00017 r = rospy.Rate(rate)
00018 import random, math
00019 while not rospy.is_shutdown():
00020   counter = counter + 1
00021   text = OverlayText()
00022   theta = counter % 255 / 255.0
00023   text.width = 400
00024   text.height = 600
00025   #text.height = 600
00026   text.left = 10
00027   text.top = 10
00028   text.text_size = 12
00029   text.line_width = 2
00030   text.font = "DejaVu Sans Mono"
00031   text.text = """This is OverlayText plugin.
00032 The update rate is %d Hz.
00033 You can write several text to show to the operators.
00034 New line is supported and automatical wrapping text is also supported.
00035 And you can choose font, this text is now rendered by '%s'
00036 
00037 You can specify background color and foreground color separatelly.
00038 
00039 Of course, the text is not needed to be fixed, see the counter: %d.
00040   """ % (rate, text.font, counter)
00041   text.fg_color = ColorRGBA(25 / 255.0, 1.0, 240.0 / 255.0, 1.0)
00042   text.bg_color = ColorRGBA(0.0, 0.0, 0.0, 0.2)
00043   text_pub.publish(text)
00044   value_pub.publish(math.sin(counter * math.pi * 2 / 100))
00045   r.sleep()
00046 


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Mon Oct 6 2014 01:18:44