20 from cob_msgs.msg
import EmergencyStopState, PowerState, DashboardState
21 from diagnostic_msgs.msg
import DiagnosticStatus
25 self.
msg = DashboardState()
28 self.
pub = rospy.Publisher(
"dashboard_agg", DashboardState, queue_size=1)
32 rospy.Subscriber(
"diagnostics_toplevel_state", DiagnosticStatus, self.
DiagnosticStatusCB)
34 rospy.Subscriber(
"power_state", PowerState, self.
PowerStateCB)
39 self.msg.diagnostics_toplevel_state = msg
42 self.msg.power_state = msg
45 self.msg.emergency_stop_state = msg
48 self.pub.publish(self.
msg)
50 if __name__ ==
"__main__":
51 rospy.init_node(
"cob_dashboard_aggregator")
55 while not rospy.is_shutdown():
59 except rospy.exceptions.ROSInterruptException
as e:
def PowerStateCB(self, msg)
def DiagnosticStatusCB(self, msg)
def EmergencyStopStateCB(self, msg)