19 from std_msgs.msg
import Float64
20 from cob_msgs.msg
import EmergencyStopState
23 rospy.init_node(
'cob_relayboard_sim')
26 pub_em_stop = rospy.Publisher(
'emergency_stop_state', EmergencyStopState, queue_size=1)
27 msg_em = EmergencyStopState()
28 msg_em.emergency_button_stop =
False
29 msg_em.scanner_stop =
False
30 msg_em.emergency_state = 0
33 pub_voltage = rospy.Publisher(
'voltage', Float64, queue_size=1)
34 msg_voltage = Float64()
35 msg_voltage.data = 48.0
37 while not rospy.is_shutdown():
38 pub_em_stop.publish(msg_em)
39 pub_voltage.publish(msg_voltage)
42 if __name__ ==
'__main__':
45 except rospy.ROSInterruptException: