overlay_sample.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 try:
3  from jsk_rviz_plugins.msg import *
4 except:
5  import roslib;roslib.load_manifest("jsk_rviz_plugins")
6  from jsk_rviz_plugins.msg import *
7 
8 from std_msgs.msg import ColorRGBA, Float32
9 import rospy
10 import math
11 rospy.init_node("overlay_sample")
12 
13 text_pub = rospy.Publisher("text_sample", OverlayText, queue_size=1)
14 value_pub = rospy.Publisher("value_sample", Float32, queue_size=1)
15 counter = 0
16 rate = 100
17 r = rospy.Rate(rate)
18 import random, math
19 while not rospy.is_shutdown():
20  counter = counter + 1
21  text = OverlayText()
22  theta = counter % 255 / 255.0
23  text.width = 400
24  text.height = 600
25  #text.height = 600
26  text.left = 10
27  text.top = 10
28  text.text_size = 12
29  text.line_width = 2
30  text.font = "DejaVu Sans Mono"
31  text.text = """This is OverlayText plugin.
32 The update rate is %d Hz.
33 You can write several text to show to the operators.
34 New line is supported and automatical wrapping text is also supported.
35 And you can choose font, this text is now rendered by '%s'
36 
37 You can specify background color and foreground color separatelly.
38 
39 Of course, the text is not needed to be fixed, see the counter: %d.
40 
41 You can change text color like <span style="color: red;">this</span>
42 by using <span style="font-style: italic;">css</style>.
43  """ % (rate, text.font, counter)
44  text.fg_color = ColorRGBA(25 / 255.0, 1.0, 240.0 / 255.0, 1.0)
45  text.bg_color = ColorRGBA(0.0, 0.0, 0.0, 0.2)
46  text_pub.publish(text)
47  value_pub.publish(math.sin(counter * math.pi * 2 / 100))
48  if int(counter % 500) == 0:
49  rospy.logdebug('This is ROS_DEBUG.')
50  elif int(counter % 500) == 100:
51  rospy.loginfo('This is ROS_INFO.')
52  elif int(counter % 500) == 200:
53  rospy.logwarn('This is ROS_WARN.')
54  elif int(counter % 500) == 300:
55  rospy.logerr('This is ROS_ERROR.')
56  elif int(counter % 500) == 400:
57  rospy.logfatal('This is ROS_FATAL.')
58  r.sleep()
59 


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Sat Mar 20 2021 03:03:18