|
From: <rob...@us...> - 2008-09-17 21:26:53
|
Revision: 4398
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=4398&view=rev
Author: rob_wheeler
Date: 2008-09-17 21:26:58 +0000 (Wed, 17 Sep 2008)
Log Message:
-----------
Change value_label to label
Modified Paths:
--------------
pkg/trunk/controllers/testing_controllers/motor_qualification_controllers/src/motor_test2.cpp
pkg/trunk/controllers/testing_controllers/motor_qualification_controllers/src/motor_test4.cpp
pkg/trunk/drivers/cam/axis_cam/src/axis_cam/axis_cam.cpp
pkg/trunk/drivers/imu/imu_node/imu_node.cc
pkg/trunk/drivers/motor/ethercat_hardware/src/ethercat_hardware.cpp
pkg/trunk/drivers/motor/ethercat_hardware/src/wg0x.cpp
pkg/trunk/hardware_test/qualification/src/qualification/base_test.py
pkg/trunk/hardware_test/runtime_monitor/monitor
pkg/trunk/hardware_test/runtime_monitor/wxmonitor
pkg/trunk/hardware_test/self_test/src/run_selftest.cpp
pkg/trunk/robot_msgs/msg/DiagnosticValue.msg
Modified: pkg/trunk/controllers/testing_controllers/motor_qualification_controllers/src/motor_test2.cpp
===================================================================
--- pkg/trunk/controllers/testing_controllers/motor_qualification_controllers/src/motor_test2.cpp 2008-09-17 21:26:22 UTC (rev 4397)
+++ pkg/trunk/controllers/testing_controllers/motor_qualification_controllers/src/motor_test2.cpp 2008-09-17 21:26:58 UTC (rev 4398)
@@ -171,9 +171,9 @@
//the motor isn't moving
status->level = 2;
status->message = "ERROR: The motor is not correctly labeled. The speed constant is not correct.";
- status->values[0].value_label = "measured speed constant";
+ status->values[0].label = "measured speed constant";
status->values[0].value = speed_const_meas;
- status->values[1].value_label = "expected speed constant";
+ status->values[1].label = "expected speed constant";
status->values[1].value = speed_constant_;
}
else
@@ -181,9 +181,9 @@
//test passed
status->level = 0;
status->message = "OK: Passed.";
- status->values[0].value_label = "measured speed constant";
+ status->values[0].label = "measured speed constant";
status->values[0].value = speed_const_meas;
- status->values[1].value_label = "expected speed constant";
+ status->values[1].label = "expected speed constant";
status->values[1].value = speed_constant_;
}
publisher_.publish(diagnostic_message_);
Modified: pkg/trunk/controllers/testing_controllers/motor_qualification_controllers/src/motor_test4.cpp
===================================================================
--- pkg/trunk/controllers/testing_controllers/motor_qualification_controllers/src/motor_test4.cpp 2008-09-17 21:26:22 UTC (rev 4397)
+++ pkg/trunk/controllers/testing_controllers/motor_qualification_controllers/src/motor_test4.cpp 2008-09-17 21:26:58 UTC (rev 4398)
@@ -159,9 +159,9 @@
//the motor isn't moving
status->level = 2;
status->message = "ERROR: The motor is not correctly labeled. The speed constant is not correct.";
- status->values[0].value_label = "measured speed constant";
+ status->values[0].label = "measured speed constant";
status->values[0].value = speed_torque_const_meas;
- status->values[1].value_label = "expected speed constant";
+ status->values[1].label = "expected speed constant";
status->values[1].value = speed_torque_constant_;
}
else
@@ -169,9 +169,9 @@
//test passed
status->level = 0;
status->message = "OK: Passed.";
- status->values[0].value_label = "measured speed constant";
+ status->values[0].label = "measured speed constant";
status->values[0].value = speed_torque_const_meas;
- status->values[1].value_label = "expected speed constant";
+ status->values[1].label = "expected speed constant";
status->values[1].value = speed_torque_constant_;
}
publisher_.publish(diagnostic_message_);
Modified: pkg/trunk/drivers/cam/axis_cam/src/axis_cam/axis_cam.cpp
===================================================================
--- pkg/trunk/drivers/cam/axis_cam/src/axis_cam/axis_cam.cpp 2008-09-17 21:26:22 UTC (rev 4397)
+++ pkg/trunk/drivers/cam/axis_cam/src/axis_cam/axis_cam.cpp 2008-09-17 21:26:58 UTC (rev 4398)
@@ -164,9 +164,9 @@
status.level = 0;
status.message = "Retrieved image successfully.";
status.set_values_size(2);
- status.values[0].value_label = "Width";
+ status.values[0].label = "Width";
status.values[0].value = image.width;
- status.values[1].value_label = "Height";
+ status.values[1].label = "Height";
status.values[1].value = image.height;
}
}
Modified: pkg/trunk/drivers/imu/imu_node/imu_node.cc
===================================================================
--- pkg/trunk/drivers/imu/imu_node/imu_node.cc 2008-09-17 21:26:22 UTC (rev 4397)
+++ pkg/trunk/drivers/imu/imu_node/imu_node.cc 2008-09-17 21:26:58 UTC (rev 4398)
@@ -328,12 +328,12 @@
status.message = "Successfully calculated gyro biases.";
status.set_values_size(3);
- status.values[0].value_label = "Bias_X";
- status.values[0].value = bias_x;
- status.values[1].value_label = "Bias_Y";
- status.values[1].value = bias_y;
- status.values[2].value_label = "Bias_Z";
- status.values[2].value = bias_z;
+ status.values[0].label = "Bias_X";
+ status.values[0].value = bias_x;
+ status.values[1].label = "Bias_Y";
+ status.values[1].value = bias_y;
+ status.values[2].label = "Bias_Z";
+ status.values[2].value = bias_z;
}
@@ -417,10 +417,10 @@
}
status.set_values_size(2);
- status.values[0].value_label = "Measured gravity";
- status.values[0].value = grav;
- status.values[1].value_label = "Gravity error";
- status.values[1].value = err;
+ status.values[0].label = "Measured gravity";
+ status.values[0].value = grav;
+ status.values[1].label = "Gravity error";
+ status.values[1].value = err;
}
}
Modified: pkg/trunk/drivers/motor/ethercat_hardware/src/ethercat_hardware.cpp
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/src/ethercat_hardware.cpp 2008-09-17 21:26:22 UTC (rev 4397)
+++ pkg/trunk/drivers/motor/ethercat_hardware/src/ethercat_hardware.cpp 2008-09-17 21:26:58 UTC (rev 4398)
@@ -202,7 +202,7 @@
// Num devices
v.value = num_slaves_;
- v.value_label = "EtherCAT devices";
+ v.label = "EtherCAT devices";
values.push_back(v);
// Interface
@@ -218,11 +218,11 @@
diagnostics_.max_roundtrip_ = max(diagnostics_.max_roundtrip_, diagnostics_.iteration_[i].roundtrip_);
}
v.value = total / 1000.0;
- v.value_label = "Average roundtrip time";
+ v.label = "Average roundtrip time";
values.push_back(v);
v.value = diagnostics_.max_roundtrip_;
- v.value_label = "Maximum roundtrip time";
+ v.label = "Maximum roundtrip time";
values.push_back(v);
status.set_values_vec(values);
Modified: pkg/trunk/drivers/motor/ethercat_hardware/src/wg0x.cpp
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/src/wg0x.cpp 2008-09-17 21:26:22 UTC (rev 4397)
+++ pkg/trunk/drivers/motor/ethercat_hardware/src/wg0x.cpp 2008-09-17 21:26:58 UTC (rev 4398)
@@ -688,7 +688,7 @@
s.value = (val); \
strings.push_back(s)
#define ADD_VALUE(lab, val) \
- v.value_label = (lab); \
+ v.label = (lab); \
v.value = (val); \
values.push_back(v)
void WG0X::diagnostics(robot_msgs::DiagnosticStatus &d)
Modified: pkg/trunk/hardware_test/qualification/src/qualification/base_test.py
===================================================================
--- pkg/trunk/hardware_test/qualification/src/qualification/base_test.py 2008-09-17 21:26:22 UTC (rev 4397)
+++ pkg/trunk/hardware_test/qualification/src/qualification/base_test.py 2008-09-17 21:26:58 UTC (rev 4398)
@@ -194,7 +194,7 @@
res += 'Test %2d) %s\n' % (i, stat.name)
res += ' [%s]: %s\n' % (statdict[stat.level], stat.message)
for val in stat.values:
- res += ' [%s] = %f\n' % (val.value_label, val.value)
+ res += ' [%s] = %f\n' % (val.label, val.value)
i += 1
head = '----------------------------------------\n'
Modified: pkg/trunk/hardware_test/runtime_monitor/monitor
===================================================================
--- pkg/trunk/hardware_test/runtime_monitor/monitor 2008-09-17 21:26:22 UTC (rev 4397)
+++ pkg/trunk/hardware_test/runtime_monitor/monitor 2008-09-17 21:26:58 UTC (rev 4398)
@@ -50,7 +50,7 @@
## @TODO process byte level
print "Name: %s \nMessage: %s"%(s.name, s.message)
for v in s.values:
- print " Value: %.2f Label: %s"%(v.value, v.value_label)
+ print " Value: %.2f Label: %s"%(v.value, v.label)
def listener():
rospy.TopicSub("/diagnostics", DiagnosticMessage, callback)
Modified: pkg/trunk/hardware_test/runtime_monitor/wxmonitor
===================================================================
--- pkg/trunk/hardware_test/runtime_monitor/wxmonitor 2008-09-17 21:26:22 UTC (rev 4397)
+++ pkg/trunk/hardware_test/runtime_monitor/wxmonitor 2008-09-17 21:26:58 UTC (rev 4398)
@@ -123,7 +123,7 @@
for v in self.components[self.button_id_dict[e.GetId()]].strings:
values_str = values_str + "%s: %s\n"%(v.label, v.value)
for v in self.components[self.button_id_dict[e.GetId()]].values:
- values_str = values_str + "%s: %f\n"%(v.value_label, v.value)
+ values_str = values_str + "%s: %f\n"%(v.label, v.value)
d = wx.MessageDialog(self, "%s\n%s\n%s"%(self.components[self.button_id_dict[e.GetId()]].name, self.components[self.button_id_dict[e.GetId()]].message, values_str),"%s"%self.components[self.button_id_dict[e.GetId()]].name, wx.OK)
Modified: pkg/trunk/hardware_test/self_test/src/run_selftest.cpp
===================================================================
--- pkg/trunk/hardware_test/self_test/src/run_selftest.cpp 2008-09-17 21:26:22 UTC (rev 4397)
+++ pkg/trunk/hardware_test/self_test/src/run_selftest.cpp 2008-09-17 21:26:58 UTC (rev 4398)
@@ -73,7 +73,7 @@
printf("%s\n", res.status[i].message.c_str());
for (size_t j = 0; j < res.status[i].get_values_size(); j++)
- printf(" [%s] %f\n", res.status[i].values[j].value_label.c_str(), res.status[i].values[j].value);
+ printf(" [%s] %f\n", res.status[i].values[j].label.c_str(), res.status[i].values[j].value);
printf("\n");
}
Modified: pkg/trunk/robot_msgs/msg/DiagnosticValue.msg
===================================================================
--- pkg/trunk/robot_msgs/msg/DiagnosticValue.msg 2008-09-17 21:26:22 UTC (rev 4397)
+++ pkg/trunk/robot_msgs/msg/DiagnosticValue.msg 2008-09-17 21:26:58 UTC (rev 4398)
@@ -1,2 +1,2 @@
float32 value # a value to track over time
-string value_label # what to label this value when viewing
+string label # what to label this value when viewing
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|