|
From: <jfa...@us...> - 2009-08-09 01:24:11
|
Revision: 21203
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=21203&view=rev
Author: jfaustwg
Date: 2009-08-09 01:23:59 +0000 (Sun, 09 Aug 2009)
Log Message:
-----------
Fixes for diagnostic_msgs::KeyValue::label -> key
Modified Paths:
--------------
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/controllers/robot_mechanism_controllers/src/cartesian_wrench_controller.cpp
pkg/trunk/controllers/robot_mechanism_controllers/src/joint_inverse_dynamics_controller.cpp
pkg/trunk/demos/led_demo/led_status_demo.py
pkg/trunk/drivers/cam/axis_cam/src/axis_cam/axis_cam.cpp
pkg/trunk/highlevel/doors/doors_core/src/door_reactive_planner.cpp
pkg/trunk/pr2/qualification/scripts/run_selftest.py
pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp
pkg/trunk/stacks/camera_drivers/dcam/src/nodes/stereodcam.cpp
pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp
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/diagnostic_updater/test/diagnostic_updater_test.cpp
pkg/trunk/stacks/hardware_test/diagnostics_analysis/export_csv.py
pkg/trunk/stacks/hardware_test/self_test/src/run_selftest.cpp
pkg/trunk/stacks/hardware_test/self_test/src/selftest_example.cpp
pkg/trunk/stacks/hardware_test/self_test/src/selftest_rostest.cpp
pkg/trunk/stacks/imu_drivers/imu_node/imu_node.cc
pkg/trunk/stacks/laser_drivers/hokuyo_node/src/node/hokuyo_node.cpp
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/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/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
pkg/trunk/stacks/pr2_power_drivers/pr2_power_board/src/pr2_power_board/pr2_power_board_panel.py
pkg/trunk/stacks/stereo/stereo_image_proc/src/stereoproc.cpp
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-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -702,18 +702,18 @@
for(unsigned int i=0; i < c_->joint_pd_controllers_.size(); i++)
{
- v.label = c_->joint_pd_controllers_[i]->getJointName() + "/Position/Actual";
+ v.key = c_->joint_pd_controllers_[i]->getJointName() + "/Position/Actual";
v.value = c_->joint_pd_controllers_[i]->joint_state_->position_;
values.push_back(v);
// ROS_INFO("Diagnostics %d: 1",i);
- v.label = c_->joint_pd_controllers_[i]->getJointName() + "/Position/Command";
+ v.key = c_->joint_pd_controllers_[i]->getJointName() + "/Position/Command";
c_->joint_pd_controllers_[i]->getCommand(cmd);
v.value = cmd.positions[0];
values.push_back(v);
- v.label = c_->joint_pd_controllers_[i]->getJointName() + "/Position/Error (Command-Actual)";
+ v.key = c_->joint_pd_controllers_[i]->getJointName() + "/Position/Error (Command-Actual)";
v.value = cmd.positions[0] - c_->joint_pd_controllers_[i]->joint_state_->position_;
values.push_back(v);
@@ -721,35 +721,35 @@
}
- v.label = "Trajectory id";
+ v.key = "Trajectory id";
v.value = current_trajectory_id_;
values.push_back(v);
// ROS_INFO("Diagnostics 2");
- v.label = "Trajectory Status:: ";
+ v.key = "Trajectory Status:: ";
std::map<int, int>::const_iterator it = joint_trajectory_status_.find((int)current_trajectory_id_);
if(it == joint_trajectory_status_.end())
{
- v.label += "UNKNOWN";
+ v.key += "UNKNOWN";
v.value = -1;
}
else
{
- v.label += JointTrajectoryStatusString[it->second];
+ v.key += JointTrajectoryStatusString[it->second];
v.value = it->second;
}
values.push_back(v);
// ROS_INFO("Diagnostics 3");
- v.label = "Trajectory Current Time";
+ v.key = "Trajectory Current Time";
v.value = c_->current_time_-c_->trajectory_start_time_;
values.push_back(v);
// ROS_INFO("Diagnostics 4");
- v.label = "Trajectory Expected End Time (computed)";
+ v.key = "Trajectory Expected End Time (computed)";
v.value = c_->trajectory_end_time_-c_->trajectory_start_time_;
values.push_back(v);
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-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/base_trajectory_controller.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -288,55 +288,55 @@
status.name = ros_node_.getName();
status.message = control_state_;
- v.label = "Error.x";
+ v.key = "Error.x";
v.value = error_x_;
values.push_back(v);
- v.label = "Error.y";
+ v.key = "Error.y";
v.value = error_y_;
values.push_back(v);
- v.label = "Error.th";
+ v.key = "Error.th";
v.value = error_th_;
values.push_back(v);
- v.label = "Goal.x";
+ v.key = "Goal.x";
v.value = goal_.q_[0];
values.push_back(v);
- v.label = "Goal.y";
+ v.key = "Goal.y";
v.value = goal_.q_[1];
values.push_back(v);
- v.label = "Goal.th";
+ v.key = "Goal.th";
v.value = goal_.q_[2];
values.push_back(v);
- v.label = "Number of waypoints";
+ v.key = "Number of waypoints";
v.value = path_msg_.get_points_size();
values.push_back(v);
- v.label = "Controller frequency (Hz)";
+ v.key = "Controller frequency (Hz)";
v.value = controller_frequency_;
values.push_back(v);
- v.label = "Max update delta time (s)";
+ v.key = "Max update delta time (s)";
v.value = max_update_time_;
values.push_back(v);
- v.label = "Control topic name";
+ v.key = "Control topic name";
v.value = control_topic_name_;
values.push_back(v);
- v.label = "Global frame";
+ v.key = "Global frame";
v.value = global_frame_;
values.push_back(v);
- v.label = "Path input topic name";
+ v.key = "Path input topic name";
v.value = path_input_topic_name_;
values.push_back(v);
- v.label = "Trajectory type";
+ v.key = "Trajectory type";
v.value = trajectory_type_;
values.push_back(v);
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-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/joint_trajectory_controller.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -948,93 +948,93 @@
for(unsigned int i=0; i < joint_pv_controllers_.size(); i++)
{
- v.label = joint_pv_controllers_[i]->getJointName() + "/Position/Actual";
+ v.key = joint_pv_controllers_[i]->getJointName() + "/Position/Actual";
v.value = joint_pv_controllers_[i]->joint_state_->position_;
values.push_back(v);
- v.label = joint_pv_controllers_[i]->getJointName() + "/Position/Command";
+ v.key = joint_pv_controllers_[i]->getJointName() + "/Position/Command";
joint_pv_controllers_[i]->getCommand(cmd);
v.value = cmd.positions[0];
values.push_back(v);
- v.label = joint_pv_controllers_[i]->getJointName() + "/Position/Error (Command-Actual)";
+ v.key = joint_pv_controllers_[i]->getJointName() + "/Position/Error (Command-Actual)";
v.value = cmd.positions[0] - joint_pv_controllers_[i]->joint_state_->position_;
values.push_back(v);
}
- v.label = "Trajectory id";
+ v.key = "Trajectory id";
v.value = current_trajectory_id_;
values.push_back(v);
- v.label = "Trajectory Status:: ";
+ v.key = "Trajectory Status:: ";
if(current_trajectory_id_ < 0)
{
- v.label += "AT REST";
+ v.key += "AT REST";
v.value = -1;
}
else
{
- v.label += JointTrajectoryStatusString[joint_trajectory_status_[current_trajectory_id_]];
+ v.key += JointTrajectoryStatusString[joint_trajectory_status_[current_trajectory_id_]];
v.value = joint_trajectory_status_[current_trajectory_id_];
}
values.push_back(v);
- v.label = "Trajectory Current Time";
+ v.key = "Trajectory Current Time";
v.value = current_time_-trajectory_start_time_;
values.push_back(v);
- v.label = "Trajectory Expected End Time (computed)";
+ v.key = "Trajectory Expected End Time (computed)";
v.value = trajectory_end_time_-trajectory_start_time_;
values.push_back(v);
- v.label = "Current trajectory queue index";
+ v.key = "Current trajectory queue index";
v.value = current_trajectory_index_;
values.push_back(v);
- v.label = "Number queued trajectories";
+ v.key = "Number queued trajectories";
v.value = num_trajectory_available_;
values.push_back(v);
- v.label = "Next queue free index";
+ v.key = "Next queue free index";
v.value = next_free_index_;
values.push_back(v);
- v.label = "Number joints";
+ v.key = "Number joints";
v.value = num_joints_;
values.push_back(v);
- v.label = "Velocity scaling factor";
+ v.key = "Velocity scaling factor";
v.value = velocity_scaling_factor_;
values.push_back(v);
- v.label = "Trajectory wait timeout";
+ v.key = "Trajectory wait timeout";
v.value = trajectory_wait_timeout_;
values.push_back(v);
- v.label = "Max allowed update time";
+ v.key = "Max allowed update time";
v.value = max_allowed_update_time_;
values.push_back(v);
- v.label = "Diagnostics publish time";
+ v.key = "Diagnostics publish time";
v.value = diagnostics_publish_delta_time_;
values.push_back(v);
- v.label = "Max trajectory queue size";
+ v.key = "Max trajectory queue size";
v.value = max_trajectory_queue_size_;
values.push_back(v);
- v.label = "Listen topic name";
+ v.key = "Listen topic name";
v.value = listen_topic_name_;
values.push_back(v);
- v.label = "Trajectory set service";
+ v.key = "Trajectory set service";
v.value = name_ + "/TrajectoryStart";
values.push_back(v);
- v.label = "Trajectory query service";
+ v.key = "Trajectory query service";
v.value = name_ + "/TrajectoryQuery";
values.push_back(v);
- v.label = "Trajectory cancel service";
+ v.key = "Trajectory cancel service";
v.value = name_ + "/TrajectoryCancel";
values.push_back(v);
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_wrench_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_wrench_controller.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/cartesian_wrench_controller.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -119,10 +119,10 @@
diagnostics_.status[0].name = "Wrench Controller";
diagnostics_.status[0].values.resize(2);
diagnostics_.status[0].values[0].value = "3";
- diagnostics_.status[0].values[0].label = "TestValueLabel";
+ diagnostics_.status[0].values[0].key = "TestValueLabel";
diagnostics_.status[0].values[1].value = "TestValue";
- diagnostics_.status[0].values[1].label = "TestLabel";
+ diagnostics_.status[0].values[1].key = "TestLabel";
diagnostics_time_ = ros::Time::now();
diagnostics_interval_ = ros::Duration().fromSec(1.0);
Modified: pkg/trunk/controllers/robot_mechanism_controllers/src/joint_inverse_dynamics_controller.cpp
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/src/joint_inverse_dynamics_controller.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/controllers/robot_mechanism_controllers/src/joint_inverse_dynamics_controller.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -124,10 +124,10 @@
diagnostics_.status[0].name = "Inverse Dynamics Controller";
diagnostics_.status[0].values.resize(2);
diagnostics_.status[0].values[0].value = "3";
- diagnostics_.status[0].values[0].label = "TestValueLabel";
+ diagnostics_.status[0].values[0].key = "TestValueLabel";
diagnostics_.status[0].values[1].value = "TestValue";
- diagnostics_.status[0].values[1].label = "TestLabel";
+ diagnostics_.status[0].values[1].key = "TestLabel";
diagnostics_time_ = ros::Time::now();
diagnostics_interval_ = ros::Duration().fromSec(1.0);
Modified: pkg/trunk/demos/led_demo/led_status_demo.py
===================================================================
--- pkg/trunk/demos/led_demo/led_status_demo.py 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/demos/led_demo/led_status_demo.py 2009-08-09 01:23:59 UTC (rev 21203)
@@ -50,7 +50,7 @@
## @TODO process byte level
print "Name: %s \nMessage: %s"%(s.name, s.message)
for v in s.strings + s.values:
- print " %s: %s" % (v.label, v.value)
+ print " %s: %s" % (v.key, v.value)
sys.stdout.flush()
def battery_callback(state):
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 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/drivers/cam/axis_cam/src/axis_cam/axis_cam.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -170,9 +170,9 @@
status.level = 0;
status.message = "Retrieved image successfully.";
status.set_values_size(2);
- status.values[0].label = "Width";
+ status.values[0].key = "Width";
status.values[0].value = images.images[0].width;
- status.values[1].label = "Height";
+ status.values[1].key = "Height";
status.values[1].value = images.images[0].height;
}
}
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-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/highlevel/doors/doors_core/src/door_reactive_planner.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -346,75 +346,75 @@
status.name = "Door Reactive Planner";
status.level = 0;
#warning These need a MACRO/function to do num to string
- v.label = "Goal x";
+ v.key = "Goal x";
v.value = goal_.x;
values.push_back(v);
- v.label = "Goal y";
+ v.key = "Goal y";
v.value = goal_.y;
values.push_back(v);
- v.label = "Goal theta";
+ v.key = "Goal theta";
v.value = goal_.th;
values.push_back(v);
- v.label = "Carrot x";
+ v.key = "Carrot x";
v.value = carrot_.x;
values.push_back(v);
- v.label = "Carrot y";
+ v.key = "Carrot y";
v.value = carrot_.y;
values.push_back(v);
- v.label = "Carrot theta";
+ v.key = "Carrot theta";
v.value = carrot_.th;
values.push_back(v);
- v.label = "Centerline angle";
+ v.key = "Centerline angle";
v.value = centerline_angle_;
values.push_back(v);
- v.label = "Travel angle";
+ v.key = "Travel angle";
v.value = travel_angle_;
values.push_back(v);
- v.label = "Sideslip.x";
+ v.key = "Sideslip.x";
v.value = vector_along_door_.x;
values.push_back(v);
- v.label = "Sideslip.y";
+ v.key = "Sideslip.y";
v.value = vector_along_door_.y;
values.push_back(v);
- v.label = "Plan delta angle";
+ v.key = "Plan delta angle";
v.value = delta_angle_;
values.push_back(v);
- v.label = "Plan length";
+ v.key = "Plan length";
v.value = plan_length_;
values.push_back(v);
- v.label = "Centerline distance";
+ v.key = "Centerline distance";
v.value = centerline_distance_;
values.push_back(v);
- v.label = "Current x";
+ v.key = "Current x";
v.value = current_position_.x;
values.push_back(v);
- v.label = "Current y";
+ v.key = "Current y";
v.value = current_position_.y;
values.push_back(v);
- v.label = "Current th";
+ v.key = "Current th";
v.value = current_position_.th;
values.push_back(v);
- v.label = "Cell distance from obstacles";
+ v.key = "Cell distance from obstacles";
v.value = cell_distance_from_obstacles_;
values.push_back(v);
- v.label = "Current position in collision";
+ v.key = "Current position in collision";
v.value = current_position_in_collision_;
values.push_back(v);
Modified: pkg/trunk/pr2/qualification/scripts/run_selftest.py
===================================================================
--- pkg/trunk/pr2/qualification/scripts/run_selftest.py 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/pr2/qualification/scripts/run_selftest.py 2009-08-09 01:23:59 UTC (rev 21203)
@@ -95,9 +95,7 @@
html += "<table border=\"1\" cellpadding=\"2\" cellspacing=\"0\">\n"
html += "<tr><b><td>Label</td><td>Value</td></b></tr>\n"
for val in stat.values:
- html += "<tr><td>%s</td><td>%f</td></tr>\n" % (val.label, val.value)
- for val in stat.strings:
- html += "<tr><td>%s</td><td>%s</td></tr>\n" % (val.label, val.value)
+ html += "<tr><td>%s</td><td>%s</td></tr>\n" % (val.key, val.value)
html += "</table></p>\n"
html += "<hr size=\"2\">\n"
Modified: pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/camera_drivers/dcam/src/nodes/dcam.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -323,11 +323,11 @@
}
status.set_values_size(3);
- status.values[0].label = "Images in interval";
+ status.values[0].key = "Images in interval";
status.values[0].value = count_;
- status.values[1].label = "Desired frequency";
+ status.values[1].key = "Desired frequency";
status.values[1].value = desired_freq_;
- status.values[2].label = "Actual frequency";
+ status.values[2].key = "Actual frequency";
status.values[2].value = freq;
printf("%g fps\n", freq);
Modified: pkg/trunk/stacks/camera_drivers/dcam/src/nodes/stereodcam.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/dcam/src/nodes/stereodcam.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/camera_drivers/dcam/src/nodes/stereodcam.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -429,11 +429,11 @@
}
status.set_values_size(3);
- status.values[0].label = "Images in interval";
+ status.values[0].key = "Images in interval";
status.values[0].value = count_;
- status.values[1].label = "Desired frequency";
+ status.values[1].key = "Desired frequency";
status.values[1].value = desired_freq_;
- status.values[2].label = "Actual frequency";
+ status.values[2].key = "Actual frequency";
status.values[2].value = freq;
printf("%g fps\n", freq);
Modified: pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp
===================================================================
--- pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/camera_drivers/prosilica_cam/src/nodes/prosilica_node.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -314,11 +314,11 @@
}
status.set_values_size(3);
- status.values[0].label = "Images in interval";
+ status.values[0].key = "Images in interval";
status.values[0].value = count_;
- status.values[1].label = "Desired frequency";
+ status.values[1].key = "Desired frequency";
status.values[1].value = desired_freq_;
- status.values[2].label = "Actual frequency";
+ status.values[2].key = "Actual frequency";
status.values[2].value = freq;
count_ = 0;
@@ -362,15 +362,15 @@
}
status.set_values_size(5);
- status.values[0].label = "Camera Frame Rate";
+ status.values[0].key = "Camera Frame Rate";
status.values[0].value = frame_rate;
- status.values[1].label = "Recent % Frames Completed";
+ status.values[1].key = "Recent % Frames Completed";
status.values[1].value = recent_ratio * 100.0f;
- status.values[2].label = "Overall % Frames Completed";
+ status.values[2].key = "Overall % Frames Completed";
status.values[2].value = total_ratio * 100.0f;
- status.values[3].label = "Frames Completed";
+ status.values[3].key = "Frames Completed";
status.values[3].value = completed;
- status.values[4].label = "Frames Dropped";
+ status.values[4].key = "Frames Dropped";
status.values[4].value = dropped;
}
@@ -433,19 +433,19 @@
#endif
status.set_values_size(7);
- status.values[0].label = "Recent % Packets Received";
+ status.values[0].key = "Recent % Packets Received";
status.values[0].value = recent_ratio * 100.0f;
- status.values[1].label = "Overall % Packets Received";
+ status.values[1].key = "Overall % Packets Received";
status.values[1].value = total_ratio * 100.0f;
- status.values[2].label = "Received Packets";
+ status.values[2].key = "Received Packets";
status.values[2].value = received;
- status.values[3].label = "Missed Packets";
+ status.values[3].key = "Missed Packets";
status.values[3].value = missed;
- status.values[4].label = "Requested Packets";
+ status.values[4].key = "Requested Packets";
status.values[4].value = requested;
- status.values[5].label = "Resent Packets";
+ status.values[5].key = "Resent Packets";
status.values[5].value = resent;
- status.values[6].label = "Data Rate (bytes/s)";
+ status.values[6].key = "Data Rate (bytes/s)";
status.values[6].value = data_rate;
}
@@ -465,7 +465,7 @@
}
status.set_values_size(1);
- status.values[0].label = "Erroneous Packets";
+ status.values[0].key = "Erroneous Packets";
status.values[0].value = erroneous;
}
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-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/hardware_test/diagnostic_test/scripts/diagnostic_test.py 2009-08-09 01:23:59 UTC (rev 21203)
@@ -56,10 +56,8 @@
## Also stores last time of message, allows stale checks.
def status_to_map(status):
str_map = {}
- for s in status.strings:
- str_map[s.label] = s.value;
for val in status.values:
- str_map[val.label] = val.value;
+ str_map[val.key] = val.value;
str_map["name"]= status.name
str_map["message"] = status.message
str_map["level"] = status.level
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-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/hardware_test/diagnostic_updater/include/diagnostic_updater/DiagnosticStatusWrapper.h 2009-08-09 01:23:59 UTC (rev 21203)
@@ -127,7 +127,7 @@
void DiagnosticStatusWrapper::adds<std::string>(const std::string &key, const std::string &s)
{
diagnostic_msgs::KeyValue ds;
- ds.label = key;
+ ds.key = key;
ds.value = s;
values.push_back(ds);
}
Modified: pkg/trunk/stacks/hardware_test/diagnostic_updater/test/diagnostic_updater_test.cpp
===================================================================
--- pkg/trunk/stacks/hardware_test/diagnostic_updater/test/diagnostic_updater_test.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/hardware_test/diagnostic_updater/test/diagnostic_updater_test.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -103,9 +103,9 @@
EXPECT_STREQ("5.0", stat.values[0].value.c_str()) << "Bad value, adding a value with addsf";
EXPECT_STREQ("5", stat.values[1].value.c_str()) << "Bad value, adding a string with adds";
EXPECT_STREQ("00027", stat.values[2].value.c_str()) << "Bad value, adding a string with addsf";
- EXPECT_STREQ("toto", stat.values[0].label.c_str()) << "Bad label, adding a value with addv";
- EXPECT_STREQ("baba", stat.values[1].label.c_str()) << "Bad label, adding a string with adds";
- EXPECT_STREQ("foo", stat.values[2].label.c_str()) << "Bad label, adding a string with addsf";
+ EXPECT_STREQ("toto", stat.values[0].key.c_str()) << "Bad label, adding a value with addv";
+ EXPECT_STREQ("baba", stat.values[1].key.c_str()) << "Bad label, adding a string with adds";
+ EXPECT_STREQ("foo", stat.values[2].key.c_str()) << "Bad label, adding a string with addsf";
}
TEST(DiagnosticUpdater, testFrequencyStatus)
Modified: pkg/trunk/stacks/hardware_test/diagnostics_analysis/export_csv.py
===================================================================
--- pkg/trunk/stacks/hardware_test/diagnostics_analysis/export_csv.py 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/hardware_test/diagnostics_analysis/export_csv.py 2009-08-09 01:23:59 UTC (rev 21203)
@@ -63,8 +63,8 @@
if(not stats.has_key(name)):
stats[name] = {}
- stats[name]['string_fields'] = [s.label for s in status.strings]
- stats[name]['float_fields'] = [s.label for s in status.values]
+ stats[name]['string_fields'] = [s.key for s in status.strings]
+ stats[name]['float_fields'] = [s.key for s in status.values]
stats[name]['level'] = status.level
stats[name]['message'] = status.message
@@ -77,14 +77,14 @@
# Need stuff for different string fields
# Store as dictionary, then convert to CSV?
- if (not [s.label for s in status.strings] == stats[name]['string_fields']):
- #print "ERROR, mismatched field names in component %s. Label: %s" %(name, s.label)
- #print [s.label for s in status.strings]
+ if (not [s.key for s in status.strings] == stats[name]['string_fields']):
+ #print "ERROR, mismatched field names in component %s. Label: %s" %(name, s.key)
+ #print [s.key for s in status.strings]
#print str(stats[name]['string_fields'])
#return stats
continue
- if (not [s.label for s in status.values] == stats[name]['float_fields']):
- #print "ERROR, mismatched field names in component %s. Label: %s" %(name, s.label)
+ if (not [s.key for s in status.values] == stats[name]['float_fields']):
+ #print "ERROR, mismatched field names in component %s. Label: %s" %(name, s.key)
#return stats
continue
Modified: pkg/trunk/stacks/hardware_test/self_test/src/run_selftest.cpp
===================================================================
--- pkg/trunk/stacks/hardware_test/self_test/src/run_selftest.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/hardware_test/self_test/src/run_selftest.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -69,7 +69,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].label.c_str(), res.status[i].values[j].value);
+ printf(" [%s] %f\n", res.status[i].values[j].key.c_str(), res.status[i].values[j].value);
printf("\n");
}
Modified: pkg/trunk/stacks/hardware_test/self_test/src/selftest_example.cpp
===================================================================
--- pkg/trunk/stacks/hardware_test/self_test/src/selftest_example.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/hardware_test/self_test/src/selftest_example.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -136,7 +136,7 @@
status.set_values_size(1);
status.values[0].value = some_val;
- status.values[0].label = "some value";
+ status.values[0].key = "some value";
status.level = 0;
status.message = "We successfully changed the value.";
Modified: pkg/trunk/stacks/hardware_test/self_test/src/selftest_rostest.cpp
===================================================================
--- pkg/trunk/stacks/hardware_test/self_test/src/selftest_rostest.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/hardware_test/self_test/src/selftest_rostest.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -82,7 +82,7 @@
EXPECT_EQ(0, res.status[i].level) << res.status[i].name << " did not PASS: " << res.status[i].message;
for (size_t j = 0; j < res.status[i].get_values_size(); j++)
- printf(" [%s] %f\n", res.status[i].values[j].label.c_str(), res.status[i].values[j].value);
+ printf(" [%s] %f\n", res.status[i].values[j].key.c_str(), res.status[i].values[j].value);
printf("\n");
}
Modified: pkg/trunk/stacks/imu_drivers/imu_node/imu_node.cc
===================================================================
--- pkg/trunk/stacks/imu_drivers/imu_node/imu_node.cc 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/imu_drivers/imu_node/imu_node.cc 2009-08-09 01:23:59 UTC (rev 21203)
@@ -405,11 +405,11 @@
status.message = "Successfully calculated gyro biases.";
status.set_values_size(3);
- status.values[0].label = "Bias_X";
+ status.values[0].key = "Bias_X";
status.values[0].value = bias_x_;
- status.values[1].label = "Bias_Y";
+ status.values[1].key = "Bias_Y";
status.values[1].value = bias_y_;
- status.values[2].label = "Bias_Z";
+ status.values[2].key = "Bias_Z";
status.values[2].value = bias_z_;
}
@@ -494,9 +494,9 @@
}
status.set_values_size(2);
- status.values[0].label = "Measured gravity";
+ status.values[0].key = "Measured gravity";
status.values[0].value = grav;
- status.values[1].label = "Gravity error";
+ status.values[1].key = "Gravity error";
status.values[1].value = err;
}
}
Modified: pkg/trunk/stacks/laser_drivers/hokuyo_node/src/node/hokuyo_node.cpp
===================================================================
--- pkg/trunk/stacks/laser_drivers/hokuyo_node/src/node/hokuyo_node.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/laser_drivers/hokuyo_node/src/node/hokuyo_node.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -417,11 +417,11 @@
}
status.set_values_size(3);
- status.values[0].label = "Port";
+ status.values[0].key = "Port";
status.values[0].value = port_;
- status.values[1].label = "Device ID";
+ status.values[1].key = "Device ID";
status.values[1].value = device_id_;
- status.values[2].label = "Device Status";
+ status.values[2].key = "Device Status";
status.values[2].value = device_status_;
}
@@ -444,11 +444,11 @@
}
status.set_values_size(3);
- status.values[0].label = "Scans in interval";
+ status.values[0].key = "Scans in interval";
status.values[0].value = count_;
- status.values[1].label = "Desired frequency";
+ status.values[1].key = "Desired frequency";
status.values[1].value = desired_freq;
- status.values[2].label = "Actual frequency";
+ status.values[2].key = "Actual frequency";
status.values[2].value = freq;
count_ = 0;
Modified: pkg/trunk/stacks/mechanism/mechanism_control/src/mechanism_control.cpp
===================================================================
--- pkg/trunk/stacks/mechanism/mechanism_control/src/mechanism_control.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/mechanism/mechanism_control/src/mechanism_control.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -110,7 +110,7 @@
#define ADD_STRING_FMT(lab, fmt, ...) \
- v.label = (lab); \
+ v.key = (lab); \
{ char buf[1024]; \
snprintf(buf, sizeof(buf), fmt, ##__VA_ARGS__); \
v.value = buf; \
Modified: pkg/trunk/stacks/pr2/pr2_etherCAT/src/main.cpp
===================================================================
--- pkg/trunk/stacks/pr2/pr2_etherCAT/src/main.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/pr2/pr2_etherCAT/src/main.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -121,13 +121,13 @@
if (first)
{
first = false;
- v.label = "Robot Description";
+ v.key = "Robot Description";
v.value = g_robot_desc;
values.push_back(v);
}
#define ADD_STRING_FMT(lab, fmt, ...) \
- v.label = (lab); \
+ v.key = (lab); \
{ char buf[1024]; \
snprintf(buf, sizeof(buf), fmt, ##__VA_ARGS__); \
v.value = buf; \
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-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/ek1122.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -70,7 +70,7 @@
d.hardware_id = serial;
d.level = 0;
- v.label = "Product code";
+ v.key = "Product code";
str.str("");
str << "EK1122 (" << sh_->get_product_code() << ")";
v.value = str.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-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/ethercat_hardware.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -193,14 +193,14 @@
}
#define ADD_STRING_FMT(lab, fmt, ...) \
- v.label = (lab); \
+ v.key = (lab); \
{ char buf[1024]; \
snprintf(buf, sizeof(buf), fmt, ##__VA_ARGS__); \
v.value = buf; \
} \
values_.push_back(v)
#define ADD_STRING(lab, val) \
- v.label = (lab); \
+ v.key = (lab); \
v.value = (val); \
values_.push_back(v)
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-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/wg014.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -57,7 +57,7 @@
return 0;
}
#define ADD_STRING_FMT(lab, fmt, ...) \
- v.label = (lab); \
+ v.key = (lab); \
{ char buf[1024]; \
snprintf(buf, sizeof(buf), fmt, ##__VA_ARGS__); \
v.value = buf; \
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-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/pr2_ethercat_drivers/ethercat_hardware/src/wg0x.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -866,14 +866,14 @@
}
#define ADD_STRING_FMT(lab, fmt, ...) \
- v.label = (lab); \
+ v.key = (lab); \
{ char buf[1024]; \
snprintf(buf, sizeof(buf), fmt, ##__VA_ARGS__); \
v.value = buf; \
} \
values_.push_back(v)
#define ADD_STRING(lab, val) \
- v.label = (lab); \
+ v.key = (lab); \
v.value = (val); \
values_.push_back(v)
void WG0X::diagnostics(diagnostic_msgs::DiagnosticStatus &d, unsigned char *buffer)
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-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/pr2_power_drivers/pr2_power_board/src/power_node/power_node.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -682,14 +682,14 @@
ss.str("");
ss << pmesg->header.serial_num;
val.value = ss.str();
- val.label = "Serial Number";
+ val.key = "Serial Number";
stat.values.push_back(val);
ROS_DEBUG(" Current = %f", status->input_current);
ss.str("");
ss << status->input_current;
val.value = ss.str();
- val.label = "Input Current";
+ val.key = "Input Current";
stat.values.push_back(val);
ROS_DEBUG(" Voltages:");
@@ -697,69 +697,69 @@
ss.str("");
ss << status->input_voltage;
val.value = ss.str();
- val.label = "Input Voltage";
+ val.key = "Input Voltage";
stat.values.push_back(val);
ROS_DEBUG(" DCDC 12 = %f", status->DCDC_12V_out_voltage);
ss.str("");
ss << status->DCDC_12V_out_voltage;
val.value = ss.str();
- val.label = "DCDC12";
+ val.key = "DCDC12";
stat.values.push_back(val);
ROS_DEBUG(" DCDC 15 = %f", status->DCDC_19V_out_voltage);
ss.str("");
ss << status->DCDC_19V_out_voltage;
val.value = ss.str();
- val.label = "DCDC 15";
+ val.key = "DCDC 15";
stat.values.push_back(val);
ROS_DEBUG(" CB0 (Base) = %f", status->CB0_voltage);
ss.str("");
ss << status->CB0_voltage;
val.value = ss.str();
- val.label = "Breaker 0 Voltage";
+ val.key = "Breaker 0 Voltage";
stat.values.push_back(val);
ROS_DEBUG(" CB1 (R-arm) = %f", status->CB1_voltage);
ss.str("");
ss << status->CB1_voltage;
val.value = ss.str();
- val.label = "Breaker 1 Voltage";
+ val.key = "Breaker 1 Voltage";
stat.values.push_back(val);
ROS_DEBUG(" CB2 (L-arm) = %f", status->CB2_voltage);
ss.str("");
ss << status->CB2_voltage;
val.value = ss.str();
- val.label = "Breaker 2 Voltage";
+ val.key = "Breaker 2 Voltage";
stat.values.push_back(val);
ROS_DEBUG(" Board Temp = %f", status->ambient_temp);
ss.str("");
ss << status->ambient_temp;
val.value = ss.str();
- val.label = "Board Temperature";
+ val.key = "Board Temperature";
stat.values.push_back(val);
ROS_DEBUG(" Fan Speeds:");
ROS_DEBUG(" Fan 0 = %u", status->fan0_speed);
ss.str("");
ss << status->fan0_speed;
val.value = ss.str();
- val.label = "Fan 0 Speed";
+ val.key = "Fan 0 Speed";
stat.values.push_back(val);
ROS_DEBUG(" Fan 1 = %u", status->fan1_speed);
ss.str("");
ss << status->fan1_speed;
val.value = ss.str();
- val.label = "Fan 1 Speed";
+ val.key = "Fan 1 Speed";
stat.values.push_back(val);
ROS_DEBUG(" Fan 2 = %u", status->fan2_speed);
ss.str("");
ss << status->fan2_speed;
val.value = ss.str();
- val.label = "Fan 2 Speed";
+ val.key = "Fan 2 Speed";
stat.values.push_back(val);
ROS_DEBUG(" Fan 3 = %u", status->fan3_speed);
ss.str("");
ss << status->fan3_speed;
val.value = ss.str();
- val.label = "Fan 3 Speed";
+ val.key = "Fan 3 Speed";
stat.values.push_back(val);
ROS_DEBUG(" State:");
@@ -767,47 +767,47 @@
ss.str("");
ss << cb_state_to_str(status->CB0_state);
val.value = ss.str();
- val.label = "Breaker 0 State";
+ val.key = "Breaker 0 State";
stat.values.push_back(val);
ROS_DEBUG(" CB1 (R-arm) = %s", cb_state_to_str(status->CB1_state));
ss.str("");
ss << cb_state_to_str(status->CB1_state);
val.value = ss.str();
- val.label = "Breaker 1 State";
+ val.key = "Breaker 1 State";
stat.values.push_back(val);
ROS_DEBUG(" CB2 (L-arm) = %s", cb_state_to_str(status->CB2_state));
val.value = cb_state_to_str(status->CB2_state);
- val.label = "Breaker 2 State";
+ val.key = "Breaker 2 State";
stat.values.push_back(val);
ROS_DEBUG(" DCDC = %s", master_state_to_str(status->DCDC_state));
val.value = master_state_to_str(status->DCDC_state);
- val.label = "DCDC state";
+ val.key = "DCDC state";
stat.values.push_back(val);
ROS_DEBUG(" Status:");
ROS_DEBUG(" CB0 (Base) = %s", (status->CB0_status) ? "On" : "Off");
val.value = (status->CB0_status) ? "On" : "Off";
- val.label = "Breaker 0 Status";
+ val.key = "Breaker 0 Status";
stat.values.push_back(val);
ROS_DEBUG(" CB1 (R-arm) = %s", (status->CB1_status) ? "On" : "Off");
val.value = (status->CB1_status) ? "On" : "Off";
- val.label = "Breaker 1 Status";
+ val.key = "Breaker 1 Status";
stat.values.push_back(val);
ROS_DEBUG(" CB2 (L-arm) = %s", (status->CB2_status) ? "On" : "Off");
val.value = (status->CB2_status) ? "On" : "Off";
- val.label = "Breaker 2 Status";
+ val.key = "Breaker 2 Status";
stat.values.push_back(val);
ROS_DEBUG(" estop_button= %x", (status->estop_button_status));
ss.str("");
ss << status->estop_button_status;
val.value = ss.str();
- val.label = "RunStop Button Status";
+ val.key = "RunStop Button Status";
stat.values.push_back(val);
ROS_DEBUG(" estop_status= %x", (status->estop_status));
ss.str("");
ss << status->estop_status;
val.value = ss.str();
- val.label = "RunStop Status";
+ val.key = "RunStop Status";
stat.values.push_back(val);
ROS_DEBUG(" Revisions:");
@@ -815,36 +815,36 @@
ss.str("");
ss << status->pca_rev;
val.value = ss.str();
- val.label = "PCA";
+ val.key = "PCA";
stat.values.push_back(val);
ROS_DEBUG(" PCB = %c", status->pcb_rev);
ss.str("");
ss << status->pcb_rev;
val.value = ss.str();
- val.label = "PCB";
+ val.key = "PCB";
stat.values.push_back(val);
ROS_DEBUG(" Major = %c", status->major_rev);
ss.str("");
ss << status->major_rev;
val.value = ss.str();
- val.label = "Major Revision";
+ val.key = "Major Revision";
stat.values.push_back(val);
ROS_DEBUG(" Minor = %c", status->minor_rev);
ss.str("");
ss << status->minor_rev;
val.value = ss.str();
- val.label = "Minor Revision";
+ val.key = "Minor Revision";
stat.values.push_back(val);
ss.str("");
ss << status->min_input_voltage;
val.value = ss.str();
- val.label = "Min Voltage";
+ val.key = "Min Voltage";
stat.values.push_back(val);
ss.str("");
ss << status->max_input_current;
val.value = ss.str();
- val.label = "Max Current";
+ val.key = "Max Current";
stat.values.push_back(val);
@@ -858,56 +858,56 @@
val.value = ss.str();
ss.str("");
ss << "CB" << cb_index << " Stop Count";
- val.label = ss.str();
+ val.key = ss.str();
stat.values.push_back(val);
ss.str("");
ss << trans->estop_count;
val.value = ss.str();
ss.str("");
ss << "CB" << cb_index << " E-Stop Count";
- val.label = ss.str();
+ val.key = ss.str();
stat.values.push_back(val);
ss.str("");
ss << trans->trip_count;
val.value = ss.str();
ss.str("");
ss << "CB" << cb_index << " Trip Count";
- val.label = ss.str();
+ val.key = ss.str();
stat.values.push_back(val);
ss.str("");
ss << trans->fail_18V_count;
val.value = ss.str();
ss.str("");
ss << "CB" << cb_index << " 18V Fail Count";
- val.label = ss.str();
+ val.key = ss.str();
stat.values.push_back(val);
ss.str("");
ss << trans->disable_count;
val.value = ss.str();
ss.str("");
ss << "CB" << cb_index << " Disable Count";
- val.label = ss.str();
+ val.key = ss.str();
stat.values.push_back(val);
ss.str("");
ss << trans->start_count;
val.value = ss.str();
ss.str("");
ss << "CB" << cb_index << " Start Count";
- val.label = ss.str();
+ val.key = ss.str();
stat.values.push_back(val);
ss.str("");
ss << trans->pump_fail_count;
val.value = ss.str();
ss.str("");
ss << "CB" << cb_index << " Pump Fail Count";
- val.label = ss.str();
+ val.key = ss.str();
stat.values.push_back(val);
ss.str("");
ss << trans->reset_count;
val.value = ss.str();
ss.str("");
ss << "CB" << cb_index << " Reset Count";
- val.label = ss.str();
+ val.key = ss.str();
stat.values.push_back(val);
}
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-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/pr2_power_drivers/pr2_power_board/src/power_node/power_node_simulator.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -364,107 +364,107 @@
ROS_DEBUG("Device %u", i);
ROS_DEBUG(" Serial = %u", pmesg->header.serial_num);
- //val.label = "Time";
+ //val.key = "Time";
//val.value = (float)Devices[i]->message_time;
//stat.values.push_back(val);
ss.str("");
ss << pmesg->header.serial_num;
strval.value = ss.str();
- strval.label = "Serial Number";
+ strval.key = "Serial Number";
stat.strings.push_back(strval);
ROS_DEBUG(" Current = %f", status->input_current);
val.value = status->input_current;
- val.label = "Input Current";
+ val.key = "Input Current";
stat.values.push_back(val);
ROS_DEBUG(" Voltages:");
ROS_DEBUG(" Input = %f", status->input_voltage);
val.value = status->input_voltage;
- val.label = "Input Voltage";
+ val.key = "Input Voltage";
stat.values.push_back(val);
ROS_DEBUG(" DCDC 12 = %f", status->DCDC_12V_out_voltage);
val.value = status->DCDC_12V_out_voltage;
- val.label = "DCDC12";
+ val.key = "DCDC12";
stat.values.push_back(val);
ROS_DEBUG(" DCDC 15 = %f", status->DCDC_19V_out_voltage);
val.value = status->DCDC_19V_out_voltage;
- val.label = "DCDC 15";
+ val.key = "DCDC 15";
stat.values.push_back(val);
ROS_DEBUG(" CB0 (Base) = %f", status->CB0_voltage);
val.value = status->CB0_voltage;
- val.label = "Breaker 0 Voltage";
+ val.key = "Breaker 0 Voltage";
stat.values.push_back(val);
ROS_DEBUG(" CB1 (R-arm) = %f", status->CB1_voltage);
val.value = status->CB1_voltage;
- val.label = "Breaker 1 Voltage";
+ val.key = "Breaker 1 Voltage";
stat.values.push_back(val);
ROS_DEBUG(" CB2 (L-arm) = %f", status->CB2_voltage);
val.value = status->CB2_voltage;
- val.label = "Breaker 2 Voltage";
+ val.key = "Breaker 2 Voltage";
stat.values.push_back(val);
ROS_DEBUG(" Board Temp = %f", status->ambient_temp);
val.value = status->ambient_temp;
- val.label = "Board Temperature";
+ val.key = "Board Temperature";
stat.values.push_back(val);
ROS_DEBUG(" Fan Speeds:");
ROS_DEBUG(" Fan 0 = %u", status->fan0_speed);
val.value = status->fan0_speed;
- val.label = "Fan 0 Speed";
+ val.key = "Fan 0 Speed";
stat.values.push_back(val);
ROS_DEBUG(" Fan 1 = %u", status->fan1_speed);
val.value = status->fan1_speed;
- val.label = "Fan 1 Speed";
+ val.key = "Fan 1 Speed";
stat.values.push_back(val);
ROS_DEBUG(" Fan 2 = %u", status->fan2_speed);
val.value = status->fan2_speed;
- val.label = "Fan 2 Speed";
+ val.key = "Fan 2 Speed";
stat.values.push_back(val);
ROS_DEBUG(" Fan 3 = %u", status->fan3_speed);
val.value = status->fan3_speed;
- val.label = "Fan 3 Speed";
+ val.key = "Fan 3 Speed";
stat.values.push_back(val);
ROS_DEBUG(" State:");
ROS_DEBUG(" CB0 (Base) = %s", cb_state_to_str(status->CB0_state));
strval.value = cb_state_to_str(status->CB0_state);
- strval.label = "Breaker 0 State";
+ strval.key = "Breaker 0 State";
stat.strings.push_back(strval);
ROS_DEBUG(" CB1 (R-arm) = %s", cb_state_to_str(status->CB1_state));
strval.value = cb_state_to_str(status->CB1_state);
- strval.label = "Breaker 1 State";
+ strval.key = "Breaker 1 State";
stat.strings.push_back(strval);
ROS_DEBUG(" CB2 (L-arm) = %s", cb_state_to_str(status->CB2_state));
strval.value = cb_state_to_str(status->CB2_state);
- strval.label = "Breaker 2 State";
+ strval.key = "Breaker 2 State";
stat.strings.push_back(strval);
ROS_DEBUG(" DCDC = %s", master_state_to_str(status->DCDC_state));
strval.value = master_state_to_str(status->DCDC_state);
- strval.label = "DCDC state";
+ strval.key = "DCDC state";
stat.strings.push_back(strval);
ROS_DEBUG(" Status:");
ROS_DEBUG(" CB0 (Base) = %s", (status->CB0_status) ? "On" : "Off");
strval.value = (status->CB0_status) ? "On" : "Off";
- strval.label = "Breaker 0 Status";
+ strval.key = "Breaker 0 Status";
stat.strings.push_back(strval);
ROS_DEBUG(" CB1 (R-arm) = %s", (status->CB1_status) ? "On" : "Off");
strval.value = (status->CB1_status) ? "On" : "Off";
- strval.label = "Breaker 1 Status";
+ strval.key = "Breaker 1 Status";
stat.strings.push_back(strval);
ROS_DEBUG(" CB2 (L-arm) = %s", (status->CB2_status) ? "On" : "Off");
strval.value = (status->CB2_status) ? "On" : "Off";
- strval.label = "Breaker 2 Status";
+ strval.key = "Breaker 2 Status";
stat.strings.push_back(strval);
ROS_DEBUG(" estop_button= %x", (status->estop_button_status));
val.value = status->estop_button_status;
- val.label = "RunStop Button Status";
+ val.key = "RunStop Button Status";
stat.values.push_back(val);
ROS_DEBUG(" estop_status= %x", (status->estop_status));
val.value = status->estop_status;
- val.label = "RunStop Status";
+ val.key = "RunStop Status";
stat.values.push_back(val);
ROS_DEBUG(" Revisions:");
@@ -472,32 +472,32 @@
ss.str("");
ss << status->pca_rev;
strval.value = ss.str();
- strval.label = "PCA";
+ strval.key = "PCA";
stat.strings.push_back(strval);
ROS_DEBUG(" PCB = %c", status->pcb_rev);
ss.str("");
ss << status->pcb_rev;
strval.value = ss.str();
- strval.label = "PCB";
+ strval.key = "PCB";
stat.strings.push_back(strval);
ROS_DEBUG(" Major = %c", status->major_rev);
ss.str("");
ss << status->major_rev;
strval.value = ss.str();
- strval.label = "Major Revision";
+ strval.key = "Major Revision";
stat.strings.push_back(strval);
ROS_DEBUG(" Minor = %c", status->minor_rev);
ss.str("");
ss << status->minor_rev;
strval.value = ss.str();
- strval.label = "Minor Revision";
+ strval.key = "Minor Revision";
stat.strings.push_back(strval);
val.value = status->min_input_voltage;
- val.label = "Min Voltage";
+ val.key = "Min Voltage";
stat.values.push_back(val);
val.value = status->max_input_current;
- val.label = "Max Current";
+ val.key = "Max Current";
stat.values.push_back(val);
@@ -509,42 +509,42 @@
val.value = trans->stop_count;
ss.str("");
ss << "CB" << cb_index << " Stop Count";
- val.label = ss.str();
+ val.key = ss.str();
stat.values.push_back(val);
val.value = trans->estop_count;
ss.str("");
ss << "CB" << cb_index << " E-Stop Count";
- val.label = ss.str();
+ val.key = ss.str();
stat.values.push_back(val);
val.value = trans->trip_count;
ss.str("");
ss << "CB" << cb_index << " Trip Count";
- val.label = ss.str();
+ val.key = ss.str();
stat.values.push_back(val);
val.value = trans->fail_18V_count;
ss.str("");
ss << "CB" << cb_index << " 18V Fail Count";
- val.label = ss.str();
+ val.key = ss.str();
stat.values.push_back(val);
val.value = trans->disable_count;
ss.str("");
ss << "CB" << cb_index << " Disable Count";
- val.label = ss.str();
+ val.key = ss.str();
stat.values.push_back(val);
val.value = trans->start_count;
ss.str("");
ss << "CB" << cb_index << " Start Count";
- val.label = ss.str();
+ val.key = ss.str();
stat.values.push_back(val);
val.value = trans->pump_fail_count;
ss.str("");
ss << "CB" << cb_index << " Pump Fail Count";
- val.label = ss.str();
+ val.key = ss.str();
stat.values.push_back(val);
val.value = trans->reset_count;
ss.str("");
ss << "CB" << cb_index << " Reset Count";
- val.label = ss.str();
+ val.key = ss.str();
stat.values.push_back(val);
}
Modified: pkg/trunk/stacks/pr2_power_drivers/pr2_power_board/src/pr2_power_board/pr2_power_board_panel.py
===================================================================
--- pkg/trunk/stacks/pr2_power_drivers/pr2_power_board/src/pr2_power_board/pr2_power_board_panel.py 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/pr2_power_drivers/pr2_power_board/src/pr2_power_board/pr2_power_board_panel.py 2009-08-09 01:23:59 UTC (rev 21203)
@@ -135,7 +135,7 @@
name = status.name
serial = int(0)
for strvals in status.values:
- if (strvals.label == "Serial Number"):
+ if (strvals.key == "Serial Number"):
serial = int(strvals.value)
print "Adding: %s serial=%d" %(name,serial)
self.myList.Append(str(name));
@@ -172,18 +172,18 @@
self._real_panel.Enable(False)
for value in status.values:
- if (value.label == "Breaker 0 Voltage"):
+ if (value.key == "Breaker 0 Voltage"):
self.voltages[0] = value.value
- if (value.label == "Breaker 1 Voltage"):
+ if (value.key == "Breaker 1 Voltage"):
self.voltages[1] = value.value
- if (value.label == "Breaker 2 Voltage"):
+ if (value.key == "Breaker 2 Voltage"):
self.voltages[2] = value.value
- if (value.label == "RunStop Button Status"):
+ if (value.key == "RunStop Button Status"):
if value.value > 0.5:
self.estop_wireless_status = "Run"
else:
self.estop_wireless_status = "Stop"
- if (value.label == "RunStop Status"):
+ if (value.key == "RunStop Status"):
if value.value > 0.5:
self.estop_button_status = "Run"
else:
@@ -193,11 +193,11 @@
self.estop_button_status = "Stop"
for strvals in status.values:
- if (strvals.label == "Breaker 0 State"):
+ if (strvals.key == "Breaker 0 State"):
self.breaker_state[0] = strvals.value
- if (strvals.label == "Breaker 1 State"):
+ if (strvals.key == "Breaker 1 State"):
self.breaker_state[1] = strvals.value
- if (strvals.label == "Breaker 2 State"):
+ if (strvals.key == "Breaker 2 State"):
self.breaker_state[2] = strvals.value
Modified: pkg/trunk/stacks/stereo/stereo_image_proc/src/stereoproc.cpp
===================================================================
--- pkg/trunk/stacks/stereo/stereo_image_proc/src/stereoproc.cpp 2009-08-09 01:20:18 UTC (rev 21202)
+++ pkg/trunk/stacks/stereo/stereo_image_proc/src/stereoproc.cpp 2009-08-09 01:23:59 UTC (rev 21203)
@@ -409,11 +409,11 @@
}
status.set_values_size(3);
- status.values[0].label = "Images in interval";
+ status.values[0].key = "Images in interval";
status.values[0].value = count_;
- status.values[1].label = "Desired frequency";
+ status.values[1].key = "Desired frequency";
status.values[1].value = desired_freq_;
- status.values[2].label = "Actual frequency";
+ status.values[2].key = "Actual frequency";
status.values[2].value = freq;
printf("%g fps\n", freq);
This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site.
|