Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 import time
00019 import rospy
00020 from cob_msgs.msg import EmergencyStopState, PowerState, DashboardState
00021 from diagnostic_msgs.msg import DiagnosticStatus
00022
00023 class DashboardAggregator:
00024 def __init__(self):
00025 self.msg = DashboardState()
00026
00027
00028 self.pub = rospy.Publisher("dashboard_agg", DashboardState, queue_size=1)
00029
00030
00031
00032 rospy.Subscriber("diagnostics_toplevel_state", DiagnosticStatus, self.DiagnosticStatusCB)
00033
00034 rospy.Subscriber("power_state", PowerState, self.PowerStateCB)
00035
00036 rospy.Subscriber("emergency_stop_state", EmergencyStopState, self.EmergencyStopStateCB)
00037
00038 def DiagnosticStatusCB(self, msg):
00039 self.msg.diagnostics_toplevel_state = msg
00040
00041 def PowerStateCB(self, msg):
00042 self.msg.power_state = msg
00043
00044 def EmergencyStopStateCB(self, msg):
00045 self.msg.emergency_stop_state = msg
00046
00047 def publish(self):
00048 now = time.time()
00049 self.pub.publish(self.msg)
00050
00051 if __name__ == "__main__":
00052 rospy.init_node("cob_dashboard_aggregator")
00053 rospy.sleep(1)
00054 da = DashboardAggregator()
00055 r = rospy.Rate(1)
00056 while not rospy.is_shutdown():
00057 da.publish()
00058 try:
00059 r.sleep()
00060 except rospy.exceptions.ROSInterruptException as e:
00061 pass