ecstats_listener.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Software License Agreement (BSD License)
00004 #
00005 # Copyright (c) 2009, Willow Garage, Inc.
00006 # All rights reserved.
00007 #
00008 # Redistribution and use in source and binary forms, with or without
00009 # modification, are permitted provided that the following conditions
00010 # are met:
00011 #
00012 #  * Redistributions of source code must retain the above copyright
00013 #    notice, this list of conditions and the following disclaimer.
00014 #  * Redistributions in binary form must reproduce the above
00015 #    copyright notice, this list of conditions and the following
00016 #    disclaimer in the documentation and/or other materials provided
00017 #    with the distribution.
00018 #  * Neither the name of Willow Garage, Inc. nor the names of its
00019 #    contributors may be used to endorse or promote products derived
00020 #    from this software without specific prior written permission.
00021 #
00022 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 # POSSIBILITY OF SUCH DAMAGE.
00034 #
00035 
00036 ##\author Kevin Watts
00037 ##\brief Listens to ecstats, makes sure no dropping packets
00038 
00039 from __future__ import with_statement
00040 PKG = 'pr2_hardware_test_monitor'
00041 
00042 import roslib
00043 roslib.load_manifest(PKG)
00044 
00045 from ectools.msg import ecstats
00046 from std_srvs.srv import *
00047 from diagnostic_msgs.msg import DiagnosticStatus, KeyValue
00048 
00049 import rospy
00050 
00051 import threading
00052 
00053 from pr2_hw_listener import PR2HWListenerBase
00054 
00055 class ECStatsListener(PR2HWListenerBase):
00056     def __init__(self):
00057         self._ec_stats_sub = rospy.Subscriber('ecstats', ecstats, self._ecstats_cb)
00058         self._mutex = threading.Lock()
00059 
00060         self._ok = True
00061         self._update_time = -1
00062         
00063         self._halt_motors = rospy.ServiceProxy('pr2_etherCAT/halt_motors', Empty)
00064 
00065         self._drop_count_at_reset = 0
00066         self._time_at_last_reset = rospy.get_time()
00067         self._reset_count = 0
00068 
00069         self._has_link = False
00070         self._max_device_count = 0
00071         self._total_sent = 0
00072         self._interval_sent = 0
00073         self._total_dropped = 0
00074         self._interval_dropped = 0
00075         self._total_late = 0
00076         self._interval_late = 0
00077         self._total_bandwidth = 0
00078         self._interval_bandwidth = 0
00079 
00080         self._lost_link_count_since_reset = 0
00081         self._lost_link_count = 0
00082 
00083     def reset(self):
00084         with self._mutex:
00085             self._time_at_last_reset = rospy.get_time()
00086             self._drop_count_at_reset = self._total_dropped
00087             self._ok = True
00088             self._reset_count += 1
00089             self._lost_link_count_since_reset = 0
00090 
00091     def _ecstats_cb(self, msg):
00092         with self._mutex:
00093             self._has_link              = msg.has_link
00094             self._max_device_count      = msg.max_device_count
00095             self._total_sent            = msg.total_sent_packets
00096             self._interval_sent_packets = msg.interval_sent_packets
00097             self._total_dropped         = msg.total_dropped_packets
00098             self._interval_dropped      = msg.interval_dropped_packets
00099             self._total_late            = msg.total_late_packets
00100             self._interval_late         = msg.interval_late_packets
00101             self._total_bandwidth       = msg.total_bandwidth_mbps
00102             self._interval_bandwidth    = msg.interval_bandwidth_mbps
00103             
00104             if not self._has_link:
00105                 self._lost_link_count += 1
00106                 self._lost_link_count_since_reset += 1
00107 
00108             was_ok = self._ok
00109             self._ok = self._ok and self._has_link
00110             #self._total_dropped == self._drop_count_at_reset 
00111             if was_ok and not self._ok:
00112                 try:
00113                     # self._halt_motors()
00114                     rospy.logerr('Should\'ve halted motors, went down')
00115                 except Exception, e:
00116                     rospy.logerr('Attempted to halt motors after dropped packets, failed')
00117                     
00118             self._update_time = rospy.get_time()
00119 
00120     
00121     def check_ok(self):
00122         with self._mutex:
00123             stat = 0 if self._ok else 2
00124             msg = '' if self._ok else 'Dropped Packets'
00125 
00126             if rospy.get_time() - self._update_time > 3:
00127                 stat = 3
00128                 msg = 'Packet Data Stale'
00129                 if self._update_time == -1:
00130                     msg = 'No Packet Data'
00131         
00132             diag = DiagnosticStatus()
00133             diag.name = 'EC Stats Packet Data'
00134             diag.level = stat
00135             diag.message = msg
00136             if diag.level == 0:
00137                 diag.message = 'OK'
00138             
00139             diag.values = [
00140                 KeyValue(key='Has Link?',              value=str(self._has_link)),
00141                 KeyValue(key='Dropped Since Reset',    value=str(self._total_dropped - self._drop_count_at_reset)),
00142                 KeyValue(key='Total Drops',            value=str(self._total_dropped)),
00143                 KeyValue(key='Lost Link Count',        value=str(self._lost_link_count)),
00144                 KeyValue(key='Lost Links Since Reset', value=str(self._lost_link_count_since_reset)),
00145                 KeyValue(key='Number of Resets',       value=str(self._reset_count)),
00146                 KeyValue(key='Time Since Last Reset',  value=str(rospy.get_time() - self._time_at_last_reset)),
00147                 KeyValue(key='Drops at Last Reset',    value=str(self._drop_count_at_reset)),
00148                 KeyValue(key='Max Device Count',       value=str(self._max_device_count)),
00149                 KeyValue(key='Interval Drops',         value=str(self._interval_dropped)),
00150                 KeyValue(key='Total Late Packets',     value=str(self._total_late)),
00151                 KeyValue(key='Interval Late Packets',  value=str(self._interval_late)),
00152                 KeyValue(key='Total Sent Packets',     value=str(self._total_sent)),
00153                 KeyValue(key='Interval Sent Packets',  value=str(self._interval_sent)),
00154                 KeyValue(key='Total Bandwidth',        value=str(self._total_bandwidth)),
00155                 KeyValue(key='Interval Bandwidth',     value=str(self._interval_bandwidth))
00156                 ]
00157         
00158         return stat, msg, [ diag ]
00159     


pr2_hardware_test_monitor
Author(s): Kevin Watts
autogenerated on Sat Dec 28 2013 17:54:19