|
From: <wa...@us...> - 2009-08-09 02:57:52
|
Revision: 21210
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21210&view=rev
Author: wattsk
Date: 2009-08-09 02:57:45 +0000 (Sun, 09 Aug 2009)
Log Message:
-----------
Fixed trans_monitor and ethercat_test_monitor to use diagnostic_msgs/KeyValue
Modified Paths:
--------------
pkg/trunk/pr2/life_test/scripts/ethercat_test_monitor.py
pkg/trunk/pr2/life_test/simple_test/fake_test.py
pkg/trunk/pr2/life_test/src/life_test/trans_monitor.py
Modified: pkg/trunk/pr2/life_test/scripts/ethercat_test_monitor.py
===================================================================
--- pkg/trunk/pr2/life_test/scripts/ethercat_test_monitor.py 2009-08-09 02:42:05 UTC (rev 21209)
+++ pkg/trunk/pr2/life_test/scripts/ethercat_test_monitor.py 2009-08-09 02:57:45 UTC (rev 21210)
@@ -39,7 +39,7 @@
roslib.load_manifest('life_test')
from mechanism_msgs.msg import MechanismState
-from diagnostic_msgs.msg import *
+from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
from std_srvs.srv import *
@@ -140,7 +140,9 @@
self.test_status_pub.publish(status)
- self.diag_pub.publish(status = self._trans_status)
+ array = DiagnosticArray()
+ array.status = self._trans_status
+ self.diag_pub.publish(array)
# DISABLE FOR TESTING
# Halt the test if we have a bad transmission
Modified: pkg/trunk/pr2/life_test/simple_test/fake_test.py
===================================================================
--- pkg/trunk/pr2/life_test/simple_test/fake_test.py 2009-08-09 02:42:05 UTC (rev 21209)
+++ pkg/trunk/pr2/life_test/simple_test/fake_test.py 2009-08-09 02:57:45 UTC (rev 21210)
@@ -39,7 +39,7 @@
import wx
import sys
-from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, KeyValue, DiagnosticString
+from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
from std_srvs.srv import *
from mechanism_msgs.msg import MechanismState, JointState, ActuatorState
@@ -57,7 +57,7 @@
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', DiagnosticArray)
self.mech_pub = rospy.Publisher('mechanism_state', MechanismState)
self._mech_timer = wx.Timer(self, 2)
@@ -187,7 +187,7 @@
def publish_diag(self, level, choice):
- msg = DiagnosticMessage()
+ msg = DiagnosticArray()
stat = DiagnosticStatus()
msg.status.append(stat)
Modified: pkg/trunk/pr2/life_test/src/life_test/trans_monitor.py
===================================================================
--- pkg/trunk/pr2/life_test/src/life_test/trans_monitor.py 2009-08-09 02:42:05 UTC (rev 21209)
+++ pkg/trunk/pr2/life_test/src/life_test/trans_monitor.py 2009-08-09 02:57:45 UTC (rev 21210)
@@ -95,15 +95,14 @@
diag.name = "Trans. Monitor: %s" % self._joint
diag.message = "OK"
diag.values = [ ]
- diag.strings = [ ]
- diag.strings.append(KeyValue(value=self._joint, label="Joint"))
- diag.strings.append(KeyValue(value=self._actuator, label="Actuator"))
- diag.strings.append(KeyValue(value=str(self._positive), label="Positive Joint"))
- diag.strings.append(KeyValue(value=str(self._continuous), label="Continuous Joint"))
- diag.values.append(KeyValue(value=float(self._ref_position), label="Reference Position"))
- diag.values.append(KeyValue(value=float(self._deadband), label="Deadband"))
- diag.values.append(KeyValue(value=float(self._rx_count), label="Mech State RX Count"))
+ diag.values.append(KeyValue("Joint", self._joint))
+ diag.values.append(KeyValue("Actuator", self._actuator))
+ diag.values.append(KeyValue("Positive Joint", str(self._positive)))
+ diag.values.append(KeyValue("Continuous Joint", str(self._continuous)))
+ diag.values.append(KeyValue("Reference Position", str(self._ref_position)))
+ diag.values.append(KeyValue("Deadband", str(self._deadband)))
+ diag.values.append(KeyValue("Mech State RX Count", str(self._rx_count)))
# Check if we can find both the joint and actuator
@@ -122,8 +121,8 @@
calibrated = (mech_state.joint_states[joint_names.index(self._joint)].is_calibrated == 1)
- diag.strings.append(KeyValue(value=str(act_exists), label='Actuator Exists'))
- diag.strings.append(KeyValue(value=str(joint_exists), label='Joint Exists'))
+ diag.values.append(KeyValue('Actuator Exists', str(act_exists)))
+ diag.values.append(KeyValue('Joint Exists', str(joint_exists)))
@@ -147,20 +146,20 @@
diag.message = 'Broken'
diag.level = 2
- diag.strings.insert(0, KeyValue(value=diag.message, label='Transmission Status'))
- diag.strings.insert(1, KeyValue(value=reading_msg, label='Current Reading'))
- diag.strings.append(KeyValue(value=str(calibrated), label='Is Calibrated'))
- diag.values.append(KeyValue(value=cal_reading, label='Calibration Reading'))
- diag.values.append(KeyValue(value=position, label='Joint Position'))
+ diag.values.insert(0, KeyValue('Transmission Status', diag.message))
+ diag.values.insert(1, KeyValue('Current Reading', reading_msg))
+ diag.values.append(KeyValue('Is Calibrated', str(calibrated)))
+ diag.values.append(KeyValue('Calibration Reading',str(cal_reading)))
+ diag.values.append(KeyValue('Joint Position', str(position)))
- diag.values.append(KeyValue(value=self._num_errors, label='Total Errors'))
- diag.values.append(KeyValue(value=self._num_errors_since_reset, label='Errors Since Reset'))
+ diag.values.append(KeyValue('Total Errors', str(self._num_errors)))
+ diag.values.append(KeyValue('Errors Since Reset', str(self._num_errors_since_reset)))
self._max_position = max(self._max_position, position)
- diag.values.append(KeyValue(value = self._max_position, label='Max Obs. Position'))
+ diag.values.append(KeyValue('Max Obs. Position', str(self._max_position)))
self._min_position = min(self._min_position, position)
- diag.values.append(KeyValue(value = self._min_position, label='Min Obs. Position'))
+ diag.values.append(KeyValue('Min Obs. Position', str(self._min_position)))
return diag, self._ok
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|