|
From: <wa...@us...> - 2009-06-26 04:11:54
|
Revision: 17753
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=17753&view=rev
Author: wattsk
Date: 2009-06-26 04:11:49 +0000 (Fri, 26 Jun 2009)
Log Message:
-----------
Moved disk_usage.py to pr2_computer_monitor
Modified Paths:
--------------
pkg/trunk/pr2/life_test/manifest.xml
pkg/trunk/pr2/life_test/simple_test/fake_test.py
pkg/trunk/pr2/life_test/simple_test/test.launch
pkg/trunk/pr2/life_test/src/life_test/life_test.py
pkg/trunk/pr2/life_test/src/life_test/ui.py
pkg/trunk/pr2/life_test/tests.xml
pkg/trunk/pr2/life_test/xrc/gui.fbp
pkg/trunk/pr2/life_test/xrc/gui.xrc
pkg/trunk/pr2/motorconf_gui/src/motorconf_gui/ui.py
pkg/trunk/pr2/pr2_computer_monitor/manifest.xml
pkg/trunk/pr2/pr2_computer_monitor/scripts/hd_monitor.py
pkg/trunk/pr2/qualification/manifest.xml
pkg/trunk/pr2/qualification/scripts/hysteresis_sinesweep_plot.py
pkg/trunk/pr2/qualification/src/qualification/result.py
pkg/trunk/pr2/qualification/src/qualification/ui.py
pkg/trunk/pr2/qualification/tests/simple_example/startup.launch
Added Paths:
-----------
pkg/trunk/pr2/life_test/msg/
pkg/trunk/pr2/life_test/msg/DeviceReading.msg
pkg/trunk/pr2/life_test/msg/TestStatus.msg
pkg/trunk/pr2/life_test/scripts/ethercat_test_monitor.py
pkg/trunk/pr2/life_test/simple_test/fake_trans.csv
pkg/trunk/pr2/life_test/src/life_test/test_param.py
pkg/trunk/pr2/life_test/src/life_test/test_record.py
pkg/trunk/pr2/life_test/src/life_test/trans_monitor.py
pkg/trunk/pr2/pr2_computer_monitor/scripts/disk_usage.py
pkg/trunk/pr2/wg_hardware_roslaunch/
pkg/trunk/pr2/wg_hardware_roslaunch/manifest.xml
pkg/trunk/pr2/wg_hardware_roslaunch/src/
pkg/trunk/pr2/wg_hardware_roslaunch/src/wg_hardware_roslaunch/
pkg/trunk/pr2/wg_hardware_roslaunch/src/wg_hardware_roslaunch/__init__.py
pkg/trunk/pr2/wg_hardware_roslaunch/src/wg_hardware_roslaunch/roslaunch_caller.py
Removed Paths:
-------------
pkg/trunk/stacks/hardware_test/runtime_monitor/scripts/disk_usage.py
Modified: pkg/trunk/pr2/life_test/manifest.xml
===================================================================
--- pkg/trunk/pr2/life_test/manifest.xml 2009-06-26 03:55:29 UTC (rev 17752)
+++ pkg/trunk/pr2/life_test/manifest.xml 2009-06-26 04:11:49 UTC (rev 17753)
@@ -31,4 +31,6 @@
<depend package="runtime_monitor" />
<depend package="invent_client" />
<depend package="diagnostic_msgs" />
+ <depend package="wg_hardware_roslaunch" />
+ <depend package="mechanism_msgs" />
</package>
Added: pkg/trunk/pr2/life_test/msg/DeviceReading.msg
===================================================================
--- pkg/trunk/pr2/life_test/msg/DeviceReading.msg (rev 0)
+++ pkg/trunk/pr2/life_test/msg/DeviceReading.msg 2009-06-26 04:11:49 UTC (rev 17753)
@@ -0,0 +1,9 @@
+byte DEVICE_OK = 0
+byte DEVICE_BROKEN = 1
+byte DEVICE_NO_EXIST = 2
+
+string joint_name
+string act_name
+byte cal_reading
+float64 position
+byte status
\ No newline at end of file
Added: pkg/trunk/pr2/life_test/msg/TestStatus.msg
===================================================================
--- pkg/trunk/pr2/life_test/msg/TestStatus.msg (rev 0)
+++ pkg/trunk/pr2/life_test/msg/TestStatus.msg 2009-06-26 04:11:49 UTC (rev 17753)
@@ -0,0 +1,7 @@
+byte TEST_RUNNING = 0
+byte TEST_WARNING = 1
+byte TEST_ERROR = 2
+byte TEST_STALE = 3
+
+byte test_ok
+string message
\ No newline at end of file
Added: pkg/trunk/pr2/life_test/scripts/ethercat_test_monitor.py
===================================================================
--- pkg/trunk/pr2/life_test/scripts/ethercat_test_monitor.py (rev 0)
+++ pkg/trunk/pr2/life_test/scripts/ethercat_test_monitor.py 2009-06-26 04:11:49 UTC (rev 17753)
@@ -0,0 +1,207 @@
+#!/usr/bin/env python
+#
+# Software License Agreement (BSD License)
+#
+# Copyright (c) 2008, Willow Garage, Inc.
+# All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# * Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# * Redistributions in binary form must reproduce the above
+# copyright notice, this list of conditions and the following
+# disclaimer in the documentation and/or other materials provided
+# with the distribution.
+# * Neither the name of Willow Garage, Inc. nor the names of its
+# contributors may be used to endorse or promote products derived
+# from this software without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+
+# Author: Kevin Watts
+
+import roslib
+roslib.load_manifest('life_test')
+
+from mechanism_msgs.msg import MechanismState
+from diagnostic_msgs.msg import *
+
+from std_srvs.srv import *
+
+from life_test import *
+from life_test.msg import TestStatus
+from life_test.trans_monitor import TransmissionMonitor
+
+import rospy
+
+import sys, os
+
+import threading
+import traceback
+import csv
+
+
+class EtherCATTestMonitorNode():
+ def __init__(self):
+ rospy.init_node('test_monitor', anonymous = True)
+
+ csv_filename = rospy.myargv()[1] # CSV of device data
+ self.create_trans_monitors(csv_filename)
+
+ self._mutex = threading.Lock()
+
+ self._ethercat_ok = True
+ self._transmissions_ok = True
+ self._ethercat_update_time = 0
+ self._mech_update_time = 0
+ self._diags = []
+ self._trans_status = []
+
+ self.test_status_pub = rospy.Publisher('test_status', TestStatus)
+ self.diag_sub = rospy.Subscriber('/diagnostics', DiagnosticMessage, self.diag_callback)
+ self.diag_pub = rospy.Publisher('/diagnostics', DiagnosticMessage)
+
+ self.reset_motors = rospy.ServiceProxy('reset_motors', Empty)
+ self.halt_motors = rospy.ServiceProxy('halt_motors', Empty)
+
+ self.reset_srv = rospy.Service('reset_test', Empty, self.reset_test)
+ self.halt_srv = rospy.Service('halt_test', Empty, self.halt_test)
+
+ self.mech_state_sub = rospy.Subscriber('mechanism_state', MechanismState, self.mech_state_callback)
+
+ # Publish status at 1Hz
+ self._timer = threading.Timer(1.0, self.publish_status)
+ self._timer.start()
+
+ rospy.spin()
+
+ def __del__(self):
+ self.test_status_pub.unregister()
+ self.diag_sub.unregister()
+ self.mech_state_sub.unregister()
+
+ self.reset_srv.unregister()
+ self.halt_srv.unregister()
+
+
+ def create_trans_monitors(self, csv_filename):
+ self._trans_monitors = []
+ trans_csv = csv.reader(open(csv_filename, 'rb'))
+ for row in trans_csv:
+ actuator = row[0].lstrip().rstrip()
+ joint = row[1].lstrip().rstrip()
+ ref = float(row[2])
+ deadband = float(row[3])
+ continuous = (int(row[4]) == 1)
+ positive = (int(row[5]) == 1)
+ self._trans_monitors.append(TransmissionMonitor(
+ actuator, joint, ref,
+ deadband, continuous, positive))
+
+ def publish_status(self):
+ self._mutex.acquire()
+
+ self.check_diags()
+
+ status = TestStatus()
+
+ if rospy.get_time() - self._ethercat_update_time > 3 or rospy.get_time() - self._mech_update_time > 1:
+ status.test_ok = TestStatus.TEST_STALE
+ status.message = 'EtherCAT Master Stale'
+ elif self._ethercat_ok and self._transmissions_ok:
+ status.test_ok = TestStatus.TEST_RUNNING
+ status.message = 'OK'
+ else:
+ status.test_ok = TestStatus.TEST_ERROR
+ if not self._transmissions_ok:
+ status.message = 'Transmission Broken'
+ else:
+ status.message = 'EtherCAT Halted'
+
+ self.test_status_pub.publish(status)
+
+ self.diag_pub.publish(status = self._trans_status)
+
+ # Halt the test if we have a bad transmission
+ if self._ethercat_ok and not self._transmissions_ok:
+ self.halt_motors()
+
+ if not rospy.is_shutdown():
+ timer = threading.Timer(0.5, self.publish_status)
+ timer.start()
+
+ self._mutex.release()
+
+
+ def reset_test(self, srv):
+ self._mutex.acquire() # Need this here?
+
+ for monitor in self._trans_monitors:
+ monitor.reset()
+ self.reset_motors()
+
+ self._mutex.release()
+ return EmptyResponse()
+
+ def halt_test(self, srv = None):
+ self.halt_motors()
+ return EmptyResponse()
+
+ def mech_state_callback(self, mech_state):
+ self._mutex.acquire()
+
+ self._mech_update_time = rospy.get_time()
+
+ self._transmissions_ok = True
+ self._trans_status = []
+ for monitor in self._trans_monitors:
+ diag, state = monitor.update(mech_state)
+ self._trans_status.append(diag)
+ self._transmissions_ok = self._transmissions_ok and state
+
+ self._mutex.release()
+
+ def diag_callback(self, msg):
+ self._mutex.acquire()
+ self._diags.append(msg)
+ self._mutex.release()
+
+ def check_diags(self):
+ # Checks EtherCAT Master diagnostics to see if test running
+ etherCAT_master_name = 'EtherCAT Master'
+ try:
+ for msg in self._diags:
+ for stat in msg.status:
+ if stat.name == 'EtherCAT Master':
+ self._ethercat_ok = (stat.level == 0)
+ self._ethercat_update_time = rospy.get_time()
+
+ self._diags = []
+
+ except Exception, e:
+ rospy.logerr('Caught exception processing diagnostic msg.\nEx: %s' % traceback.format_exc())
+
+
+
+if __name__ == '__main__':
+ try:
+ my_node = EtherCATTestMonitorNode()
+ except:
+ print 'Caught exception in test monitor node'
+ traceback.print_exc()
+ sys.exit(2)
Property changes on: pkg/trunk/pr2/life_test/scripts/ethercat_test_monitor.py
___________________________________________________________________
Added: svn:executable
+ *
Modified: pkg/trunk/pr2/life_test/simple_test/fake_test.py
===================================================================
--- pkg/trunk/pr2/life_test/simple_test/fake_test.py 2009-06-26 03:55:29 UTC (rev 17752)
+++ pkg/trunk/pr2/life_test/simple_test/fake_test.py 2009-06-26 04:11:49 UTC (rev 17753)
@@ -32,6 +32,8 @@
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
+# Author: Kevin Watts
+
import roslib
roslib.load_manifest('life_test')
import wx
@@ -39,6 +41,7 @@
from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, DiagnosticValue, DiagnosticString
from std_srvs.srv import *
+from mechanism_msgs.msg import MechanismState, JointState, ActuatorState
import os
import time
@@ -48,16 +51,24 @@
import threading
from wx import xrc
+import math
+
class FakeTestFrame(wx.Frame):
def __init__(self, parent):
wx.Frame.__init__(self, parent, wx.ID_ANY, 'Fake Test')
- self.diag_pub = rospy.Publisher('diagnostics', DiagnosticMessage)
+ self.diag_pub = rospy.Publisher('/diagnostics', DiagnosticMessage)
+ self.mech_pub = rospy.Publisher('mechanism_state', MechanismState)
+ self._mech_timer = wx.Timer(self, 2)
+ self.Bind(wx.EVT_TIMER, self.on_mech_timer, self._mech_timer)
+ self._last_mech_pub = rospy.get_time()
+ self._mech_timer.Start(50, True)
+
self._diag_timer = wx.Timer(self, 1)
self.Bind(wx.EVT_TIMER, self.on_timer, self._diag_timer)
self._last_publish = rospy.get_time()
- self._diag_timer.Start(250, True)
+ self._diag_timer.Start(500, True)
# Load XRC
xrc_path = os.path.join(roslib.packages.get_pkg_dir('life_test'), 'xrc/gui.xrc')
@@ -65,10 +76,78 @@
self._panel = xrc.XmlResource(xrc_path).LoadPanel(self, 'fake_panel')
self._pub_check_box = xrc.XRCCTRL(self._panel, 'publish_check_box')
self._level_choice = xrc.XRCCTRL(self._panel, 'level_choice')
+
+ self.enum_param_ctrl = xrc.XRCCTRL(self._panel, 'enum_param_ctrl')
+ self.range_param_ctrl = xrc.XRCCTRL(self._panel, 'range_param_ctrl')
+
+ self._cal_box = xrc.XRCCTRL(self._panel, 'calibration_box')
self._reset_srv = rospy.Service('reset_motors', Empty, self.on_reset)
self._halt_srv = rospy.Service('halt_motors', Empty, self.on_halt)
+
+ self._start_time = rospy.get_time()
+ def on_mech_timer(self, event = None):
+ self._mech_timer.Start(10, True)
+
+ # Joint state is a sine, period 1s, Amplitude 2,
+ trig_arg = rospy.get_time() - self._start_time
+
+ sine = math.sin(trig_arg)
+ cosine = math.cos(trig_arg)
+
+ # Stop joint at zero if not running
+ level = self._level_choice.GetSelection()
+ if level != 0:
+ sine = 0
+ cosine = 0
+
+ jnt_st = JointState()
+ jnt_st.name = 'fake_joint'
+ jnt_st.position = float(2 * sine)
+ jnt_st.velocity = float(2 * cosine)
+ jnt_st.applied_effort = float(-2 * sine)
+ jnt_st.commanded_effort = float(-2 * sine)
+ jnt_st.is_calibrated = 1
+
+ # Use same position as above, with 100:1 reduction -> Ampltitude 200
+ act_st = ActuatorState()
+ act_st.name = 'fake_motor'
+ act_st.device_id = 0
+ act_st.encoder_count = 200 * int(sine) + 1134
+ act_st.position = float(200 * sine)
+ act_st.timestamp = float(rospy.get_time())
+ act_st.encoder_velocity = float(200 * sine)
+ act_st.velocity = float(200 * cosine)
+
+ # Only one that makes a difference
+ act_st.calibration_reading = 14
+ if sine > 0.0 and self._cal_box.IsChecked():
+ act_st.calibration_reading = 13
+
+ act_st.calibration_rising_edge_valid = 1
+ act_st.calibration_falling_edge_valid = 1
+ act_st.last_calibration_rising_edge = float(0.0)
+ act_st.last_calibration_falling_edge = float(0.0)
+ act_st.is_enabled = 1
+ act_st.run_stop_hit = 0
+ act_st.last_requested_current = float(0.0)
+ act_st.last_commanded_current = float(0.0)
+ act_st.last_measured_current = float(0.0)
+ act_st.last_requested_effort = float(0.0)
+ act_st.last_commanded_effort = float(0.0)
+ act_st.last_measured_effort = float(0.0)
+ act_st.motor_voltage = float(0.0)
+ act_st.num_encoder_errors = 0
+
+ mech_st = MechanismState()
+ mech_st.time = rospy.get_time()
+ mech_st.actuator_states = [ act_st ]
+ mech_st.joint_states = [ jnt_st ]
+
+ self.mech_pub.publish(mech_st)
+
+
def on_halt(self, srv):
print 'Halting'
wx.CallAfter(self.set_level, 2)
@@ -79,21 +158,29 @@
return EmptyResponse()
def set_level(self, val):
- print 'Setting level'
self._level_choice.SetSelection(val)
+ def set_enum_ctrl(self):
+ enum_param = rospy.get_param('test_choice')
+ self.enum_param_ctrl.SetValue(enum_param)
+
+ def set_range_ctrl(self):
+ range_param = rospy.get_param('cycle_rate')
+ self.range_param_ctrl.SetValue(range_param)
+
def on_timer(self, event = None):
print 'Making message'
- self._diag_timer.Start(500, True)
+ self._diag_timer.Start(1000, True)
level_dict = { "OK": 0, "Warn": 1, "Error": 2 }
level = self._level_choice.GetSelection()
- # level_dict[self._level_choice.GetStringSelection()]
- print 'Level %s' % level
+
choice = self._level_choice.GetStringSelection()
- print 'Choice %s' % choice
+ self.set_enum_ctrl()
+ self.set_range_ctrl()
+
if self._pub_check_box.IsChecked():
self.publish_diag(level, str(choice))
@@ -105,15 +192,15 @@
stat.level = level
stat.name = 'EtherCAT Master' # So ghetto
- stat.message = choice #'OK'
+ stat.message = choice
self.diag_pub.publish(msg)
class FakeTestApp(wx.App):
def OnInit(self):
- rospy.init_node("fake_test")
+ rospy.init_node("fake_test_node")
self._frame = FakeTestFrame(None)
- self._frame.SetSize(wx.Size(200, 100))
+ self._frame.SetSize(wx.Size(224, 230))
self._frame.Layout()
self._frame.Centre()
self._frame.Show(True)
Added: pkg/trunk/pr2/life_test/simple_test/fake_trans.csv
===================================================================
--- pkg/trunk/pr2/life_test/simple_test/fake_trans.csv (rev 0)
+++ pkg/trunk/pr2/life_test/simple_test/fake_trans.csv 2009-06-26 04:11:49 UTC (rev 17753)
@@ -0,0 +1 @@
+fake_motor,fake_joint,0.0,0.1,0,1
\ No newline at end of file
Modified: pkg/trunk/pr2/life_test/simple_test/test.launch
===================================================================
--- pkg/trunk/pr2/life_test/simple_test/test.launch 2009-06-26 03:55:29 UTC (rev 17752)
+++ pkg/trunk/pr2/life_test/simple_test/test.launch 2009-06-26 04:11:49 UTC (rev 17753)
@@ -1,3 +1,5 @@
<launch>
<node pkg="life_test" type="fake_test.py" />
+
+ <node pkg="life_test" type="ethercat_test_monitor.py" args="$(find life_test)/simple_test/fake_trans.csv" />
</launch>
\ No newline at end of file
Modified: pkg/trunk/pr2/life_test/src/life_test/life_test.py
===================================================================
--- pkg/trunk/pr2/life_test/src/life_test/life_test.py 2009-06-26 03:55:29 UTC (rev 17752)
+++ pkg/trunk/pr2/life_test/src/life_test/life_test.py 2009-06-26 04:11:49 UTC (rev 17753)
@@ -38,20 +38,24 @@
roslib.load_manifest('life_test')
import sys, os, math, string
-from datetime import datetime
import csv
import traceback
-from time import sleep, mktime, strftime, localtime
+from time import sleep, strftime, localtime
import threading
from socket import gethostname
import wx
-import wx.aui
from wx import xrc
-import rospy, roslaunch
+import rospy
from std_srvs.srv import *
from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, DiagnosticValue, DiagnosticString
+
+# Stuff from life_test package
+from msg import TestStatus
+from test_param import TestParam, LifeTest
+from test_record import TestRecord
+
import runtime_monitor
from runtime_monitor.monitor_panel import MonitorPanel
@@ -61,138 +65,9 @@
from email.mime.base import MIMEBase
from email import Encoders
-
-class LifeTest:
- def __init__(self, short_serial, test_name, desc, cycle_rate, test_type, launch_file):
- self._short_serial = short_serial
- self._name = test_name
- self._desc = desc
- self._cycle_rate = cycle_rate
- self._launch_script = launch_file
- self._test_type = test_type
-
-class TestRecord:
- def __init__(self, test, serial):
- self._start_time = rospy.get_time()
- self._cum_seconds = 0
- self._last_update_time = rospy.get_time()
- self._was_running = False
- self._was_launched = False
- self._num_alerts = 0
- self._num_halts = 0
-
- self._rate = test._cycle_rate
- self._serial = serial
- self._test_name = test._name
-
- self._log = {}
- self._last_log_time = self._last_update_time
-
- csv_name = strftime("%m%d%Y_%H%M%S", localtime(self._start_time)) + '_' + str(self._serial) + '_' + self._test_name + '.csv'
- csv_name = csv_name.replace(' ', '_').replace('/', '__')
- self.log_file = os.path.join(roslib.packages.get_pkg_dir('life_test'), 'logs/%s' % csv_name)
-
+import wg_hardware_roslaunch.roslaunch_caller as roslaunch_caller
- log_csv = csv.writer(open(self.log_file, 'wb'))
- log_csv.writerow(['Time', 'Status',
- 'Elapsed (s)', 'Active (s)',
- 'Cycles', 'Cycle Rate', 'Notes'])
- def get_elapsed(self):
- elapsed = rospy.get_time() - self._start_time
- return elapsed
-
- def get_cum_time(self):
- return self._cum_seconds
-
- def get_duration_str(self, duration):
- hrs = max(math.floor(duration / 3600), 0)
- min = max(math.floor(duration / 6), 0) / 10 - hrs * 60
-
- return "%dhr, %.1fm" % (hrs, min)
-
- def get_active_str(self):
- return self.get_duration_str(self._cum_seconds)
-
- def get_elapsed_str(self):
- return self.get_duration_str(self.get_elapsed())
-
- def get_cycles(self):
- cycles = self._rate * self._cum_seconds
- return cycles
-
- def update(self, launched, running, stale, note):
- if running and not launched:
- rospy.logerr('Reported impossible state of running and not launched')
- return 0, ''
-
- if stale and running:
- rospy.logerr('Reported impossible state of running and stale')
- return 0, ''
-
- if self._was_running and running:
- self._cum_seconds = rospy.get_time() - self._last_update_time + self._cum_seconds
-
- alert = 0 # 0 - None, 1 - Notify, 2 - alert
- msg = ''
- state = 'Running'
-
- if launched and (not running) and stale:
- state = 'Halted, stale'
- elif launched and (not running):
- state = 'Halted'
- elif not launched:
- state = 'Stopped'
-
- if (not self._was_launched) and launched:
- alert = 1
- msg = "Test launched."
- elif self._was_launched and (not launched):
- alert = 1
- msg = "Test shut down."
-
- elif self._was_running and (not running):
- alert = 2
- if stale:
- msg = "Test has gone stale!"
- else:
- msg = "Test has stopped running!"
- elif (not self._was_running) and running:
- alert = 1
- msg = "Test has restarted and is running."
-
- self._num_halts += 1
-
- if alert:
- self._num_alerts += 1
-
- self._was_running = running
- self._was_launched = launched
- self._last_update_time = rospy.get_time()
-
- if alert or note != '' or (running and self._last_log_time - rospy.get_time() > 7200):
- self.write_csv_row(self._last_update_time, state, msg, note)
- self._log[rospy.get_time()] = msg + ' ' + note
- self._last_log_time = self._last_update_time
-
- return alert, msg
-
- def write_csv_row(self, update_time, state, msg, note):
- log_msg = msg + ' ' + note
- log_msg = log_msg.replace(',', ';')
-
- time_str = strftime("%m/%d/%Y %H:%M:%S", localtime(update_time))
-
- log_csv = csv.writer(open(self.log_file, 'ab'))
- log_csv.writerow([time_str, state,
- self.get_elapsed(), self.get_cum_time(),
- self.get_cycles(), self._rate,
- log_msg])
-
- def csv_filename(self):
- return self.log_file
-
-
class TestMonitorPanel(wx.Panel):
def __init__(self, parent, manager, test, serial):
wx.Panel.__init__(self, parent)
@@ -201,8 +76,7 @@
self._mutex = threading.Lock()
-
- self._diag_sub = None
+ self._status_sub = None
self._diags = []
# Set up test and loggers
@@ -250,7 +124,6 @@
self._user_submit.Bind(wx.EVT_BUTTON, self.on_user_entry)
self._done_time_ctrl = xrc.XRCCTRL(self._panel, 'done_time_ctrl')
- self._total_cycles_ctrl = xrc.XRCCTRL(self._panel, 'total_cycles_ctrl')
self._elapsed_time_ctrl = xrc.XRCCTRL(self._panel, 'elapsed_time_ctrl')
self._active_time_ctrl = xrc.XRCCTRL(self._panel, 'active_time_ctrl')
@@ -261,8 +134,7 @@
self._send_log_button = xrc.XRCCTRL(self._panel, 'send_test_log_button')
self._send_log_button.Bind(wx.EVT_BUTTON, self.on_send_test_log)
-
- # Add runtime to the pane...
+ # Add runtime to the panel...
self._notebook = xrc.XRCCTRL(self._panel, 'test_data_notebook')
wx.CallAfter(self.create_monitor)
@@ -270,8 +142,6 @@
self._sizer.Add(self._panel, 1, wx.EXPAND)
self.SetSizer(self._sizer)
self.Layout()
-
- self._test_team = [ "wa...@wi...", "sta...@wi..." ]
self._machine = None
self._current_log = {}
@@ -286,6 +156,7 @@
self._test_complete = False
# Timeout for etherCAT diagnostics
+ # Don't start it here, wait until test is launched
self.timer = wx.Timer(self)
self.Bind(wx.EVT_TIMER, self.on_timer, self.timer)
self.last_message_time = rospy.get_time()
@@ -312,18 +183,15 @@
def __del__(self):
# Somehow calling log function in destructor
- print 'Stopping launches'
self.stop_test()
- if self._diag_sub:
- print 'Unregistering from diagnostics'
- self._diag_sub.unregister()
+ if self._status_sub:
+ self._status_sub.unregister()
def is_launched(self):
return self._test_launcher is not None
def on_end_choice(self, event = None):
- #self._mutex.acquire()
choice = self._end_cond_type.GetStringSelection()
# Set test_duration_ctrl units also
@@ -336,8 +204,7 @@
self._test_duration_ctrl.SetValue(0)
active_time = self._record.get_cum_time()
- cycles = self._record.get_cycles()
-
+ # Should probably add cycles back in somehow
if choice == 'Hours':
hrs = math.ceil((active_time / 3600))
self._test_duration_ctrl.SetRange(hrs, 168) # Week
@@ -346,20 +213,14 @@
min = math.ceil((active_time / 60))
self._test_duration_ctrl.SetRange(min, 600) # 10 Hrs
self._test_duration_ctrl.SetValue(min + 10)
- elif choice == 'Cycles':
- cycle_val = cycles + math.ceil(self._test._cycle_rate * 300) # 5 min
- self._test_duration_ctrl.SetRange(cycles, 100000) # Long time
- self._test_duration_ctrl.SetValue(cycle_val)
else:
self._test_duration_ctrl.SetRange(0, 0) # Can't change limits
self._test_duration_ctrl.SetValue(0)
- #self._mutex.release()
-
def on_user_entry(self, event):
entry = self._user_log.GetValue()
msg = 'OPERATOR: ' + entry
- self.log(msg)
+ self.update_test_record(msg)
self._user_log.Clear()
self._user_log.SetFocus()
@@ -371,26 +232,28 @@
if name.find('@') < 0:
name = name + '@willowgarage.com'
- self.notify_operator(3, 'Test log requested by operator.', string.join(names, ','))
+ self.notify_operator(3, 'Log Requested.', string.join(names, ','))
def on_close(self, event):
- #self.stop_test()
- self.log('Closing down test.')
+ self.update_test_record('Closing down test.')
self.update_invent()
self.record_test_log()
- self.notify_operator(1, 'Test closing.')
+ self.notify_operator(1, 'Closing.')
self._manager.close_tab(self._serial)
def update_test_record(self, note = ''):
alert, msg = self._record.update(self.is_launched(), self._is_running, self._is_stale, note)
- if alert > 0:
- #self.log(msg)
- self._current_log[rospy.get_time()] = msg
- self._manager.log_test_entry(self._test._name, self._machine, msg)
-
- #self._log_ctrl.AppendText(
+
+ lst = [msg, note]
+ message = string.join(lst, ' ')
+
+ if alert > 0 or note != '':
+ self._current_log[rospy.get_time()] = message
+ self._manager.log_test_entry(self._test._name, self._machine, message)
self.display_logs()
+
+ if alert > 0:
self.notify_operator(alert, msg)
@@ -405,11 +268,8 @@
return duration * 60
if end_condition == 'Seconds':
return duration
- if end_condition == 'Cycles':
- return duration / self._test._cycle_rate
-
else: #if end_condition == 'Continuous':
- return 10**9 # Roughly 30 years
+ return 10**10 # Roughly 300 years
def calc_remaining(self):
total_sec = self.calc_run_time()
@@ -422,47 +282,36 @@
if rospy.get_time() - self._last_invent_time > self.invent_timeout and self.is_launched():
self.update_invent()
- #self.invent_timer.Start(self.invent_timeout * 500, True)
-
-
def update_invent(self):
- rospy.logerr('Updating invent')
-
- # Reset timer, last time
- #self.invent_timer.Start(self.invent_timeout * 500, True)
self._last_invent_time = rospy.get_time()
# Don't log anything if we haven't launched
if not self.is_launched() and not self._invent_note_id:
return
- hrs_str = self._record.get_elapsed_str()
- cycles = self._record.get_cycles()
+ hrs_str = self._record.get_active_str()
- stats = "Stats: Total cycles %.1f, elapsed time %s." % (cycles, hrs_str)
+ stats = "Stats: Total active time %s." % (hrs_str)
if self.is_launched() and self._is_running:
- note = "Test running %s at %s Hz. " % (self._test._name, self._test._cycle_rate)
+ note = "Test running %s. " % (self._test._name)
elif self.is_launched() and not self._is_running:
note = "Test %s is halted. " % self._test._name
else:
note = "Test %s finished. CSV name: %s. " % (self._test._name, os.path.basename(self._record.csv_filename()))
- # rospy.logerr('Updated note successfully')
self._invent_note_id = self._manager._invent_client.setNote(self._serial, note + stats, self._invent_note_id)
- #print 'Logging in invent for reference %s: %s' % (self._serial, note + stats)
+ # Should also be in notifier class
def record_test_log(self):
try:
# Adds log csv to invent
if self._record.get_cum_time() == 0:
return # Don't log test that hasn't run
-
- # rospy.logerr('Writing CSV file')
-
+
f = open(self._record.csv_filename(), 'rb')
- csv = f.read()
- self._manager._invent_client.add_attachment(self._serial, os.path.basename(self._record.csv_filename()), 'text/csv', csv)
+ csv_file = f.read()
+ self._manager._invent_client.add_attachment(self._serial, os.path.basename(self._record.csv_filename()), 'text/csv', csv_file)
f.close()
# print 'Wrote CSV of test log to invent'
@@ -476,26 +325,25 @@
self.timer.Start(1000 * self.timeout_interval, True)
def on_timer(self, event):
+ # Need the mutex?
self._mutex.acquire()
interval = rospy.get_time() - self.last_message_time
- if interval > self.timeout_interval or interval < 0:
+ if interval > self.timeout_interval: # or interval < 0:
# Make EtherCAT status stale
self._is_running = False
self._is_stale = True
self.update_test_record()
self.stop_if_done()
- self.update_controls(3)
+ self.update_controls(4)
else:
- #self.start_timer()
self._is_stale = False
self._mutex.release()
- #self.Refresh()
- def update_controls(self, level = 3, msg = 'None'):
+ def update_controls(self, level = 4, msg = 'None'):
# Assumes it has the lock
if not self.is_launched():
self._status_bar.SetValue("Launch to display status")
@@ -507,11 +355,14 @@
self._status_bar.SetValue("Test Warning! Warning: %s" % msg)
self._status_bar.SetBackgroundColour("Orange")
elif level == 2:
- self._status_bar.SetValue("Error in EtherCAT Master: %s" % msg)
+ self._status_bar.SetValue("Error in Test Monitor: %s" % msg)
self._status_bar.SetBackgroundColour("Red")
+ elif level == 3:
+ self._status_bar.SetValue("Test Monitor reports stale: %s" % msg)
+ self._status_bar.SetBackgroundColour("Light Blue")
else:
self._status_bar.SetBackgroundColour("White")
- self._status_bar.SetValue("EtherCAT Master Stale!")
+ self._status_bar.SetValue("Test Monitor Stale")
self._reset_button.Enable(self.is_launched())
self._halt_button.Enable(self.is_launched())
@@ -524,9 +375,6 @@
remain_str = self._record.get_duration_str(remaining)
self._done_time_ctrl.SetValue(remain_str)
- cycles = "%.1f" % self._record.get_cycles()
- self._total_cycles_ctrl.SetValue(cycles)
-
self._test_log_window.Freeze()
(x, y) = self._test_log_window.GetViewStart()
self._test_log_window.SetPage(self.make_html_cycle_log_table())
@@ -558,21 +406,20 @@
# negative time before we shutdown
# Can this be part of test record?
if remain < 0:
- self.notify_operator(1, 'Test complete!')
self._test_complete = True
self.stop_test()
def stop_test(self, event = None):
if self.is_launched():
self.on_halt_motors(None)
- self._test_launcher.stop()
+ self._test_launcher.shutdown()
self._manager.test_stop(self._machine)
- self.log('Stopping test launch')
+ self.update_test_record('Stopping test launch')
self._test_launcher = None
- if self._diag_sub:
- self._diag_sub.unregister()
- self._diag_sub = None
+ if self._status_sub:
+ self._status_sub.unregister()
+ self._status_sub = None
self._is_running = False
@@ -580,73 +427,53 @@
self.update_controls()
- def log(self, msg):
- self.update_test_record(msg)
- self._current_log[rospy.get_time()] = msg
- self._manager.log_test_entry(self._test._name, self._machine, msg)
-
- #wx.CallAfter(self.display_logs)
-
def display_logs(self):
- #try:
- # self._mutex.acquire()
- #except:
- # rospy.logerr('Error attempting to acquire mutex!')
- # return
-
+
self._log_ctrl.AppendText(self.print_cur_log())
- #self._log_ctrl.Refresh()
- #self._log_ctrl.Update()
self._current_log = {}
- #self._mutex.release()
-
- def diag_callback(self, message):
+
+ def status_callback(self, msg):
self._mutex.acquire()
- self._diags.append(message)
+ self._status_msg = msg
self._mutex.release()
wx.CallAfter(self.new_msg)
-
+
def new_msg(self):
self._mutex.acquire()
- # Simple and hopefully effective way to see if test is still running
- etherCAT_master_name = 'EtherCAT Master'
- level_dict = { 0: 'OK', 1: 'Warn', 2: 'Error' }
- try:
- for msg in self._diags:
- for stat in msg.status:
- if stat.name == etherCAT_master_name:
- self.last_message_time = rospy.get_time()
- self.start_timer()
+ level_dict = { 0: 'OK', 1: 'Warn', 2: 'Error', 3: 'Stale' }
- self._is_running = (stat.level == 0)
- self._is_stale = False
- self.update_test_record()
- self.stop_if_done()
- self.update_controls(stat.level, stat.message)
+ self._is_running = (self._status_msg.test_ok == 0)
+ self._is_stale = False
+ self.start_timer()
+ self.update_test_record()
+ self.stop_if_done()
+ self.update_controls(self._status_msg.test_ok, self._status_msg.message)
- self._diags = []
-
- except Exception, e:
- rospy.logerr('Caught exception processing diagnostic msg.\nEx: %s' % traceback.format_exc())
-
+
self._mutex.release()
- #self.Refresh()
+
-
- def make_launch_script(self):
+ def make_launch_script(self, local_diag_topic):
launch = '<launch>\n'
launch += '<group ns="%s">' % self._machine
# Remap
- launch += '<remap from="/diagnostics" to="/%s/diagnostics" />' % self._machine
+ launch += '<remap from="/diagnostics" to="%s" />' % local_diag_topic
# Init machine
launch += '<machine name="test_host_root" user="root" address="%s" ' % self._machine
launch += 'ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" default="never"/>'
launch += '<machine name="test_host" address="%s" ' % self._machine
launch += 'ros-root="$(env ROS_ROOT)" ros-package-path="$(env ROS_PACKAGE_PATH)" />'
+ # Include our launch file
launch += '<include file="$(find life_test)/%s" />' % self._test._launch_script
+
+ # TODO: Check bag, make sure it's on the right topic
+ # Record our diagnostics remaped back to local diagnostics
+ launch += '<remap from="%s" to="/diagnostics" />' % local_diag_topic
+ launch += ' <node pkg="rosrecord" type="rosrecord" args="-f /hwlog/test_runtime_automatic %s" />' % local_diag_topic
+
launch += '</group>\n</launch>'
return launch
@@ -656,12 +483,10 @@
# Add subscriber to diagnostics
# Launch file, subscribe diagnostics
def launch_test(self, event):
- # Prompt ARE YOU SURE
dialog = wx.MessageDialog(self, 'Are you sure you want to launch?', 'Confirm Launch', wx.OK|wx.CANCEL)
if dialog.ShowModal() != wx.ID_OK:
return
-
# Get machine, end condition, etc
machine = self._test_machine_ctrl.GetStringSelection()
@@ -669,42 +494,42 @@
wx.MessageBox('Machine in use, select again!', 'Machine in use', wx.OK|wx.ICON_ERROR, self)
return
-
self._machine = machine
+ local_diag = '/' + self._machine + '/diagnostics'
- self.log('Launching test %s on machine %s.' % (self._test._name, self._machine))
+ self.update_test_record('Launching test %s on machine %s.' % (self._test._name, self._machine))
- config = roslaunch.ROSLaunchConfig()
+ self._test.set_params(self._machine)
+ self._test_launcher = roslaunch_caller.ScriptRoslaunch(
+ self.make_launch_script(local_diag))
try:
- loader = roslaunch.XmlLoader()
- loader.load_string(self.make_launch_script(), config)
- self._test_launcher = roslaunch.ROSLaunchRunner(config)
- self._test_launcher.launch()
+ self._test_launcher.start()
except roslaunch.RLException, e:
- self.log('Failed to launch script')
- self.log(traceback.format_exc())
+ traceback.print_exc()
self._manager.test_stop(self._machine)
self._machine = None
- return
+ self.update_test_record('Failed to launch script')
+ self.update_test_record(traceback.format_exc())
+ self._test_launcher.shutdown()
+ self._test_launcher = None
+ return None
-
- local_diagnostics = '/' + self._machine + '/diagnostics'
+ local_status = '/' + self._machine + '/test_status'
self._is_running = True
self.update_invent()
- self._monitor_panel.change_diagnostic_topic(local_diagnostics)
+ self._monitor_panel.change_diagnostic_topic(local_diag)
- self._mutex.acquire()
self.update_controls()
- self._mutex.release()
+ #self._diag_sub = rospy.Subscriber(local_diagnostics, DiagnosticMessage, self.diag_callback)
- self._diag_sub = rospy.Subscriber(local_diagnostics, DiagnosticMessage, self.diag_callback)
+ self._status_sub = rospy.Subscriber(local_status, TestStatus, self.status_callback)
-
+ # Changed from halt_motors to halt_test for test monitor
def on_halt_motors(self, event = None):
try:
- self.log('Halting motors.')
+ self.update_test_record('Halting motors.')
# Call halt motors service on NAME_SPACE/pr2_etherCAT
- halt_srv = rospy.ServiceProxy(self._machine + '/halt_motors', Empty)
+ halt_srv = rospy.ServiceProxy(self._machine + '/halt_test', Empty)
halt_srv()
except Exception, e:
@@ -712,15 +537,16 @@
def on_reset_motors(self, event = None):
try:
- self.log('Reseting motors')
- reset = rospy.ServiceProxy(self._machine + '/reset_motors', Empty)
+ self.update_test_record('Reseting motors')
+ reset = rospy.ServiceProxy(self._machine + '/reset_test', Empty)
reset()
except:
rospy.logerr('Exception on reset motors. %s' % traceback.format_exc())
#
- # Loggers and data processing -> Move to record class or elsewhere
+ # Loggers and data processing -> Move to notifier class or elsewhere
+ # Notifier class needs test record, that's it
#
def get_test_team(self):
# Don't email everyone it's debugging on NSF
@@ -733,7 +559,7 @@
machine_str = self._machine
if not self._machine:
machine_str = 'NONE'
- return "%s Test %s on machine %s of %s" % (msg, self._test._name, machine_str, self._serial)
+ return "Test %s on machine %s. MSG: %s" % (self._test.get_title(self._serial), machine_str, msg)
def notify_operator(self, level, alert_msg, recipient = None):
# Don't notify if we haven't done anything
@@ -741,20 +567,17 @@
return
sender = 'tes...@wi...'
- header = '--Test Notify--'
if level == 2:
sender = 'tes...@wi...'
- header = '--Test Alert--'
elif level == 3:
sender = 'tes...@wi...'
- header = '--Test Report--'
try:
if not recipient:
recipient = self.get_test_team()
msg = MIMEMultipart('alternative')
- msg['Subject'] = header + self.line_summary(alert_msg)
+ msg['Subject'] = self.line_summary(alert_msg)
msg['From'] = sender
msg['To'] = recipient
@@ -779,7 +602,7 @@
return True
except Exception, e:
rospy.logerr('Unable to send mail! %s' % traceback.format_exc())
- self.log('Unable to send mail! %s' % traceback.format_exc())
+ self.update_test_record('Unable to send mail! %s' % traceback.format_exc())
return False
@@ -826,7 +649,7 @@
html += '<H3>Alert: %s</H3><br>\n' % alert_msg
if self._test_complete:
- html += '<H3>Test Completed Successfully</H3>\n'
+ html += '<H3>Test Complete</H3>\n'
else:
if self.is_launched() and not self._is_running:
html += '<H3>Test Status: Launched, Halted</H3>\n'
@@ -835,14 +658,20 @@
else:
html += '<H3>Test Status: Shutdown</H3>\n'
+ # Table of test machine, etc
+ html += '<hr size="3">\n'
html += '<H4>Test Info</H4>\n'
html += '<p>Description: %s</p>\n<br>' % self._test._desc
html += self.make_test_info_table()
+ # Parameter table
+ html += '<hr size="3">\n'
+ html += '<H4>Test Parameters</H4>\n'
+ html += self.make_test_param_table()
+
# Make results table
html += '<hr size="3">\n'
html += '<H4>Test Results</H4>\n'
-
html += self.make_record_table()
@@ -857,45 +686,75 @@
def make_test_info_table(self):
html = '<table border="1" cellpadding="2" cellspacing="0">\n'
- html += self.make_table_row('Test Name', self._test._name)
- html += self.make_table_row('Serial', self._serial)
- html += self.make_table_row('Cycle Rate', self._test._cycle_rate)
- html += self.make_table_row('Test Type', self._test._test_type)
+ html += self.make_table_row(['Test Name', self._test._name])
+ if self._machine:
+ html += self.make_table_row(['Machine', self._machine])
+
+ html += self.make_table_row(['Serial', self._serial])
+ html += self.make_table_row(['Test Type', self._test._test_type])
+ html += self.make_table_row(['Launch File', self._test._launch_script])
+ html += self.make_table_row(['Trac Ticket', self._test._trac])
html += '</table>\n'
return html
+ def make_test_param_table(self):
+ if len(self._test._params) == 0:
+ return '<p>No test parameters defined.</p>\n'
- def make_table_row(self, label, value):
- return '<tr><td><b>%s</b></td><td>%s</td></tr>\n' % (label, value)
+ html = '<table border="1" cellpadding="2" cellspacing="0">\n'
+ html += self.make_table_row(['Name', 'Value', 'Key', 'Description'], True)
+ for param in self._test._params:
+ html += self.make_table_row([param._name, param._value, param._param_name, param._desc])
+ html += '</table>\n'
+ return html
+
+
+ def make_table_row(self, lst, bold = False):
+ html = '<tr>'
+ for val in lst:
+ if bold:
+ html += '<td><b>%s</b></td>' % val
+ else:
+ html += '<td>%s</td>' % val
+ html += '</tr>\n'
+ return html
+
+
def make_record_table(self):
if not self._record:
return '<p>No test record, test may have been aborted.</p>\n'
html = '<table border="1" cellpadding="2" cellspacing="0">\n'
time_str = strftime("%m/%d/%Y %H:%M:%S", localtime(self._record._start_time))
- html += self.make_table_row('Start Time', time_str)
- html += self.make_table_row('Elapsed Time', self._record.get_elapsed_str())
- cycle_str = "%.1f" % self._record.get_cycles()
- html += self.make_table_row('Total Cycles', cycle_str)
- html += self.make_table_row('Active Time', self._record.get_active_str())
-
+ html += self.make_table_row(['Start Time', time_str])
+ html += self.make_table_row(['Elapsed Time', self._record.get_elapsed_str()])
+ html += self.make_table_row(['Active Time', self._record.get_active_str()])
+ for ky in self._record.get_cum_data().keys():
+ cum_name = "Cum. %s" % ky
+ html += self.make_table_row([cum_name, self._record.get_cum_data()[ky]])
+
+ html += self.make_table_row(['Num Halts', self._record._num_halts])
+ html += self.make_table_row(['Num Alerts', self._record._num_events])
html += '</table>\n'
+
return html
def make_log_table(self):
if self._record._log is None or len(dict.keys(self._record._log)) == 0:
return '<p>No test log!</p>\n'
- html = '<table border="1" cellpadding="2" cellspacing="0">\n'
+ html = '<p>CSV location: %s on machine %s.</p>\n' % (self._record.csv_filename(), gethostname())
+
+ html += '<table border="1" cellpadding="2" cellspacing="0">\n'
html += '<tr><td><b>Time</b></td><td><b>Entry</b></td></tr>\n'
kys = dict.keys(self._record._log)
kys.sort()
for ky in kys:
time_str = strftime("%m/%d/%Y %H:%M:%S", localtime(ky))
- html += self.make_table_row(time_str, self._record._log[ky])
+ html += self.make_table_row([time_str, self._record._log[ky]])
html += '</table>\n'
Added: pkg/trunk/pr2/life_test/src/life_test/test_param.py
===================================================================
--- pkg/trunk/pr2/life_test/src/life_test/test_param.py (rev 0)
+++ pkg/trunk/pr2/life_test/src/life_test/test_param.py 2009-06-26 04:11:49 UTC (rev 17753)
@@ -0,0 +1,103 @@
+# Software License Agreement (BSD License)
+#
+# Copyright (c) 2008, Willow Garage, Inc.
+# All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# * Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# * Redistributions in binary form must reproduce the above
+# copyright notice, this list of conditions and the following
+# disclaimer in the documentation and/or other materials provided
+# with the distribution.
+# * Neither the name of Willow Garage, Inc. nor the names of its
+# contributors may be used to endorse or promote products derived
+# from this software without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+
+# Author: Kevin Watts
+
+
+import roslib
+roslib.load_manifest('life_test')
+
+import rospy
+
+# Should include parameters as a list here
+class LifeTest:
+ def __init__(self, short_serial, test_name, short_name, trac, desc, test_type, launch_file, params):
+ self._short_serial = short_serial
+ self._name = test_name
+ self._short = short_name
+ self._trac = trac
+ self._desc = desc
+ self._launch_script = launch_file
+ self._test_type = test_type
+
+ self._params = params
+
+ def set_params(self, namespace):
+ for param in self._params:
+ param.set_namespace(namespace)
+
+ def get_title(self, serial):
+ if len(serial) == 12: # Take last few digits of SN to ID part
+ return "%s #%s %s" % (self._short, self._trac,
+ serial[len(serial) - 5:
+ len(serial)])
+ # Or just return the short name and the trac ticket
+ return "%s #%s" % (self._short, self._trac)
+
+
+## Stores parameter data for each test
+## Parameters are ROS parameters, and are updated in test log
+## Examples: cycle rate, joint torque, roll on/off
+## Allows changes in test setup or implementation to be logged automatically
+class TestParam():
+ def __init__(self, name, param_name, desc, val, rate):
+ self._value = val
+ self._desc = desc
+
+ self._cumulative = rate
+ self._param_name = param_name
+ self._name = name
+ self._namespace = ''
+
+
+ def set_namespace(self, ns):
+ self._namespace = ns
+ rospy.set_param('/' + self._namespace + '/' + self._param_name, self._value)
+
+ def get_namespace(self):
+ return self._namespace
+
+ def get_value(self):
+ try:
+ val = float(self._value)
+ return val
+ except:
+ return str(self._value)
+
+ def get_name(self):
+ return self._name
+
+ def is_rate(self):
+ return self._cumulative
+
+
Added: pkg/trunk/pr2/life_test/src/life_test/test_record.py
===================================================================
--- pkg/trunk/pr2/life_test/src/life_test/test_record.py (rev 0)
+++ pkg/trunk/pr2/life_test/src/life_test/test_record.py 2009-06-26 04:11:49 UTC (rev 17753)
@@ -0,0 +1,212 @@
+#!/usr/bin/env python
+#
+# Software License Agreement (BSD License)
+#
+# Copyright (c) 2008, Willow Garage, Inc.
+# All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# * Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# * Redistributions in binary form must reproduce the above
+# copyright notice, this list of conditions and the following
+# disclaimer in the documentation and/or other materials provided
+# with the distribution.
+# * Neither the name of the Willow Garage nor the names of its
+# contributors may be used to endorse or promote products derived
+# from this software without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
+# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+
+# Author: Kevin Watts
+
+import roslib
+roslib.load_manifest('life_test')
+
+import csv
+import os, sys, math
+
+import rospy
+from time import strftime, localtime
+
+
+from test_param import TestParam, LifeTest
+
+class TestRecord:
+ def __init__(self, test, serial):
+ self._start_time = rospy.get_time()
+ self._cum_seconds = 0
+ self._last_update_time = rospy.get_time()
+ self._was_running = False
+ self._was_launched = False
+ self._num_events = 0
+ self._num_halts = 0
+
+ self._serial = serial
+ self._test_name = test._name
+
+ self._test = test
+
+ self._log = {}
+ self._last_log_time = self._last_update_time
+
+
+ self._cum_data = {}
+ for param in test._params:
+ if param.is_rate():
+ self._cum_data[param.get_name()] = 0
+
+ csv_name = strftime("%m%d%Y_%H%M%S", localtime(self._start_time)) + '_' + str(self._serial) + '_' + self._test_name + '.csv'
+ csv_name = csv_name.replace(' ', '_').replace('/', '__')
+ self.log_file = os.path.join(roslib.packages.get_pkg_dir('life_test'), 'logs/%s' % csv_name)
+
+
+ log_csv = csv.writer(open(self.log_file, 'wb'))
+ log_csv.writerow(self.csv_header())
+
+
+
+ def get_elapsed(self):
+ elapsed = rospy.get_time() - self._start_time
+ return elapsed
+
+ def get_cum_time(self):
+ return self._cum_seconds
+
+ def get_duration_str(self, duration):
+ hrs = max(math.floor(duration / 3600), 0)
+ min = max(math.floor(duration / 6), 0) / 10 - hrs * 60
+
+ return "%dhr, %.1fm" % (hrs, min)
+
+ def get_active_str(self):
+ return self.get_duration_str(self._cum_seconds)
+
+ def get_elapsed_str(self):
+ return self.get_duration_str(self.get_elapsed())
+
+ # TODO
+ def get_cycles(self, name = None):
+ if not self._cum_data.has_key(name):
+ kys = self._cum_data.keys()
+ kys.sort()
+ return self._cum_data[kys[0]]
+ return self._cum_data[name]
+
+ def update(self, launched, running, stale, note):
+ if running and not launched:
+ rospy.logerr('Reported impossible state of running and not launched')
+ return 0, ''
+
+ if stale and running:
+ rospy.logerr('Reported impossible state of running and stale')
+ return 0, ''
+
+ # Something wrong here, cum seconds not updating
+ d_seconds = 0
+ if self._was_running and running:
+ d_seconds = rospy.get_time() - self._last_update_time
+
+ self._cum_seconds += d_seconds
+
+ alert = 0 # 0 - None, 1 - Notify, 2 - alert
+ msg = ''
+ state = 'Running'
+
+ if launched and (not running) and stale:
+ state = 'Stale'
+ elif launched and (not running):
+ state = 'Halted'
+ elif not launched:
+ state = 'Stopped'
+
+ if (not self._was_launched) and launched:
+ alert = 1
+ msg = "Launched."
+ elif self._was_launched and (not launched):
+ alert = 1
+ msg = "Shut down."
+
+ elif self._was_running and (not running):
+ alert = 2
+ self._num_halts += 1
+ if stale:
+ msg = "Stale."
+ else:
+ msg = "Stopped."
+ elif (not self._was_running) and running:
+ alert = 1
+ msg = "Restarted."
+
+ if alert > 0:
+ self._num_events += 1
+
+ # Update cumulative parameters
+ for param in self._test._params:
+ if param.is_rate():
+ self._cum_data[param.get_name()] += d_seconds * param.get_value()
+
+ self._was_running = running
+ self._was_launched = launched
+ self._last_update_time = rospy.get_time()
+
+ if alert or note != '' or (running and self._last_log_time - rospy.get_time() > 7200):
+ self.write_csv_row(self._last_update_time, state, msg, note)
+ self._log[rospy.get_time()] = msg + ' ' + note
+ self._last_log_time = self._last_update_time
+
+ return alert, msg
+
+ def csv_header(self):
+ header = [ 'Time', 'Status', 'Elapsed (s)', 'Cum. Time (s)']
+
+ for param in self._test._params:
+ header.append(param.get_name())
+ if param.is_rate():
+ header.append('Cum. %s' % param.get_name())
+ self._cum_data[param.get_name()] = 0
+
+ header.extend(['Num. Halts', 'Num Events', 'Message'])
+ return header
+
+ def get_cum_data(self):
+ return self._cum_data
+
+
+ def write_csv_row(self, update_time, state, msg, note):
+ log_msg = msg + ' ' + note
+ log_msg = log_msg.replace(',', ';')
+
+ # Keep time machine readable?
+ time_str = strftime("%m/%d/%Y %H:%M:%S", localtime(update_time))
+
+ ...
[truncated message content] |