Go to the documentation of this file.00001
00002
00003 import rospy
00004 from jsk_rviz_plugins.msg import OverlayText
00005 from std_msgs.msg import Int32
00006
00007
00008 def callback(msg):
00009 global pub
00010 count = msg.data
00011 text = OverlayText()
00012 color = (52, 152, 219)
00013 text.fg_color.r = color[0] / 255.0
00014 text.fg_color.g = color[1] / 255.0
00015 text.fg_color.b = color[2] / 255.0
00016 text.fg_color.a = 1.0
00017 text.bg_color.a = 0.0
00018 text.text = "Samples: %d" % (count)
00019 text.width = 500
00020 text.height = 100
00021 text.left = 10
00022 text.top = 10
00023 text.text_size = 30
00024 pub.publish(text)
00025
00026 def main():
00027 global pub
00028 pub = rospy.Publisher("capture_text", OverlayText)
00029 sub = rospy.Subscriber("capture_count", Int32, callback)
00030 rospy.spin()
00031
00032 if __name__ == "__main__":
00033 rospy.init_node("capture_rviz_text")
00034 main()