battery_monitor.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 rospy
00019 import colorsys
00020 import copy
00021 import actionlib
00022 
00023 from std_msgs.msg import *
00024 from cob_msgs.msg import *
00025 from cob_light.msg import *
00026 from cob_light.srv import *
00027 
00028 from simple_script_server import *
00029 sss = simple_script_server()
00030 
00031 
00032 class battery_monitor():
00033 
00034     def __init__(self):
00035         self.power_state = PowerState()
00036         self.relative_remaining_capacity = 0.0
00037         self.temperature = 0.0
00038         self.is_charging = False
00039         self.topic_name = 'power_state'
00040         self.mode = LightMode()
00041 
00042         self.threshold_warning = rospy.get_param("~threshold_warning", 20.0) # % of battery level
00043         self.threshold_error = rospy.get_param("~threshold_error", 10.0)     # % of battery level
00044         self.threshold_critical = rospy.get_param("~threshold_critical", 5.0)# % of battery level
00045 
00046         self.enable_light = rospy.get_param("~enable_light", True)
00047         self.num_leds = rospy.get_param("~num_leds", 1)
00048         self.track_id_light = {}
00049         if self.enable_light:
00050             if not rospy.has_param("~light_components"):
00051                 rospy.logwarn("parameter light_components does not exist on ROS Parameter Server")
00052                 return
00053             self.light_components = rospy.get_param("~light_components")
00054             for component in self.light_components:
00055                 self.track_id_light[component] = None
00056             self.mode = LightMode()
00057             self.mode.priority = 8
00058 
00059         self.enable_sound = rospy.get_param("~enable_sound", True)
00060         self.sound_components = {}
00061         if self.enable_sound:
00062             if not rospy.has_param("~sound_components"):
00063                 rospy.logwarn("parameter sound_components does not exist on ROS Parameter Server")
00064                 return
00065             self.sound_components = rospy.get_param("~sound_components")
00066 
00067         self.sound_critical = rospy.get_param("~sound_critical", "My battery is empty, please recharge now.")
00068         self.sound_warning = rospy.get_param("~sound_warning", "My battery is nearly empty, please consider recharging.")
00069 
00070         self.last_time_warned = rospy.get_time()
00071         self.last_time_power_received = rospy.get_time()
00072         rospy.Subscriber(self.topic_name, PowerState, self.power_callback)
00073 
00074         rospy.Timer(rospy.Duration(1), self.timer_callback)
00075 
00076     def power_callback(self, msg):
00077         self.last_time_power_received = rospy.get_time()
00078         self.power_state = msg
00079 
00080     def set_light(self, mode, track=False):
00081         if self.enable_light:
00082             for component in self.light_components:
00083                 action_server_name = component + "/set_light"
00084                 client = actionlib.SimpleActionClient(action_server_name, SetLightModeAction)
00085                 # trying to connect to server
00086                 rospy.logdebug("waiting for %s action server to start",action_server_name)
00087                 if not client.wait_for_server(rospy.Duration(5)):
00088                     # error: server did not respond
00089                     rospy.logerr("%s action server not ready within timeout, aborting...", action_server_name)
00090                 else:
00091                     rospy.logdebug("%s action server ready",action_server_name)
00092 
00093                     # sending goal
00094                     goal = SetLightModeGoal()
00095                     goal.mode = mode
00096                     client.send_goal(goal)
00097                     client.wait_for_result()
00098                     res = client.get_result()
00099                     if track:
00100                         self.track_id_light[component] = res.track_id
00101 
00102     def stop_light(self):
00103         if self.enable_light:
00104             for component in self.light_components:
00105                 if self.track_id_light[component] is not None:
00106                     srv_server_name = component + "/stop_mode"
00107                     try:
00108                         rospy.wait_for_service(srv_server_name, timeout=2)
00109                         srv_proxy = rospy.ServiceProxy(srv_server_name, StopLightMode)
00110                         req = StopLightModeRequest()
00111                         req.track_id = self.track_id_light[component]
00112                         srv_proxy(req)
00113                         self.track_id_light[component] = None
00114                     except Exception as e:
00115                         rospy.logerr("%s service failed: %s",srv_server_name, e)
00116 
00117     def say(self, text):
00118         if self.enable_sound:
00119             for component in self.sound_components:
00120                 sss.say(component, [text])
00121 
00122     def timer_callback(self, event):
00123         # warn if battery is empty
00124         if self.is_charging == False:
00125             # 5%
00126             if self.power_state.relative_remaining_capacity <= self.threshold_critical and (rospy.get_time() - self.last_time_warned) > 5:
00127                 self.last_time_warned = rospy.get_time()
00128                 mode = copy.copy(self.mode)
00129                 mode.mode = LightModes.FLASH
00130                 color = ColorRGBA(1, 0, 0, 1)
00131                 mode.colors = []
00132                 mode.colors.append(color)
00133                 mode.frequency = 5
00134                 mode.pulses = 4
00135                 self.set_light(mode)
00136 
00137                 self.say(self.sound_critical)
00138 
00139             # 10%
00140             elif self.power_state.relative_remaining_capacity <= self.threshold_error and (rospy.get_time() - self.last_time_warned) > 15:
00141                 self.last_time_warned = rospy.get_time()
00142                 mode = copy.copy(self.mode)
00143                 mode.mode = LightModes.FLASH
00144                 color = ColorRGBA(1, 0, 0, 1)
00145                 mode.colors = []
00146                 mode.colors.append(color)
00147                 mode.frequency = 2
00148                 mode.pulses = 2
00149                 self.set_light(mode)
00150             # 20%
00151             elif self.power_state.relative_remaining_capacity <= self.threshold_warning and (rospy.get_time() - self.last_time_warned) > 30:
00152                 self.last_time_warned = rospy.get_time()
00153                 mode = copy.copy(self.mode)
00154                 mode.mode = LightModes.FLASH
00155                 color = ColorRGBA(1, 1, 0, 1)
00156                 mode.colors = []
00157                 mode.colors.append(color)
00158                 mode.frequency = 2
00159                 mode.pulses = 2
00160                 self.set_light(mode)
00161 
00162                 self.say(self.sound_warning)
00163 
00164         if self.is_charging == False and self.power_state.charging == True:
00165             self.is_charging = True
00166 
00167         if self.is_charging == True and (self.power_state.charging == False
00168                                     or (rospy.get_time() - self.last_time_power_received) > 2):
00169             self.is_charging = False
00170             self.relative_remaining_capacity = 0.0
00171             self.stop_light()
00172 
00173         elif self.is_charging == True:
00174             # only change color mode if capacity change is bigger than 2%
00175             if abs(self.relative_remaining_capacity - self.power_state.relative_remaining_capacity) > 2:
00176                 rospy.logdebug('adjusting leds')
00177                 mode = copy.copy(self.mode)
00178                 if self.num_leds > 1:
00179                     leds = int(self.num_leds * self.power_state.relative_remaining_capacity / 100.)
00180                     mode.mode = LightModes.CIRCLE_COLORS
00181                     mode.frequency = 60.0
00182                     mode.colors = []
00183                     color = ColorRGBA(0.0, 1.0, 0.7, 0.4)
00184                     for i in range(leds):
00185                         mode.colors.append(color)
00186                 else:
00187                     mode.mode = LightModes.BREATH
00188                     mode.frequency = 0.4
00189                     # 0.34 => green in hsv space
00190                     hue = 0.34 * (self.power_state.relative_remaining_capacity / 100.0)
00191                     rgb = colorsys.hsv_to_rgb(hue, 1, 1)
00192                     color = ColorRGBA(rgb[0], rgb[1], rgb[2], 1.0)
00193                     mode.colors = []
00194                     mode.colors.append(color)
00195 
00196                 self.relative_remaining_capacity = self.power_state.relative_remaining_capacity
00197                 self.set_light(mode, True)
00198 
00199 
00200 if __name__ == "__main__":
00201     rospy.init_node("battery_monitor")
00202     battery_monitor()
00203     rospy.spin()


cob_monitoring
Author(s): Florian Weisshardt , Felix Messmer
autogenerated on Sun Jun 9 2019 20:20:19