tracking_info.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # it depends on jsk_rviz_plugins
4 
5 import rospy
6 from jsk_rviz_plugins.msg import OverlayText
7 from std_msgs.msg import Float32
8 from threading import Lock
9 from jsk_rviz_plugins.overlay_text_interface import OverlayTextInterface
10 from jsk_recognition_msgs.msg import TrackerStatus
11 g_lock = Lock()
12 g_angle_error_msg = None
13 g_distance_error_msg = None
15  global g_angle_error_msg
16  with g_lock:
17  g_angle_error_msg = msg
19  global g_distance_error_msg
20  with g_lock:
21  g_distance_error_msg = msg
22 def publish_text(event):
23  with g_lock:
24  if g_distance_error_msg and g_angle_error_msg:
25  text_interface.publish("""RMS Distance Error: {0}
26 RMS Angular Error: {1}""".format(g_distance_error_msg.data, g_angle_error_msg.data))
27 
28 
29 if __name__ == "__main__":
30  rospy.init_node("tracking_info")
31  text_interface = OverlayTextInterface("~text")
32  sub = rospy.Subscriber("~rms_angle_error", Float32, angle_error_callback)
33  sub2 = rospy.Subscriber("~rms_distance_error", Float32, distance_error_callback)
34  rospy.Timer(rospy.Duration(0.1), publish_text)
35  rospy.spin()
def angle_error_callback(msg)
def distance_error_callback(msg)
def publish_text(event)


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47