nao_diagnostic_updater.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # This script collects diagnostic information on a Nao robot and publishes
00004 # the information as DiagnosticArray messages.
00005 #
00006 # This script was written and tested with NaoQI 1.10.52 and will probably
00007 # fail on 1.12+ as some ALMemory keys and device paths have changed.
00008 #
00009 # You can run this script either on the robot or on a remote machine,
00010 # however, CPU temperature and network status will only be available if the
00011 # script runs directly on the robot.
00012 #
00013 
00014 # Copyright 2011-2012 Stefan Osswald, University of Freiburg
00015 #
00016 # Redistribution and use in source and binary forms, with or without
00017 # modification, are permitted provided that the following conditions are met:
00018 #
00019 #    # Redistributions of source code must retain the above copyright
00020 #       notice, this list of conditions and the following disclaimer.
00021 #    # Redistributions in binary form must reproduce the above copyright
00022 #       notice, this list of conditions and the following disclaimer in the
00023 #       documentation and/or other materials provided with the distribution.
00024 #    # Neither the name of the University of Freiburg nor the names of its
00025 #       contributors may be used to endorse or promote products derived from
00026 #       this software without specific prior written permission.
00027 #
00028 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00029 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00030 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00031 # ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00032 # LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00033 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00034 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00035 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00036 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00037 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00038 # POSSIBILITY OF SUCH DAMAGE.
00039 #
00040 
00041 
00042 import roslib
00043 roslib.load_manifest('nao_diagnostic')
00044 import rospy
00045 
00046 import dbus
00047 from dbus.exceptions import DBusException
00048 
00049 from nao_driver import *
00050 import threading
00051 from threading import Thread
00052 
00053 from diagnostic_msgs.msg import *
00054 
00055 import naoqi
00056 
00057 class NaoDiagnosticUpdater(NaoNode,Thread):
00058     def __init__(self):
00059         NaoNode.__init__(self)
00060         Thread.__init__(self)
00061         
00062         # ROS initialization:
00063         rospy.init_node('nao_diagnostic_updater')        
00064         self.connectNaoQi()
00065         self.stopThread = False
00066 
00067         # Read parameters:
00068         self.sleep = 1.0/rospy.get_param('~update_rate', 0.5)  # update rate in Hz
00069         self.warningThreshold = rospy.get_param('~warning_threshold', 68) # warning threshold for joint temperatures
00070         self.errorThreshold = rospy.get_param('~error_threshold', 74)     # error threshold for joint temperatures
00071         self.runsOnRobot = naoqi.ON_GEODE   # if temperature device files cannot be opened, this flag will be set to False later.
00072 
00073         # Lists with interesting ALMemory keys
00074         self.jointNamesList = self.motionProxy.getJointNames('Body')    
00075         self.jointTempPathsList = []
00076         self.jointStiffPathsList = []    
00077         for i in range(0, len(self.jointNamesList)):
00078             self.jointTempPathsList.append("Device/SubDeviceList/%s/Temperature/Sensor/Value" % self.jointNamesList[i])
00079             self.jointStiffPathsList.append("Device/SubDeviceList/%s/Hardness/Actuator/Value" % self.jointNamesList[i])
00080 
00081         self.batteryNamesList = ["Percentage", "Status"]
00082         self.batteryPathsList = ["Device/SubDeviceList/Battery/Charge/Sensor/Value", 
00083                                  "Device/SubDeviceList/Battery/Charge/Sensor/Status",
00084                                  "Device/SubDeviceList/Battery/Current/Sensor/Value"]
00085         
00086         self.deviceInfoList = ["Device/DeviceList/ChestBoard/BodyId"]
00087         deviceInfoData = self.memProxy.getListData(self.deviceInfoList)
00088         if(len(deviceInfoData) > 1 and isinstance(deviceInfoData[1], list)):
00089             deviceInfoData = deviceInfoData[1]
00090         if(deviceInfoData[0] is None):
00091             # No device info -> running in a simulation
00092             self.isSimulator = True
00093             if(self.pip.startswith("127.") or self.pip == "localhost"):
00094                 # Replace localhost with hostname of the machine
00095                 f = open("/etc/hostname")
00096                 self.hardwareID = "%s:%d"%(f.readline().rstrip(), self.pport)
00097                 f.close()
00098             else:
00099                 self.hardwareID = "%s:%d"%(self.pip, self.pport)            
00100         else:
00101             self.hardwareID = deviceInfoData[0].rstrip()
00102             self.isSimulator = False
00103             
00104         # init. messages:        
00105         self.diagnosticPub = rospy.Publisher("diagnostics", DiagnosticArray)
00106 
00107         rospy.loginfo("nao_diagnostic_updater initialized")
00108 
00109     # (re-) connect to NaoQI:
00110     def connectNaoQi(self):
00111         """ Connects to NaoQi and gets proxies to ALMotion and ALMemory. """
00112         rospy.loginfo("Connecting to NaoQi at %s:%d", self.pip, self.pport)
00113         self.motionProxy = self.getProxy("ALMotion")
00114         self.memProxy = self.getProxy("ALMemory")
00115         
00116     def run(self):
00117         """ Diagnostic thread code - collects and sends out diagnostic data. """
00118         while(not self.stopThread):
00119             timestamp = rospy.Time.now()
00120             try:
00121                 # Get data from robot
00122                 jointsTempData = self.memProxy.getListData(self.jointTempPathsList)
00123                 jointsStiffData = self.memProxy.getListData(self.jointStiffPathsList)
00124                 batteryData = self.memProxy.getListData(self.batteryPathsList)
00125                 if isinstance(jointsTempData[1], list):
00126                     # Some naoqi versions provide data in [0, [data1, data2, ...], timestamp] format,
00127                     # others just as [data1, data2, ...]
00128                     # --> get data list                    
00129                     jointsTempData = jointsTempData[1]
00130                     jointsStiffData = jointsStiffData[1]
00131                     batteryData = batteryData[1]
00132             except RuntimeError,e:
00133                 print "Error accessing ALMemory, exiting...\n"
00134                 print e
00135                 rospy.signal_shutdown("No NaoQI available anymore")
00136 
00137             diagnosticArray = DiagnosticArray()
00138             
00139             # Process joint temperature and stiffness
00140             for i in range(0, len(self.jointTempPathsList)):
00141                 status = DiagnosticStatus()
00142                 status.hardware_id = "%s#%s"%(self.hardwareID, self.jointNamesList[i])           
00143                 status.name = "nao_joint: %s" % self.jointNamesList[i]                
00144                 kv = KeyValue()
00145                 kv.key = "Temperature"
00146                 temperature = jointsTempData[i]
00147                 kv.value = str(temperature)
00148                 status.values.append(kv)
00149                 kv = KeyValue()
00150                 kv.key = "Stiffness"
00151                 if self.jointNamesList[i] == "RHipYawPitch":
00152                     # same joint as LHipYawPitch, does not provide data
00153                     kv.value = "None"
00154                 else:
00155                     kv.value = str(jointsStiffData[i])
00156                 status.values.append(kv)
00157                 if (type(temperature) != float and type(temperature) != int) or self.jointNamesList[i] == "RHipYawPitch":
00158                     status.level = DiagnosticStatus.OK
00159                     status.message = "No temperature sensor"
00160                 elif temperature < self.warningThreshold:
00161                     status.level = DiagnosticStatus.OK
00162                     status.message = "Normal: %3.1f C" % temperature
00163                 elif temperature < self.errorThreshold:
00164                     status.level = DiagnosticStatus.WARN
00165                     status.message = "Hot: %3.1f C" % temperature
00166                 else:
00167                     status.level = DiagnosticStatus.ERROR
00168                     status.message = "Too hot: %3.1f C" % temperature
00169                 diagnosticArray.status.append(status)
00170                         
00171             # Process battery status flags
00172             status = DiagnosticStatus()
00173             status.hardware_id = "%s#%s"%(self.hardwareID, "battery")
00174             status.name ="nao_power: Battery"
00175             kv = KeyValue()
00176             kv.key = "Percentage"
00177             if batteryData[0] is None:
00178                 kv.value = "unknown"
00179             else:
00180                 kv.value = str(batteryData[0] * 100)
00181             status.values.append(kv)
00182 
00183             # Battery status: See http://www.aldebaran-robotics.com/documentation/naoqi/sensors/dcm/pref_file_architecture.html?highlight=discharge#charge-for-the-battery
00184             # Note: SANYO batteries use different keys!
00185             statuskeys = ["End off Discharge flag", "Near End Off Discharge flag", "Charge FET on", "Discharge FET on", "Accu learn flag", "Discharging flag", "Full Charge Flag", "Charge Flag", "Charge Temperature Alarm", "Over Charge Alarm", "Discharge Alarm", "Charge Over Current Alarm", "Discharge Over Current Alarm (14A)", "Discharge Over Current Alarm (6A)", "Discharge Temperature Alarm", "Power-Supply present" ]
00186                         
00187             for j in range(0, 16):
00188                 kv = KeyValue()
00189                 kv.key = statuskeys[j]
00190                 if batteryData[1] is None:
00191                     kv.value = "unknown"
00192                 elif int(batteryData[1]) & 1<<j:
00193                     kv.value = "True"
00194                 else:
00195                     kv.value = "False"
00196                 status.values.append(kv)
00197                 
00198             kv = KeyValue()
00199             kv.key = "Status"
00200             if batteryData[1] is None:
00201                 kv.value = "unknown"
00202             else:
00203                 kv.value = bin(batteryData[1])
00204             status.values.append(kv)
00205 
00206             # Process battery charge level
00207             if batteryData[0] is None:
00208                 status.level = DiagnosticStatus.OK
00209                 status.message = "Battery status unknown, assuming simulation"
00210             elif int(batteryData[1]) & 1<<6:
00211                 status.level = DiagnosticStatus.OK
00212                 status.message = "Battery fully charged"
00213             elif int(batteryData[1]) & 1<<7:
00214                 status.level = DiagnosticStatus.OK
00215                 status.message = "Charging (%3.1f%%)" % (batteryData[0] * 100)
00216             elif batteryData[0] > 0.60:
00217                 status.level = DiagnosticStatus.OK
00218                 status.message = "Battery OK (%3.1f%% left)" % (batteryData[0] * 100)
00219             elif batteryData[0] > 0.30:
00220                 status.level = DiagnosticStatus.WARN
00221                 status.message = "Battery discharging (%3.1f%% left)" % (batteryData[0] * 100)
00222             else:
00223                 status.level = DiagnosticStatus.ERROR
00224                 status.message = "Battery almost empty (%3.1f%% left)" % (batteryData[0] * 100)
00225             diagnosticArray.status.append(status)
00226             
00227 
00228             # Process battery current
00229             status = DiagnosticStatus()
00230             status.hardware_id = "%s#%s"%(self.hardwareID, "power")
00231             status.name = "nao_power: Current"
00232              
00233             if batteryData[2] is None:
00234                 status.level = DiagnosticStatus.OK
00235                 status.message = "Total Current: unknown"
00236             else:
00237                 kv = KeyValue()
00238                 kv.key = "Current"
00239                 kv.value = str(batteryData[2])
00240                 status.values.append(kv)
00241                 status.level = DiagnosticStatus.OK
00242                 if batteryData[2] > 0:
00243                     currentStatus = "charging"
00244                 else:
00245                     currentStatus = "discharging"
00246                 status.message = "Total Current: %3.2f Ampere (%s)" % (batteryData[2], currentStatus)
00247             diagnosticArray.status.append(status)
00248 
00249             # Process CPU and head temperature
00250             status = DiagnosticStatus()
00251             status.hardware_id = "%s#%s"%(self.hardwareID, "cpu")
00252             status.name = "nao_cpu: Head Temperature"
00253             temp = self.temp_get()
00254             kv = KeyValue()
00255             kv.key = "CPU Temperature"
00256             kv.value = str(temp['HeadSilicium'])
00257             status.values.append(kv)
00258             kv = KeyValue()
00259             kv.key = "Board Temperature"
00260             kv.value = str(temp['HeadBoard'])            
00261             status.values.append(kv)
00262             if(temp['HeadSilicium'] == "invalid"):
00263                 status.level = DiagnosticStatus.OK
00264                 status.message = "unknown, assuming simulation"
00265             else:
00266                 status.message = "%3.2f deg C" % (temp['HeadSilicium'])
00267                 if temp['HeadSilicium'] < 100:
00268                     status.level = DiagnosticStatus.OK
00269                 elif temp['HeadSilicium'] < 105:
00270                     status.level = DiagnosticStatus.WARN
00271                 else:
00272                     status.level = DiagnosticStatus.ERROR                    
00273             diagnosticArray.status.append(status)            
00274             
00275             
00276             # Process WIFI and LAN status
00277             statusWifi = DiagnosticStatus()
00278             statusWifi.hardware_id = "%s#%s"%(self.hardwareID, "wlan")
00279             statusWifi.name = "nao_wlan: Status"
00280             
00281             statusLan = DiagnosticStatus()
00282             statusLan.hardware_id = "%s#%s"%(self.hardwareID, "ethernet")
00283             statusLan.name = "nao_ethernet: Status"
00284             
00285             if self.runsOnRobot:
00286                 statusLan.level = DiagnosticStatus.ERROR
00287                 statusLan.message = "offline"
00288                 statusWifi.level = DiagnosticStatus.ERROR
00289                 statusWifi.message = "offline"                              
00290                 systemBus = dbus.SystemBus()
00291                 try:
00292                     manager = dbus.Interface(systemBus.get_object("org.moblin.connman", "/"), "org.moblin.connman.Manager")
00293                 except DBusException as e:
00294                     self.runsOnRobot = False
00295                 if self.runsOnRobot:
00296                     properties = manager.GetProperties()
00297                     for property in properties["Services"]:
00298                         service = dbus.Interface(systemBus.get_object("org.moblin.connman", property), "org.moblin.connman.Service")
00299                         try:
00300                             props = service.GetProperties()
00301                         except DBusException as e:
00302                             continue # WLAN network probably disappeared meanwhile
00303                         
00304                         state = str(props.get("State", "None"))
00305                         if state == "idle":
00306                             pass # other network, not connected 
00307                         else:                 
00308                             nettype = str(props.get("Type", "<unknown>"))
00309                             if(nettype == "wifi"):
00310                                 status = statusWifi
00311                             else:
00312                                 status = statusLan   
00313                             kv = KeyValue()
00314                             kv.key = "Network"
00315                             kv.value = str(props.get("Name", "<unknown>"))                    
00316                             status.values.append(kv)
00317                             if nettype == "wifi":
00318                                 strength = int(props.get("Strength", "<unknown>"))
00319                                 kv = KeyValue()
00320                                 kv.key = "Strength"
00321                                 kv.value = "%d%%"%strength
00322                                 status.values.append(kv)
00323                             else:
00324                                 strength = None                    
00325                             kv = KeyValue()
00326                             kv.key = "Type"
00327                             kv.value = nettype
00328                             status.values.append(kv)
00329                             if strength is None:
00330                                 status.message = state
00331                             else:
00332                                 status.message = "%s (%d%%)"%(state, strength)
00333                                 
00334                             if state in ["online", "ready"]:
00335                                 status.level = DiagnosticStatus.OK
00336                             elif state in ["configuration", "association"]:
00337                                 status.level = DiagnosticStatus.WARN
00338                             else: # can only be 'failure'
00339                                 status.message = str("%s (%s)"%(state, props.get("Error")))
00340                                 status.level = DiagnosticStatus.ERROR
00341             else:
00342                 statusWifi.level = DiagnosticStatus.OK
00343                 statusWifi.message = "nao_diagnostic_updater not running on robot, cannot determine WLAN status"
00344                                 
00345                 statusLan.level = DiagnosticStatus.OK
00346                 statusLan.message = "nao_diagnostic_updater not running on robot, cannot determine Ethernet status"
00347                                         
00348             diagnosticArray.status.append(statusWifi)   
00349             diagnosticArray.status.append(statusLan)   
00350             
00351             # Publish all diagnostic messages
00352             diagnosticArray.header.stamp = rospy.Time.now()                                  
00353             self.diagnosticPub.publish(diagnosticArray)                             
00354             rospy.sleep(self.sleep)
00355             
00356     def temp_get(self):
00357         """Read the CPU and head temperature from the system devices.
00358 
00359         Returns {'HeadSilicium': <temperature>, 'HeadBoard': <temperature>}
00360 
00361         Temperatures are returned as float values in degrees Celsius, or
00362         as the string 'invalid' if the sensors are not accessible.
00363         """
00364         temp = {'HeadSilicium': 'invalid', 'HeadBoard': 'invalid'}
00365         if(self.runsOnRobot):
00366             try:
00367                 f = open("/sys/class/i2c-adapter/i2c-1/1-004c/temp2_input")
00368                 temp['HeadSilicium'] = float(f.readline()) / 1000.
00369                 f.close()
00370             except IOError:
00371                 self.runsOnRobot = False
00372                 return temp
00373             except:
00374                 temp['HeadSilicium'] = "invalid"
00375             try:
00376                 f = open("/sys/class/i2c-adapter/i2c-1/1-004c/temp1_input")
00377                 temp['HeadBoard'] = float(f.readline()) / 1000.
00378                 f.close()
00379             except IOError:
00380                 self.runsOnRobot = False
00381                 return temp
00382             except:
00383                 temp['HeadBoard'] = "invalid"
00384         return temp
00385 
00386 
00387 if __name__ == '__main__':
00388     
00389     updater = NaoDiagnosticUpdater()
00390     updater.start()
00391     
00392     rospy.spin()
00393     
00394     rospy.loginfo("Stopping nao_diagnostic_updater ...")
00395     updater.stopThread = True
00396     updater.join()
00397     
00398     rospy.loginfo("nao_diagnostic_updater stopped.")
00399     exit(0)
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


nao_driver
Author(s): Armin Hornung, Stefan Osswald, Daniel Maier
autogenerated on Tue Oct 15 2013 10:06:23