|
From: <bla...@us...> - 2009-08-08 01:39:03
|
Revision: 21112
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21112&view=rev
Author: blaisegassend
Date: 2009-08-08 01:38:54 +0000 (Sat, 08 Aug 2009)
Log Message:
-----------
Changed DiagnosticValue to KeyValue
Modified Paths:
--------------
pkg/trunk/calibration/joint_calibration_monitor/src/joint_calibration_monitor/generic_joint_monitor.py
pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/base_trajectory_controller.cpp
pkg/trunk/controllers/pr2_mechanism_controllers/src/joint_trajectory_controller.cpp
pkg/trunk/drivers/ups/apcupsd_node/scripts/monitor
pkg/trunk/highlevel/doors/doors_core/src/door_reactive_planner.cpp
pkg/trunk/pr2/life_test/simple_test/fake_test.py
pkg/trunk/pr2/life_test/src/life_test/life_test.py
pkg/trunk/pr2/life_test/src/life_test/trans_monitor.py
pkg/trunk/pr2/pr2_computer_monitor/scripts/cpu_monitor.py
pkg/trunk/pr2/pr2_computer_monitor/scripts/hd_monitor.py
pkg/trunk/pr2/pr2_computer_monitor/scripts/ntp_monitor.py
pkg/trunk/stacks/common_msgs/diagnostic_msgs/migration_rules/migration_rules.py
pkg/trunk/stacks/common_msgs/diagnostic_msgs/msg/DiagnosticStatus.msg
pkg/trunk/stacks/common_msgs/test_common_msgs/mainpage.dox
pkg/trunk/stacks/common_msgs/test_common_msgs/test/DiagnosticMessage.saved
pkg/trunk/stacks/common_msgs/test_common_msgs/test/DiagnosticStatus.saved
pkg/trunk/stacks/common_msgs/test_common_msgs/test/test_common_msgs_migration.py
pkg/trunk/stacks/driver_common/dynamic_reconfigure/templates/ConfigReconfigurator.h
pkg/trunk/stacks/hardware_test/diagnostic_test/scripts/diagnostic_test.py
pkg/trunk/stacks/hardware_test/diagnostic_updater/include/diagnostic_updater/DiagnosticStatusWrapper.h
pkg/trunk/stacks/hardware_test/runtime_monitor/scripts/log_runtime_messages
pkg/trunk/stacks/hardware_test/runtime_monitor/scripts/monitor
pkg/trunk/stacks/hardware_test/runtime_monitor/scripts/test_high_level
pkg/trunk/stacks/hardware_test/runtime_monitor/src/runtime_monitor/monitor_panel.py
pkg/trunk/stacks/hardware_test/runtime_monitor/testmonitor.py
pkg/trunk/stacks/mechanism/mechanism_control/scripts/joints_to_diagnostics.py
pkg/trunk/stacks/mechanism/mechanism_control/src/mechanism_control.cpp
pkg/trunk/stacks/pr2/pr2_etherCAT/src/main.cpp
pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/include/ethercat_hardware/ethercat_hardware.h
pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/include/ethercat_hardware/wg0x.h
pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/ek1122.cpp
pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/ethercat_hardware.cpp
pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/wg014.cpp
pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/wg0x.cpp
pkg/trunk/stacks/pr2_power_drivers/ocean_battery_driver/scripts/monitor
pkg/trunk/stacks/pr2_power_drivers/pr2_power_board/src/power_node/power_node.cpp
pkg/trunk/stacks/pr2_power_drivers/pr2_power_board/src/power_node/power_node_simulator.cpp
Modified: pkg/trunk/calibration/joint_calibration_monitor/src/joint_calibration_monitor/generic_joint_monitor.py
===================================================================
--- pkg/trunk/calibration/joint_calibration_monitor/src/joint_calibration_monitor/generic_joint_monitor.py 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/calibration/joint_calibration_monitor/src/joint_calibration_monitor/generic_joint_monitor.py 2009-08-08 01:38:54 UTC (rev 21112)
@@ -66,7 +66,7 @@
# Display the time, just so that something is always updating
#timestamp = mech_state.header.stamp.to_seconds()
- #diag.values.append(DiagnosticValue(value=timestamp, label="Time"))
+ #diag.values.append(KeyValue(value=timestamp, label="Time"))
# Display the actuator and joint names for this monitor
diag.strings.append(DiagnosticString(value=self._actuator, label="Actuator"))
@@ -79,7 +79,7 @@
if act_exists :
cal_flag = mech_state.actuator_states[act_names.index(self._actuator)].calibration_reading
- diag.values.append(DiagnosticValue(value=(1 if act_exists else 0),
+ diag.values.append(KeyValue(value=(1 if act_exists else 0),
label="Actuator Exists"))
joint_names = [x.name for x in mech_state.joint_states]
@@ -87,7 +87,7 @@
if joint_exists :
joint_pos = mech_state.joint_states[joint_names.index(self._joint)].position
- diag.values.append(DiagnosticValue(value=(1 if joint_exists else 0),
+ diag.values.append(KeyValue(value=(1 if joint_exists else 0),
label="Joint Exists"))
if not (act_exists and joint_exists) :
@@ -95,10 +95,10 @@
diag.message = "Error finding joint and actuator"
return diag
- diag.values.append(DiagnosticValue(value=cal_flag,
+ diag.values.append(KeyValue(value=cal_flag,
label="Flag State"))
- diag.values.append(DiagnosticValue(value=joint_pos,
+ diag.values.append(KeyValue(value=joint_pos,
label="Joint Position"))
# Call the predicate to see what the result is for this joint
@@ -116,11 +116,11 @@
diag.strings.append(DiagnosticString(value=self._flag_lookup[sample_result],
label="Flag Check Result"))
- diag.values.append(DiagnosticValue(value=flag_oks,
+ diag.values.append(KeyValue(value=flag_oks,
label="Flag OKs"))
- diag.values.append(DiagnosticValue(value=flag_deadbands,
+ diag.values.append(KeyValue(value=flag_deadbands,
label="Flag Deadbands"))
- diag.values.append(DiagnosticValue(value=flag_errors,
+ diag.values.append(KeyValue(value=flag_errors,
label="Flag Errors"))
if flag_errors > 0 :
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp 2009-08-08 01:38:54 UTC (rev 21112)
@@ -690,10 +690,10 @@
cmd.set_velocity_size(1);
vector<diagnostic_msgs::DiagnosticStatus> statuses;
- vector<diagnostic_msgs::DiagnosticValue> values;
+ vector<diagnostic_msgs::KeyValue> values;
vector<diagnostic_msgs::DiagnosticString> strings;
diagnostic_msgs::DiagnosticStatus status;
- diagnostic_msgs::DiagnosticValue v;
+ diagnostic_msgs::KeyValue v;
status.name = service_prefix_;
status.level = 0;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/base_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/base_trajectory_controller.cpp 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/base_trajectory_controller.cpp 2009-08-08 01:38:54 UTC (rev 21112)
@@ -281,11 +281,11 @@
diagnostic_msgs::DiagnosticMessage message;
std::vector<diagnostic_msgs::DiagnosticStatus> statuses;
- std::vector<diagnostic_msgs::DiagnosticValue> values;
+ std::vector<diagnostic_msgs::KeyValue> values;
std::vector<diagnostic_msgs::DiagnosticString> strings;
diagnostic_msgs::DiagnosticStatus status;
- diagnostic_msgs::DiagnosticValue v;
+ diagnostic_msgs::KeyValue v;
diagnostic_msgs::DiagnosticString s;
status.name = ros_node_.getName();
status.message = control_state_;
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/joint_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/joint_trajectory_controller.cpp 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/joint_trajectory_controller.cpp 2009-08-08 01:38:54 UTC (rev 21112)
@@ -932,10 +932,10 @@
cmd.set_velocity_size(1);
vector<diagnostic_msgs::DiagnosticStatus> statuses;
- vector<diagnostic_msgs::DiagnosticValue> values;
+ vector<diagnostic_msgs::KeyValue> values;
vector<diagnostic_msgs::DiagnosticString> strings;
diagnostic_msgs::DiagnosticStatus status;
- diagnostic_msgs::DiagnosticValue v;
+ diagnostic_msgs::KeyValue v;
diagnostic_msgs::DiagnosticString s;
status.name = "Whole Body Trajectory Controller";
status.level = 0;
Modified: pkg/trunk/drivers/ups/apcupsd_node/scripts/monitor
===================================================================
--- pkg/trunk/drivers/ups/apcupsd_node/scripts/monitor 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/drivers/ups/apcupsd_node/scripts/monitor 2009-08-08 01:38:54 UTC (rev 21112)
@@ -48,7 +48,7 @@
import rospy
from robot_msgs.msg import BatteryState
-from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, DiagnosticValue, DiagnosticString
+from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, KeyValue, DiagnosticString
NAME = 'monitor'
Modified: pkg/trunk/highlevel/doors/doors_core/src/door_reactive_planner.cpp
===================================================================
--- pkg/trunk/highlevel/doors/doors_core/src/door_reactive_planner.cpp 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/highlevel/doors/doors_core/src/door_reactive_planner.cpp 2009-08-08 01:38:54 UTC (rev 21112)
@@ -340,10 +340,10 @@
diagnostic_msgs::DiagnosticStatus DoorReactivePlanner::getDiagnostics()
{
- vector<diagnostic_msgs::DiagnosticValue> values;
+ vector<diagnostic_msgs::KeyValue> values;
vector<diagnostic_msgs::DiagnosticString> strings;
diagnostic_msgs::DiagnosticStatus status;
- diagnostic_msgs::DiagnosticValue v;
+ diagnostic_msgs::KeyValue v;
diagnostic_msgs::DiagnosticString s;
status.name = "Door Reactive Planner";
status.level = 0;
Modified: pkg/trunk/pr2/life_test/simple_test/fake_test.py
===================================================================
--- pkg/trunk/pr2/life_test/simple_test/fake_test.py 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/pr2/life_test/simple_test/fake_test.py 2009-08-08 01:38:54 UTC (rev 21112)
@@ -39,7 +39,7 @@
import wx
import sys
-from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, DiagnosticValue, DiagnosticString
+from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, KeyValue, DiagnosticString
from std_srvs.srv import *
from mechanism_msgs.msg import MechanismState, JointState, ActuatorState
Modified: pkg/trunk/pr2/life_test/src/life_test/life_test.py
===================================================================
--- pkg/trunk/pr2/life_test/src/life_test/life_test.py 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/pr2/life_test/src/life_test/life_test.py 2009-08-08 01:38:54 UTC (rev 21112)
@@ -49,7 +49,7 @@
import rospy
from std_srvs.srv import *
-from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, DiagnosticValue, DiagnosticString
+from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, KeyValue, DiagnosticString
# Stuff from life_test package
from msg import TestStatus
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-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/pr2/life_test/src/life_test/trans_monitor.py 2009-08-08 01:38:54 UTC (rev 21112)
@@ -101,9 +101,9 @@
diag.strings.append(DiagnosticString(value=self._actuator, label="Actuator"))
diag.strings.append(DiagnosticString(value=str(self._positive), label="Positive Joint"))
diag.strings.append(DiagnosticString(value=str(self._continuous), label="Continuous Joint"))
- diag.values.append(DiagnosticValue(value=float(self._ref_position), label="Reference Position"))
- diag.values.append(DiagnosticValue(value=float(self._deadband), label="Deadband"))
- diag.values.append(DiagnosticValue(value=float(self._rx_count), label="Mech State RX Count"))
+ 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"))
# Check if we can find both the joint and actuator
@@ -150,17 +150,17 @@
diag.strings.insert(0, DiagnosticString(value=diag.message, label='Transmission Status'))
diag.strings.insert(1, DiagnosticString(value=reading_msg, label='Current Reading'))
diag.strings.append(DiagnosticString(value=str(calibrated), label='Is Calibrated'))
- diag.values.append(DiagnosticValue(value=cal_reading, label='Calibration Reading'))
- diag.values.append(DiagnosticValue(value=position, label='Joint Position'))
+ diag.values.append(KeyValue(value=cal_reading, label='Calibration Reading'))
+ diag.values.append(KeyValue(value=position, label='Joint Position'))
- diag.values.append(DiagnosticValue(value=self._num_errors, label='Total Errors'))
- diag.values.append(DiagnosticValue(value=self._num_errors_since_reset, label='Errors Since Reset'))
+ 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'))
self._max_position = max(self._max_position, position)
- diag.values.append(DiagnosticValue(value = self._max_position, label='Max Obs. Position'))
+ diag.values.append(KeyValue(value = self._max_position, label='Max Obs. Position'))
self._min_position = min(self._min_position, position)
- diag.values.append(DiagnosticValue(value = self._min_position, label='Min Obs. Position'))
+ diag.values.append(KeyValue(value = self._min_position, label='Min Obs. Position'))
return diag, self._ok
Modified: pkg/trunk/pr2/pr2_computer_monitor/scripts/cpu_monitor.py
===================================================================
--- pkg/trunk/pr2/pr2_computer_monitor/scripts/cpu_monitor.py 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/pr2/pr2_computer_monitor/scripts/cpu_monitor.py 2009-08-08 01:38:54 UTC (rev 21112)
@@ -95,7 +95,7 @@
tmp = ipmi_val.rstrip(' degrees C').lstrip()
if unicode(tmp).isnumeric():
temperature = float(tmp)
- diag_vals.append(DiagnosticValue(label = name, value = temperature))
+ diag_vals.append(KeyValue(label = name, value = temperature))
cpu_name = name.split()[0]
if temperature >= 80 and temperature < 85:
@@ -121,7 +121,7 @@
tmp = ipmi_val.rstrip(' degrees C').lstrip()
if unicode(tmp).isnumeric():
temperature = float(tmp)
- diag_vals.append(DiagnosticValue(label = name, value = temperature))
+ diag_vals.append(KeyValue(label = name, value = temperature))
dev_name = name.split()[0]
if temperature >= 60 and temperature < 70:
@@ -140,7 +140,7 @@
rpm = ipmi_val.rstrip(' RPM').lstrip()
if unicode(rpm).isnumeric():
rpm = float(rpm)
- diag_vals.append(DiagnosticValue(label = name, value = rpm))
+ diag_vals.append(KeyValue(label = name, value = rpm))
else:
diag_strs.append(DiagnosticString(label = name, value = ipmi_val))
@@ -189,7 +189,7 @@
tmp = stdout.strip()
if unicode(tmp).isnumeric():
temp = float(tmp) / 1000
- diag_vals.append(DiagnosticValue(label = 'Core %d Temp' % index, value = temp))
+ diag_vals.append(KeyValue(label = 'Core %d Temp' % index, value = temp))
if temp >= 85 and temp < 90:
diag_level = max(diag_level, 1)
@@ -233,7 +233,7 @@
speed = words[1].strip().split('.')[0]
if unicode(speed).isnumeric():
mhz = float(speed)
- vals.append(DiagnosticValue(label = 'Core %d Speed' % index, value = mhz))
+ vals.append(KeyValue(label = 'Core %d Speed' % index, value = mhz))
if mhz < 2240 and mhz > 2150:
lvl = max(lvl, 1)
@@ -279,10 +279,10 @@
load15 = float(upvals[-1])
num_users = float(upvals[-7])
- vals.append(DiagnosticValue(label = '1 min Load Average', value = load1))
- vals.append(DiagnosticValue(label = '5 min Load Average', value = load5))
- vals.append(DiagnosticValue(label = '15 min Load Average', value = load15))
- vals.append(DiagnosticValue(label = 'Number of Users', value = num_users))
+ vals.append(KeyValue(label = '1 min Load Average', value = load1))
+ vals.append(KeyValue(label = '5 min Load Average', value = load5))
+ vals.append(KeyValue(label = '15 min Load Average', value = load15))
+ vals.append(KeyValue(label = 'Number of Users', value = num_users))
if load1 > 25 or load5 > 18:
level = 1
@@ -321,9 +321,9 @@
used_mem = float(data[2])
free_mem = float(data[3])
- values.append(DiagnosticValue(label = 'Total Memory', value = total_mem))
- values.append(DiagnosticValue(label = 'Used Memory', value = used_mem))
- values.append(DiagnosticValue(label = 'Free Memory', value = free_mem))
+ values.append(KeyValue(label = 'Total Memory', value = total_mem))
+ values.append(KeyValue(label = 'Used Memory', value = used_mem))
+ values.append(KeyValue(label = 'Free Memory', value = free_mem))
level = 0
if free_mem < 10:
@@ -374,10 +374,10 @@
nice = float(lst[4])
system = float(lst[5])
- vals.append(DiagnosticValue(label = 'CPU %s User' % cpu_name, value = user))
- vals.append(DiagnosticValue(label = 'CPU %s Nice' % cpu_name, value = nice))
- vals.append(DiagnosticValue(label = 'CPU %s System' % cpu_name, value = system))
- vals.append(DiagnosticValue(label = 'CPU %s Idle' % cpu_name, value = idle))
+ vals.append(KeyValue(label = 'CPU %s User' % cpu_name, value = user))
+ vals.append(KeyValue(label = 'CPU %s Nice' % cpu_name, value = nice))
+ vals.append(KeyValue(label = 'CPU %s System' % cpu_name, value = system))
+ vals.append(KeyValue(label = 'CPU %s Idle' % cpu_name, value = idle))
core_level = 0
if user + nice > 75.0:
@@ -432,7 +432,7 @@
stat.strings.pop(0)
stat.values.pop(0)
stat.strings.insert(0, DiagnosticString(label = 'Update Status', value = stale_status))
- stat.values.insert(0, DiagnosticValue(label = 'Time Since Update', value = time_since_update))
+ stat.values.insert(0, KeyValue(label = 'Time Since Update', value = time_since_update))
class CPUMonitor():
def __init__(self, hostname):
@@ -455,7 +455,7 @@
self._temp_stat.hardware_id = hostname
self._temp_stat.message = 'No Data'
self._temp_stat.strings = [ DiagnosticString(label = 'Update Status', value = 'No Data' )]
- self._temp_stat.values = [ DiagnosticValue(label = 'Time Since Last Update', value = 100000 )]
+ self._temp_stat.values = [ KeyValue(label = 'Time Since Last Update', value = 100000 )]
self._usage_stat = DiagnosticStatus()
self._usage_stat.name = '%s CPU Usage' % hostname
@@ -463,7 +463,7 @@
self._usage_stat.hardware_id = hostname
self._usage_stat.message = 'No Data'
self._usage_stat.strings = [ DiagnosticString(label = 'Update Status', value = 'No Data' )]
- self._usage_stat.values = [ DiagnosticValue(label = 'Time Since Last Update', value = 100000 )]
+ self._usage_stat.values = [ KeyValue(label = 'Time Since Last Update', value = 100000 )]
self._nfs_stat = DiagnosticStatus()
self._nfs_stat.name = '%s NFS I/O' % hostname
@@ -471,7 +471,7 @@
self._nfs_stat.hardware_id = hostname
self._nfs_stat.message = 'No Data'
self._nfs_stat.strings = [ DiagnosticString(label = 'Update Status', value = 'No Data' )]
- self._nfs_stat.values = [ DiagnosticValue(label = 'Time Since Last Update', value = 100000 )]
+ self._nfs_stat.values = [ KeyValue(label = 'Time Since Last Update', value = 100000 )]
self._last_temp_time = 0
self._last_usage_time = 0
@@ -510,7 +510,7 @@
nfs_level = 0
msg = 'OK'
strs = [ DiagnosticString(label = 'Update Status', value = 'OK' )]
- vals = [ DiagnosticValue(label = 'Time Since Last Update', value = 0 )]
+ vals = [ KeyValue(label = 'Time Since Last Update', value = 0 )]
try:
p = subprocess.Popen('iostat -n',
@@ -535,17 +535,17 @@
r_blk_srv = float(lst[5])
w_blk_srv = float(lst[6])
- vals.append(DiagnosticValue(
+ vals.append(KeyValue(
label = '%s Read Blks/s' % file_sys, value=read_blk))
- vals.append(DiagnosticValue(
+ vals.append(KeyValue(
label = '%s Write Blks/s' % file_sys, value=write_blk))
- vals.append(DiagnosticValue(
+ vals.append(KeyValue(
label = '%s Read Blk dir/s' % file_sys, value=read_blk_dir))
- vals.append(DiagnosticValue(
+ vals.append(KeyValue(
label = '%s Write Blks dir/s' % file_sys, value=write_blk_dir))
- vals.append(DiagnosticValue(
+ vals.append(KeyValue(
label = '%s Read Blks srv/s' % file_sys, value=r_blk_srv))
- vals.append(DiagnosticValue(
+ vals.append(KeyValue(
label = '%s Write Blks srv/s' % file_sys, value=w_blk_srv))
except Exception, e:
@@ -580,7 +580,7 @@
return
diag_strs = [ DiagnosticString(label = 'Update Status', value = 'OK' ) ]
- diag_vals = [ DiagnosticValue(label = 'Time Since Last Update', value = 0 ) ]
+ diag_vals = [ KeyValue(label = 'Time Since Last Update', value = 0 ) ]
diag_msgs = []
diag_level = 0
@@ -634,7 +634,7 @@
diag_level = 0
diag_strs = [ DiagnosticString(label = 'Update Status', value = 'OK' ) ]
- diag_vals = [ DiagnosticValue(label = 'Time Since Last Update', value = 0 )]
+ diag_vals = [ KeyValue(label = 'Time Since Last Update', value = 0 )]
# Check mpstat
mp_level, mp_vals, mp_strs = check_mpstat()
Modified: pkg/trunk/pr2/pr2_computer_monitor/scripts/hd_monitor.py
===================================================================
--- pkg/trunk/pr2/pr2_computer_monitor/scripts/hd_monitor.py 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/pr2/pr2_computer_monitor/scripts/hd_monitor.py 2009-08-08 01:38:54 UTC (rev 21112)
@@ -110,7 +110,7 @@
stat.strings.pop(0)
stat.values.pop(0)
stat.strings.insert(0, DiagnosticString(label = 'Update Status', value = stale_status))
- stat.values.insert(0, DiagnosticValue(label = 'Time Since Update', value = time_since_update))
+ stat.values.insert(0, KeyValue(label = 'Time Since Update', value = time_since_update))
class hdMonitor():
def __init__(self, hostname, home_dir = ''):
@@ -130,7 +130,7 @@
self._temp_stat.hardware_id = hostname
self._temp_stat.message = 'No Data'
self._temp_stat.strings = [ DiagnosticString(label = 'Update Status', value = 'No Data' )]
- self._temp_stat.values = [ DiagnosticValue(label = 'Time Since Last Update', value = 100000 )]
+ self._temp_stat.values = [ KeyValue(label = 'Time Since Last Update', value = 100000 )]
if self._home_dir != '':
self._usage_stat = DiagnosticStatus()
@@ -138,7 +138,7 @@
self._usage_stat.hardware_id = hostname
self._usage_stat.name = '%s HD Usage' % hostname
self._usage_stat.strings = [ DiagnosticString(label = 'Update Status', value = 'No Data' )]
- self._usage_stat.values = [ DiagnosticValue(label = 'Time Since Last Update', value = 100000) ]
+ self._usage_stat.values = [ KeyValue(label = 'Time Since Last Update', value = 100000) ]
self.check_disk_usage()
self._last_temp_time = 0
@@ -170,7 +170,7 @@
return
diag_strs = [ DiagnosticString(label = 'Update Status', value = 'OK' ) ]
- diag_vals = [ DiagnosticValue(label = 'Time Since Last Update', value = 0 ) ]
+ diag_vals = [ KeyValue(label = 'Time Since Last Update', value = 0 ) ]
diag_level = 0
diag_message = 'OK'
@@ -188,7 +188,7 @@
diag_strs.append(DiagnosticString(label = 'Disk %d Temp Status' % index, value = temp_dict[temp_level]))
diag_strs.append(DiagnosticString(label = 'Disk %d Mount Pt.' % index, value = drives[index]))
diag_strs.append(DiagnosticString(label = 'Disk %d Device ID' % index, value = makes[index]))
- diag_vals.append(DiagnosticValue(label = 'Disk %d Temp' % index, value = temp))
+ diag_vals.append(KeyValue(label = 'Disk %d Temp' % index, value = temp))
if not temp_ok:
diag_level = 2
@@ -229,7 +229,7 @@
return
diag_strs = [ DiagnosticString(label = 'Update Status', value = 'OK' ) ]
- diag_vals = [ DiagnosticValue(label = 'Time Since Last Update', value = 0 ) ]
+ diag_vals = [ KeyValue(label = 'Time Since Last Update', value = 0 ) ]
diag_level = 0
diag_message = 'OK'
Modified: pkg/trunk/pr2/pr2_computer_monitor/scripts/ntp_monitor.py
===================================================================
--- pkg/trunk/pr2/pr2_computer_monitor/scripts/ntp_monitor.py 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/pr2/pr2_computer_monitor/scripts/ntp_monitor.py 2009-08-08 01:38:54 UTC (rev 21112)
@@ -34,7 +34,7 @@
import roslib
roslib.load_manifest('pr2_computer_monitor')
-from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, DiagnosticValue, DiagnosticString
+from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, KeyValue, DiagnosticString
import sys
import rospy
import socket
Modified: pkg/trunk/stacks/common_msgs/diagnostic_msgs/migration_rules/migration_rules.py
===================================================================
--- pkg/trunk/stacks/common_msgs/diagnostic_msgs/migration_rules/migration_rules.py 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/common_msgs/diagnostic_msgs/migration_rules/migration_rules.py 2009-08-08 01:38:54 UTC (rev 21112)
@@ -4,11 +4,11 @@
byte level #(OK=0, WARN=1, ERROR=2)
string name # a description of the test/component reporting
string message # a description of the status
-DiagnosticValue[] values # an array of values associated with the status
+KeyValue[] values # an array of values associated with the status
DiagnosticString[] strings # an array of string associated with the status
================================================================================
-MSG: diagnostic_msgs/DiagnosticValue
+MSG: diagnostic_msgs/KeyValue
float32 value # a value to track over time
string label # what to label this value when viewing
@@ -24,11 +24,11 @@
string name # a description of the test/component reporting
string message # a description of the status
string hardware_id # a hardware unique string
-DiagnosticValue[] values # an array of values associated with the status
+KeyValue[] values # an array of values associated with the status
DiagnosticString[] strings # an array of string associated with the status
================================================================================
-MSG: diagnostic_msgs/DiagnosticValue
+MSG: diagnostic_msgs/KeyValue
float32 value # a value to track over time
string label # what to label this value when viewing
@@ -40,7 +40,7 @@
order = 0
migrated_types = [
- ("DiagnosticValue","DiagnosticValue"),
+ ("KeyValue","DiagnosticValue"),
("DiagnosticString","DiagnosticString"),]
valid = True
@@ -50,6 +50,6 @@
new_msg.name = old_msg.name
new_msg.message = old_msg.message
new_msg.hardware_id = 'NONE'
- self.migrate_array(old_msg.values, new_msg.values, "DiagnosticValue")
+ self.migrate_array(old_msg.values, new_msg.values, "KeyValue")
self.migrate_array(old_msg.strings, new_msg.strings, "DiagnosticString")
Modified: pkg/trunk/stacks/common_msgs/diagnostic_msgs/msg/DiagnosticStatus.msg
===================================================================
--- pkg/trunk/stacks/common_msgs/diagnostic_msgs/msg/DiagnosticStatus.msg 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/common_msgs/diagnostic_msgs/msg/DiagnosticStatus.msg 2009-08-08 01:38:54 UTC (rev 21112)
@@ -2,5 +2,5 @@
string name # a description of the test/component reporting
string message # a description of the status
string hardware_id # a hardware unique string
-DiagnosticValue[] values # an array of values associated with the status
+KeyValue[] values # an array of values associated with the status
DiagnosticString[] strings # an array of string associated with the status
Modified: pkg/trunk/stacks/common_msgs/test_common_msgs/mainpage.dox
===================================================================
--- pkg/trunk/stacks/common_msgs/test_common_msgs/mainpage.dox 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/common_msgs/test_common_msgs/mainpage.dox 2009-08-08 01:38:54 UTC (rev 21112)
@@ -19,14 +19,14 @@
diagnostic_status_classes = self.load_saved_classes('DiagnosticStatus.saved')
diagnostic_status = diagnostic_status_classes['diagnostic_msgs/DiagnosticStatus']
- diagnostic_value = diagnostic_status_classes['diagnostic_msgs/DiagnosticValue']
+ diagnostic_value = diagnostic_status_classes['diagnostic_msgs/KeyValue']
diagnostic_value = diagnostic_status_classes['diagnostic_msgs/DiagnosticString']
return diagnostic_status(0, "abcdef", "ghijkl", [diagnostic_value(42.42, 'foo')], [diagnostic_value('xxxxx', 'bar')])
def get_new_diagnostic_status(self):
diagnostic_status = load_current_class('diagnostic_msgs/DiagnosticStatus')
- diagnostic_value = load_current_class('diagnostic_msgs/DiagnosticValue')
+ diagnostic_value = load_current_class('diagnostic_msgs/KeyValue')
diagnostic_value = load_current_class('diagnostic_msgs/DiagnosticString')
return diagnostic_status(0, "abcdef", "ghijkl", [diagnostic_value(42.42, 'foo')], [diagnostic_value('xxxxx', 'bar')])
Modified: pkg/trunk/stacks/common_msgs/test_common_msgs/test/DiagnosticMessage.saved
===================================================================
--- pkg/trunk/stacks/common_msgs/test_common_msgs/test/DiagnosticMessage.saved 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/common_msgs/test_common_msgs/test/DiagnosticMessage.saved 2009-08-08 01:38:54 UTC (rev 21112)
@@ -22,11 +22,11 @@
string name # a description of the test/component reporting
string message # a description of the status
string hardware_id # a hardware unique string
-DiagnosticValue[] values # an array of values associated with the status
+KeyValue[] values # an array of values associated with the status
DiagnosticString[] strings # an array of string associated with the status
================================================================================
-MSG: diagnostic_msgs/DiagnosticValue
+MSG: diagnostic_msgs/KeyValue
float32 value # a value to track over time
string label # what to label this value when viewing
Modified: pkg/trunk/stacks/common_msgs/test_common_msgs/test/DiagnosticStatus.saved
===================================================================
--- pkg/trunk/stacks/common_msgs/test_common_msgs/test/DiagnosticStatus.saved 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/common_msgs/test_common_msgs/test/DiagnosticStatus.saved 2009-08-08 01:38:54 UTC (rev 21112)
@@ -2,11 +2,11 @@
byte level #(OK=0, WARN=1, ERROR=2)
string name # a description of the test/component reporting
string message # a description of the status
-DiagnosticValue[] values # an array of values associated with the status
+KeyValue[] values # an array of values associated with the status
DiagnosticString[] strings # an array of string associated with the status
================================================================================
-MSG: diagnostic_msgs/DiagnosticValue
+MSG: diagnostic_msgs/KeyValue
float32 value # a value to track over time
string label # what to label this value when viewing
Modified: pkg/trunk/stacks/common_msgs/test_common_msgs/test/test_common_msgs_migration.py
===================================================================
--- pkg/trunk/stacks/common_msgs/test_common_msgs/test/test_common_msgs_migration.py 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/common_msgs/test_common_msgs/test/test_common_msgs_migration.py 2009-08-08 01:38:54 UTC (rev 21112)
@@ -57,17 +57,17 @@
diagnostic_status_classes = self.load_saved_classes('DiagnosticStatus.saved')
diagnostic_status = diagnostic_status_classes['diagnostic_msgs/DiagnosticStatus']
- diagnostic_value = diagnostic_status_classes['diagnostic_msgs/DiagnosticValue']
+ diagnostic_value = diagnostic_status_classes['diagnostic_msgs/KeyValue']
diagnostic_string = diagnostic_status_classes['diagnostic_msgs/DiagnosticString']
return diagnostic_status(0, "abcdef", "ghijkl", [diagnostic_value(42.42, 'foo')], [diagnostic_string('xxxxx', 'bar')])
def get_new_diagnostic_status(self):
from diagnostic_msgs.msg import DiagnosticStatus
- from diagnostic_msgs.msg import DiagnosticValue
+ from diagnostic_msgs.msg import KeyValue
from diagnostic_msgs.msg import DiagnosticString
- return DiagnosticStatus(0, "abcdef", "ghijkl", "NONE", [DiagnosticValue(42.42, 'foo')], [DiagnosticString('xxxxx', 'bar')])
+ return DiagnosticStatus(0, "abcdef", "ghijkl", "NONE", [KeyValue(42.42, 'foo')], [DiagnosticString('xxxxx', 'bar')])
def test_diagnostic_status(self):
Modified: pkg/trunk/stacks/driver_common/dynamic_reconfigure/templates/ConfigReconfigurator.h
===================================================================
--- pkg/trunk/stacks/driver_common/dynamic_reconfigure/templates/ConfigReconfigurator.h 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/driver_common/dynamic_reconfigure/templates/ConfigReconfigurator.h 2009-08-08 01:38:54 UTC (rev 21112)
@@ -109,6 +109,11 @@
return changelvl;
}
+ static void clamp(ConfigType &config)
+ {
+#line ${linenum} "${filename}"
+ }
+
private:
static bool initialized;
static boost::mutex initializing;
Modified: pkg/trunk/stacks/hardware_test/diagnostic_test/scripts/diagnostic_test.py
===================================================================
--- pkg/trunk/stacks/hardware_test/diagnostic_test/scripts/diagnostic_test.py 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/hardware_test/diagnostic_test/scripts/diagnostic_test.py 2009-08-08 01:38:54 UTC (rev 21112)
@@ -40,7 +40,7 @@
import sys, time
import rospy
-from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, DiagnosticValue, DiagnosticString
+from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, KeyValue, DiagnosticString
NAME = 'diagnostic_test'
Modified: pkg/trunk/stacks/hardware_test/diagnostic_updater/include/diagnostic_updater/DiagnosticStatusWrapper.h
===================================================================
--- pkg/trunk/stacks/hardware_test/diagnostic_updater/include/diagnostic_updater/DiagnosticStatusWrapper.h 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/hardware_test/diagnostic_updater/include/diagnostic_updater/DiagnosticStatusWrapper.h 2009-08-08 01:38:54 UTC (rev 21112)
@@ -116,7 +116,7 @@
void addv(const std::string &key, double v)
{
- diagnostic_msgs::DiagnosticValue dv;
+ diagnostic_msgs::KeyValue dv;
dv.label = key;
dv.value = v;
values.push_back(dv);
Modified: pkg/trunk/stacks/hardware_test/runtime_monitor/scripts/log_runtime_messages
===================================================================
--- pkg/trunk/stacks/hardware_test/runtime_monitor/scripts/log_runtime_messages 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/hardware_test/runtime_monitor/scripts/log_runtime_messages 2009-08-08 01:38:54 UTC (rev 21112)
@@ -40,7 +40,7 @@
import sys
import rospy
-from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, DiagnosticValue, DiagnosticString
+from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, KeyValue, DiagnosticString
NAME = 'runtime_monitor_logging'
Modified: pkg/trunk/stacks/hardware_test/runtime_monitor/scripts/monitor
===================================================================
--- pkg/trunk/stacks/hardware_test/runtime_monitor/scripts/monitor 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/hardware_test/runtime_monitor/scripts/monitor 2009-08-08 01:38:54 UTC (rev 21112)
@@ -39,7 +39,7 @@
import sys
import rospy
-from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, DiagnosticValue, DiagnosticString
+from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, KeyValue, DiagnosticString
NAME = 'runtime_monitor'
Modified: pkg/trunk/stacks/hardware_test/runtime_monitor/scripts/test_high_level
===================================================================
--- pkg/trunk/stacks/hardware_test/runtime_monitor/scripts/test_high_level 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/hardware_test/runtime_monitor/scripts/test_high_level 2009-08-08 01:38:54 UTC (rev 21112)
@@ -39,7 +39,7 @@
import sys
import rospy
-from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, DiagnosticValue, DiagnosticString
+from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, KeyValue, DiagnosticString
NAME = 'runtime_monitor'
Modified: pkg/trunk/stacks/hardware_test/runtime_monitor/src/runtime_monitor/monitor_panel.py
===================================================================
--- pkg/trunk/stacks/hardware_test/runtime_monitor/src/runtime_monitor/monitor_panel.py 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/hardware_test/runtime_monitor/src/runtime_monitor/monitor_panel.py 2009-08-08 01:38:54 UTC (rev 21112)
@@ -39,7 +39,7 @@
import sys
import rospy
-from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, DiagnosticValue, DiagnosticString
+from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, KeyValue, DiagnosticString
import wx
from wx import xrc
Modified: pkg/trunk/stacks/hardware_test/runtime_monitor/testmonitor.py
===================================================================
--- pkg/trunk/stacks/hardware_test/runtime_monitor/testmonitor.py 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/hardware_test/runtime_monitor/testmonitor.py 2009-08-08 01:38:54 UTC (rev 21112)
@@ -39,7 +39,7 @@
import sys, time
import rospy
-from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, DiagnosticValue, DiagnosticString
+from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, KeyValue, DiagnosticString
NAME = 'test_runtime_broadcaster'
@@ -50,10 +50,10 @@
for c in range(0,4):
floatval = []
strval = []
- floatval.append(DiagnosticValue(c, "Time Remaining Controller %d"%c))
- floatval.append(DiagnosticValue(c+.1, "Average charge percent Controller %d"%c))
- floatval.append(DiagnosticValue(c+.2, "Current Controller %d"%c))
- floatval.append(DiagnosticValue(c+.2, "Voltage Controller %d"%c))
+ floatval.append(KeyValue(c, "Time Remaining Controller %d"%c))
+ floatval.append(KeyValue(c+.1, "Average charge percent Controller %d"%c))
+ floatval.append(KeyValue(c+.2, "Current Controller %d"%c))
+ floatval.append(KeyValue(c+.2, "Voltage Controller %d"%c))
strval.append(DiagnosticString("String Value","Controller String Label"))
stat.append(DiagnosticStatus(c, "IBPS %d"%c, "All good", floatval,strval))
## @todo make the status string represent errors etc
@@ -61,9 +61,9 @@
for b in range(0,4):
bval = []
bstrval = []
- bval.append(DiagnosticValue(c+b*.01+.1, "present (0,1)"))
- bval.append(DiagnosticValue(c+b*.01+.2, "charging (0,1)"))
- bval.append(DiagnosticValue(c+b*.01+.3, "supplying power (0,1)"))
+ bval.append(KeyValue(c+b*.01+.1, "present (0,1)"))
+ bval.append(KeyValue(c+b*.01+.2, "charging (0,1)"))
+ bval.append(KeyValue(c+b*.01+.3, "supplying power (0,1)"))
bstrval.append(DiagnosticString("String Value","Controller, String Label"))
for a in range(0,100):
Modified: pkg/trunk/stacks/mechanism/mechanism_control/scripts/joints_to_diagnostics.py
===================================================================
--- pkg/trunk/stacks/mechanism/mechanism_control/scripts/joints_to_diagnostics.py 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/mechanism/mechanism_control/scripts/joints_to_diagnostics.py 2009-08-08 01:38:54 UTC (rev 21112)
@@ -41,11 +41,11 @@
d.message = 'UNCALIBRATED'
d.name = "Joint (%s)" % js.name
d.values = [
- DiagnosticValue(js.position, 'Position'),
- DiagnosticValue(js.velocity, 'Velocity'),
- DiagnosticValue(js.applied_effort, 'Applied Effort'),
- DiagnosticValue(js.commanded_effort, 'Commanded Effort'),
- DiagnosticValue(js.is_calibrated, 'Calibrated')]
+ KeyValue(js.position, 'Position'),
+ KeyValue(js.velocity, 'Velocity'),
+ KeyValue(js.applied_effort, 'Applied Effort'),
+ KeyValue(js.commanded_effort, 'Commanded Effort'),
+ KeyValue(js.is_calibrated, 'Calibrated')]
return d
rospy.init_node('joints_to_diagnostics')
Modified: pkg/trunk/stacks/mechanism/mechanism_control/src/mechanism_control.cpp
===================================================================
--- pkg/trunk/stacks/mechanism/mechanism_control/src/mechanism_control.cpp 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/mechanism/mechanism_control/src/mechanism_control.cpp 2009-08-08 01:38:54 UTC (rev 21112)
@@ -451,10 +451,10 @@
TimeStatistics blank_statistics;
std::vector<diagnostic_msgs::DiagnosticStatus> statuses;
- std::vector<diagnostic_msgs::DiagnosticValue> values;
+ std::vector<diagnostic_msgs::KeyValue> values;
std::vector<diagnostic_msgs::DiagnosticString> strings;
diagnostic_msgs::DiagnosticStatus status;
- diagnostic_msgs::DiagnosticValue v;
+ diagnostic_msgs::KeyValue v;
diagnostic_msgs::DiagnosticString s;
status.name = "Mechanism Control";
Modified: pkg/trunk/stacks/pr2/pr2_etherCAT/src/main.cpp
===================================================================
--- pkg/trunk/stacks/pr2/pr2_etherCAT/src/main.cpp 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/pr2/pr2_etherCAT/src/main.cpp 2009-08-08 01:38:54 UTC (rev 21112)
@@ -103,10 +103,10 @@
{
accumulator_set<double, stats<tag::max, tag::mean> > zero;
vector<diagnostic_msgs::DiagnosticStatus> statuses;
- vector<diagnostic_msgs::DiagnosticValue> values;
+ vector<diagnostic_msgs::KeyValue> values;
vector<diagnostic_msgs::DiagnosticString> strings;
diagnostic_msgs::DiagnosticStatus status;
- diagnostic_msgs::DiagnosticValue v;
+ diagnostic_msgs::KeyValue v;
diagnostic_msgs::DiagnosticString s;
static double max_ec = 0, max_mc = 0;
Modified: pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/include/ethercat_hardware/ethercat_hardware.h
===================================================================
--- pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/include/ethercat_hardware/ethercat_hardware.h 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/include/ethercat_hardware/ethercat_hardware.h 2009-08-08 01:38:54 UTC (rev 21112)
@@ -109,7 +109,7 @@
double last_published_;
vector<diagnostic_msgs::DiagnosticStatus> statuses_;
- vector<diagnostic_msgs::DiagnosticValue> values_;
+ vector<diagnostic_msgs::KeyValue> values_;
vector<diagnostic_msgs::DiagnosticString> strings_;
};
Modified: pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/include/ethercat_hardware/wg0x.h
===================================================================
--- pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/include/ethercat_hardware/wg0x.h 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/include/ethercat_hardware/wg0x.h 2009-08-08 01:38:54 UTC (rev 21112)
@@ -304,7 +304,7 @@
// Diagnostic message values
vector<diagnostic_msgs::DiagnosticString> strings_;
- vector<diagnostic_msgs::DiagnosticValue> values_;
+ vector<diagnostic_msgs::KeyValue> values_;
string reason_;
int level_;
double voltage_error_, max_voltage_error_;
Modified: pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/ek1122.cpp
===================================================================
--- pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/ek1122.cpp 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/ek1122.cpp 2009-08-08 01:38:54 UTC (rev 21112)
@@ -59,8 +59,8 @@
void EK1122::diagnostics(diagnostic_msgs::DiagnosticStatus &d, unsigned char *)
{
vector<diagnostic_msgs::DiagnosticString> strings;
- vector<diagnostic_msgs::DiagnosticValue> values;
- diagnostic_msgs::DiagnosticValue v;
+ vector<diagnostic_msgs::KeyValue> values;
+ diagnostic_msgs::KeyValue v;
diagnostic_msgs::DiagnosticString s;
stringstream str;
Modified: pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/ethercat_hardware.cpp
===================================================================
--- pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/ethercat_hardware.cpp 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/ethercat_hardware.cpp 2009-08-08 01:38:54 UTC (rev 21112)
@@ -209,7 +209,7 @@
{
// Publish status of EtherCAT master
diagnostic_msgs::DiagnosticStatus status;
- diagnostic_msgs::DiagnosticValue v;
+ diagnostic_msgs::KeyValue v;
diagnostic_msgs::DiagnosticString s;
strings_.clear();
Modified: pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/wg014.cpp
===================================================================
--- pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/wg014.cpp 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/wg014.cpp 2009-08-08 01:38:54 UTC (rev 21112)
@@ -67,8 +67,8 @@
void WG014::diagnostics(diagnostic_msgs::DiagnosticStatus &d, unsigned char *)
{
vector<diagnostic_msgs::DiagnosticString> strings;
- vector<diagnostic_msgs::DiagnosticValue> values;
- diagnostic_msgs::DiagnosticValue v;
+ vector<diagnostic_msgs::KeyValue> values;
+ diagnostic_msgs::KeyValue v;
diagnostic_msgs::DiagnosticString s;
stringstream str;
Modified: pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/wg0x.cpp
===================================================================
--- pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/wg0x.cpp 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/wg0x.cpp 2009-08-08 01:38:54 UTC (rev 21112)
@@ -878,7 +878,7 @@
strings_.push_back(s)
void WG0X::diagnostics(diagnostic_msgs::DiagnosticStatus &d, unsigned char *buffer)
{
- diagnostic_msgs::DiagnosticValue v;
+ diagnostic_msgs::KeyValue v;
diagnostic_msgs::DiagnosticString s;
WG0XStatus *status = (WG0XStatus *)(buffer + command_size_);
Modified: pkg/trunk/stacks/pr2_power_drivers/ocean_battery_driver/scripts/monitor
===================================================================
--- pkg/trunk/stacks/pr2_power_drivers/ocean_battery_driver/scripts/monitor 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/pr2_power_drivers/ocean_battery_driver/scripts/monitor 2009-08-08 01:38:54 UTC (rev 21112)
@@ -48,7 +48,7 @@
import rospy
from robot_msgs.msg import BatteryState
-from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, DiagnosticValue, DiagnosticString
+from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, KeyValue, DiagnosticString
import socket
@@ -212,7 +212,7 @@
(c.total_current(), "Current (A)"),
(c.average_voltage(), "Voltage (V)"),
(time.time() - c.last_time, "Time since update (s)")]
- sval = [DiagnosticValue(v, s) for v,s in sval]
+ sval = [KeyValue(v, s) for v,s in sval]
controller_status_value = 0
controller_status_string = "OK"
if timeout < time.time() - c.last_time:
@@ -263,7 +263,7 @@
(b.design_capacity, "design capacity (mAh)"),
(b.design_voltage, "design voltage (V)"),
(time.time() - b.last_time, "Time since update (s)")]
- bval = [DiagnosticValue(v, s) for v,s in bval]
+ bval = [KeyValue(v, s) for v,s in bval]
stringval = [DiagnosticString("%s"%b.serial_number, "Serial Number")]
##stringval.append(DiagnosticString(b.chemistry, "Chemistry"))
Modified: pkg/trunk/stacks/pr2_power_drivers/pr2_power_board/src/power_node/power_node.cpp
===================================================================
--- pkg/trunk/stacks/pr2_power_drivers/pr2_power_board/src/power_node/power_node.cpp 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/pr2_power_drivers/pr2_power_board/src/power_node/power_node.cpp 2009-08-08 01:38:54 UTC (rev 21112)
@@ -643,7 +643,7 @@
{
diagnostic_msgs::DiagnosticMessage msg_out;
diagnostic_msgs::DiagnosticStatus stat;
- diagnostic_msgs::DiagnosticValue val;
+ diagnostic_msgs::KeyValue val;
diagnostic_msgs::DiagnosticString strval;
ros::Rate r(1);
Modified: pkg/trunk/stacks/pr2_power_drivers/pr2_power_board/src/power_node/power_node_simulator.cpp
===================================================================
--- pkg/trunk/stacks/pr2_power_drivers/pr2_power_board/src/power_node/power_node_simulator.cpp 2009-08-08 01:34:08 UTC (rev 21111)
+++ pkg/trunk/stacks/pr2_power_drivers/pr2_power_board/src/power_node/power_node_simulator.cpp 2009-08-08 01:38:54 UTC (rev 21112)
@@ -333,7 +333,7 @@
{
diagnostic_msgs::DiagnosticMessage msg_out;
diagnostic_msgs::DiagnosticStatus stat;
- diagnostic_msgs::DiagnosticValue val;
+ diagnostic_msgs::KeyValue val;
diagnostic_msgs::DiagnosticString strval;
while(ok())
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|