relayboard_sim.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00004 #
00005 # Licensed under the Apache License, Version 2.0 (the "License");
00006 # you may not use this file except in compliance with the License.
00007 # You may obtain a copy of the License at
00008 #
00009 #   http://www.apache.org/licenses/LICENSE-2.0
00010 #
00011 # Unless required by applicable law or agreed to in writing, software
00012 # distributed under the License is distributed on an "AS IS" BASIS,
00013 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00014 # See the License for the specific language governing permissions and
00015 # limitations under the License.
00016 
00017 
00018 import rospy
00019 from std_msgs.msg import Float64
00020 from cob_msgs.msg import EmergencyStopState
00021 
00022 def relayboard_sim():
00023         rospy.init_node('cob_relayboard_sim')
00024 
00025         # emergency_stop topic
00026         pub_em_stop = rospy.Publisher('emergency_stop_state', EmergencyStopState, queue_size=1)
00027         msg_em = EmergencyStopState()
00028         msg_em.emergency_button_stop = False
00029         msg_em.scanner_stop = False
00030         msg_em.emergency_state = 0
00031 
00032         # voltage topic
00033         pub_voltage = rospy.Publisher('voltage', Float64, queue_size=1)
00034         msg_voltage = Float64()
00035         msg_voltage.data = 48.0 # in simulation battery is always full
00036 
00037         while not rospy.is_shutdown():
00038                 pub_em_stop.publish(msg_em)
00039                 pub_voltage.publish(msg_voltage)
00040                 rospy.sleep(1.0)
00041 
00042 if __name__ == '__main__':
00043         try:
00044                 relayboard_sim()
00045         except rospy.ROSInterruptException:
00046                 print "Interupted"
00047                 pass


cob_relayboard
Author(s): Christian Connette
autogenerated on Sat Jun 8 2019 21:02:18