37 from std_msgs.msg
import Bool
38 from pr2_msgs.msg
import PowerBoardState, PowerState, DashboardState, AccessPoint
42 self.
msg = DashboardState()
45 self.
pub = rospy.Publisher(
"dashboard_agg", DashboardState, queue_size=10)
49 rospy.Subscriber(
"power_board/state", PowerBoardState, self.
powerBoardCB)
52 rospy.Subscriber(
"power_state", PowerState, self.
powerCB)
55 rospy.Subscriber(
"ddwrt/accesspoint", AccessPoint, self.
accessPointCB)
58 rospy.Subscriber(
"pr2_etherCAT/motors_halted", Bool, self.
motorsHaltedCB)
63 self.msg.motors_halted = msg
67 self.msg.power_board_state = msg
71 self.msg.power_state = msg
75 self.msg.access_point = msg
83 self.pub.publish(self.
msg)
86 rospy.init_node(
"pr2_dashboard_aggregator")
89 while not rospy.is_shutdown():
93 except rospy.exceptions.ROSInterruptException:
94 rospy.logdebug(
'Sleep interrupted')
96 if __name__ ==
"__main__":
def motorsHaltedCB(self, msg)
def accessPointCB(self, msg)
def powerBoardCB(self, msg)