Go to the documentation of this file.00001
00002
00003 import rospy
00004
00005 from sound_play.msg import SoundRequest
00006 from sound_play.libsoundplay import SoundClient
00007
00008 if __name__ == '__main__':
00009 rospy.init_node('battery_guard')
00010 soundclient = SoundClient()
00011
00012 last_complain= rospy.Time()
00013 r= rospy.Rate(.1)
00014 while not rospy.is_shutdown():
00015 with open('/sys/class/power_supply/BAT0/capacity') as f:
00016 capacity= int(f.readline().rstrip())
00017 with open('/sys/class/power_supply/BAT0/status') as f:
00018 status= f.readline().rstrip()
00019 if status != "Charging" and rospy.Time.now() - last_complain > rospy.Duration(60):
00020 if capacity < 10:
00021 rospy.logerr("No battery power remaining. Connect the robot laptop to power immediately.")
00022 soundclient.play(SoundRequest.NEEDS_PLUGGING_BADLY)
00023 last_complain= rospy.Time.now()
00024 elif capacity < 15:
00025 rospy.logwarn("Only little battery power remaining. Please connect the robot laptop to power.")
00026 soundclient.play(SoundRequest.NEEDS_PLUGGING)
00027 last_complain= rospy.Time.now()
00028 r.sleep()