cob_dashboard_aggregator.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 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     # Create publisher
00028     self.pub = rospy.Publisher("dashboard_agg", DashboardState, queue_size=1)
00029 
00030     # Create subscribers
00031     # Diagnostics
00032     rospy.Subscriber("diagnostics_toplevel_state", DiagnosticStatus, self.DiagnosticStatusCB)
00033     # Power state
00034     rospy.Subscriber("power_state", PowerState, self.PowerStateCB)
00035     # Emergency stop state
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


cob_dashboard
Author(s): Alexander Bubeck
autogenerated on Sun Jun 9 2019 20:20:03