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