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
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 import time
00036 import rospy
00037 from std_msgs.msg import Bool
00038 from pr2_msgs.msg import PowerBoardState, PowerState, DashboardState, AccessPoint
00039
00040 class DashboardAggregator:
00041 def __init__(self):
00042 self.msg = DashboardState()
00043
00044
00045 self.pub = rospy.Publisher("dashboard_agg", DashboardState)
00046
00047
00048
00049 rospy.Subscriber("power_board/state", PowerBoardState, self.powerBoardCB)
00050 self.last_power_board_state = 0
00051
00052 rospy.Subscriber("power_state", PowerState, self.powerCB)
00053 self.last_power_state = 0
00054
00055 rospy.Subscriber("ddwrt/accesspoint", AccessPoint, self.accessPointCB)
00056 self.last_access_point = 0
00057
00058 rospy.Subscriber("pr2_etherCAT/motors_halted", Bool, self.motorsHaltedCB)
00059 self.last_motors_halted = 0
00060
00061 def motorsHaltedCB(self, msg):
00062 self.last_motors_halted = time.time()
00063 self.msg.motors_halted = msg
00064
00065 def powerBoardCB(self, msg):
00066 self.last_power_board_state = time.time()
00067 self.msg.power_board_state = msg
00068
00069 def powerCB(self, msg):
00070 self.last_power_state = time.time()
00071 self.msg.power_state = msg
00072
00073 def accessPointCB(self, msg):
00074 self.last_access_point = time.time()
00075 self.msg.access_point = msg
00076
00077 def publish(self):
00078 now = time.time()
00079 self.msg.motors_halted_valid = (now - self.last_motors_halted) < 3
00080 self.msg.power_board_state_valid = (now - self.last_power_board_state) < 3
00081 self.msg.power_state_valid = (now - self.last_power_state) < 25
00082 self.msg.access_point_valid = (now - self.last_access_point) < 5
00083 self.pub.publish(self.msg)
00084
00085 def main():
00086 rospy.init_node("pr2_dashboard_aggregator")
00087 da = DashboardAggregator()
00088 r = rospy.Rate(1)
00089 while not rospy.is_shutdown():
00090 da.publish()
00091 try:
00092 r.sleep()
00093 except rospy.exceptions.ROSInterruptException:
00094 rospy.logdebug('Sleep interrupted')
00095
00096 if __name__ == "__main__":
00097 main()