|
From: <tf...@us...> - 2009-06-05 23:40:13
|
Revision: 16796
http://personalrobots.svn.sourceforge.net/personalrobots/?rev=16796&view=rev
Author: tfoote
Date: 2009-06-05 23:40:09 +0000 (Fri, 05 Jun 2009)
Log Message:
-----------
robot_msgs/Diagnostic* to diagnostic_msgs/Diagnostic* and robot_srvs/SelfTest into diagnostic_msgs too
Modified Paths:
--------------
pkg/trunk/calibration/joint_calibration_monitor/scripts/pr2_calibration_monitor_node.py
pkg/trunk/common/diagnostic_msgs/CMakeLists.txt
pkg/trunk/common/diagnostic_msgs/manifest.xml
pkg/trunk/common/robot_actions/include/robot_actions/action.h
pkg/trunk/common/robot_actions/manifest.xml
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_trajectory_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/joint_trajectory_controller.h
pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/whole_body_trajectory_controller.h
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/pr2_mechanism_controllers/src/whole_body_trajectory_controller.cpp
pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/backlash_controller.h
pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/hold_set_controller.h
pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/hysteresis_controller.h
pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_wrench_controller.h
pkg/trunk/drivers/cam/axis_cam/src/axis_cam/axis_cam.cpp
pkg/trunk/drivers/cam/dcam/src/nodes/dcam.cpp
pkg/trunk/drivers/cam/dcam/src/nodes/stereodcam.cpp
pkg/trunk/drivers/cam/prosilica_cam/manifest.xml
pkg/trunk/drivers/cam/prosilica_cam/src/nodes/prosilica_node.cpp
pkg/trunk/drivers/imu/imu_node/imu_node.cc
pkg/trunk/drivers/laser/hokuyo_node/src/node/hokuyo_node.cpp
pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/ek1122.h
pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/ethercat_device.h
pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/ethercat_hardware.h
pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/wg014.h
pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/wg0x.h
pkg/trunk/drivers/motor/ethercat_hardware/manifest.xml
pkg/trunk/drivers/motor/ethercat_hardware/src/ek1122.cpp
pkg/trunk/drivers/motor/ethercat_hardware/src/ethercat_hardware.cpp
pkg/trunk/drivers/motor/ethercat_hardware/src/wg014.cpp
pkg/trunk/drivers/motor/ethercat_hardware/src/wg0x.cpp
pkg/trunk/drivers/robot/pr2/ocean_battery_driver/manifest.xml
pkg/trunk/drivers/robot/pr2/ocean_battery_driver/scripts/monitor
pkg/trunk/drivers/robot/pr2/pr2_power_board/manifest.xml
pkg/trunk/drivers/robot/pr2/pr2_power_board/scripts/view_power
pkg/trunk/drivers/robot/pr2/pr2_power_board/src/power_node/power_node.cpp
pkg/trunk/drivers/robot/pr2/pr2_power_board/src/power_node/power_node_simulator.cpp
pkg/trunk/drivers/robot/pr2/pr2_power_board/src/pr2_power_board/power_wires.py
pkg/trunk/drivers/robot/pr2/pr2_power_board/src/pr2_power_board/pr2_power_board_panel.py
pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/gazebo_battery.h
pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml
pkg/trunk/drivers/simulator/gazebo_plugin/src/gazebo_battery.cpp
pkg/trunk/hardware_test/diagnostic_updater/include/diagnostic_updater/DiagnosticStatusWrapper.h
pkg/trunk/hardware_test/diagnostic_updater/include/diagnostic_updater/diagnostic_updater.h
pkg/trunk/hardware_test/diagnostic_updater/manifest.xml
pkg/trunk/hardware_test/diagnostic_updater/test/diagnostic_updater_test.cpp
pkg/trunk/hardware_test/runtime_monitor/manifest.xml
pkg/trunk/hardware_test/runtime_monitor/scripts/log_runtime_messages
pkg/trunk/hardware_test/runtime_monitor/scripts/monitor
pkg/trunk/hardware_test/runtime_monitor/scripts/ntp_monitor.py
pkg/trunk/hardware_test/runtime_monitor/scripts/runtime_test
pkg/trunk/hardware_test/runtime_monitor/scripts/test_high_level
pkg/trunk/hardware_test/runtime_monitor/src/runtime_monitor/monitor_panel.py
pkg/trunk/hardware_test/runtime_monitor/testmonitor.py
pkg/trunk/hardware_test/self_test/CMakeLists.txt
pkg/trunk/hardware_test/self_test/include/self_test/self_test.h
pkg/trunk/hardware_test/self_test/manifest.xml
pkg/trunk/hardware_test/self_test/src/run_selftest.cpp
pkg/trunk/hardware_test/self_test/src/selftest_example.cpp
pkg/trunk/hardware_test/self_test/src/selftest_rostest.cpp
pkg/trunk/highlevel/doors/doors_core/include/doors_core/door_reactive_planner.h
pkg/trunk/highlevel/doors/doors_core/include/doors_core/move_base_door_action.h
pkg/trunk/highlevel/doors/doors_core/manifest.xml
pkg/trunk/highlevel/doors/doors_core/src/door_reactive_planner.cpp
pkg/trunk/highlevel/doors/doors_core/src/move_base_door_action.cpp
pkg/trunk/mechanism/mechanism_control/include/mechanism_control/mechanism_control.h
pkg/trunk/mechanism/mechanism_control/manifest.xml
pkg/trunk/mechanism/mechanism_control/src/mechanism_control.cpp
pkg/trunk/pr2/life_test/manifest.xml
pkg/trunk/pr2/life_test/simple_test/fake_test.py
pkg/trunk/pr2/life_test/src/life_test/life_test.py
pkg/trunk/pr2/pr2_etherCAT/manifest.xml
pkg/trunk/pr2/pr2_etherCAT/src/main.cpp
pkg/trunk/pr2/qualification/manifest.xml
pkg/trunk/pr2/qualification/scripts/robot_checkout.py
pkg/trunk/robot_descriptions/pr2/pr2_configurations/pr2_prototype1/motor_monitor.py
pkg/trunk/vision/stereo_image_proc/manifest.xml
pkg/trunk/vision/stereo_image_proc/src/stereoproc.cpp
Added Paths:
-----------
pkg/trunk/common/diagnostic_msgs/srv/
pkg/trunk/common/diagnostic_msgs/srv/SelfTest.srv
Removed Paths:
-------------
pkg/trunk/common/robot_msgs/msg/DiagnosticMessage.msg
pkg/trunk/common/robot_msgs/msg/DiagnosticStatus.msg
pkg/trunk/common/robot_msgs/msg/DiagnosticString.msg
pkg/trunk/common/robot_msgs/msg/DiagnosticValue.msg
Modified: pkg/trunk/calibration/joint_calibration_monitor/scripts/pr2_calibration_monitor_node.py
===================================================================
--- pkg/trunk/calibration/joint_calibration_monitor/scripts/pr2_calibration_monitor_node.py 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/calibration/joint_calibration_monitor/scripts/pr2_calibration_monitor_node.py 2009-06-05 23:40:09 UTC (rev 16796)
@@ -41,7 +41,7 @@
import threading
import math
-from robot_msgs.msg import *
+from diagnostic_msgs.msg import DiagnosticMessage
from roslib import rostime
from joint_calibration_monitor.generic_joint_monitor import *
Modified: pkg/trunk/common/diagnostic_msgs/CMakeLists.txt
===================================================================
--- pkg/trunk/common/diagnostic_msgs/CMakeLists.txt 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/common/diagnostic_msgs/CMakeLists.txt 2009-06-05 23:40:09 UTC (rev 16796)
@@ -19,7 +19,7 @@
#uncomment if you have defined messages
genmsg()
#uncomment if you have defined services
-#gensrv()
+gensrv()
#common commands for building c++ executables and libraries
#rospack_add_library(${PROJECT_NAME} src/example.cpp)
Modified: pkg/trunk/common/diagnostic_msgs/manifest.xml
===================================================================
--- pkg/trunk/common/diagnostic_msgs/manifest.xml 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/common/diagnostic_msgs/manifest.xml 2009-06-05 23:40:09 UTC (rev 16796)
@@ -9,7 +9,7 @@
<review status="api cleared" notes=""/>
<url>http://pr.willowgarage.com/wiki/diagnostic_msgs</url>
<export>
- <cpp cflags="-I${prefix}/msg/cpp"/>
+ <cpp cflags="-I${prefix}/msg/cpp -I${prefix}/srv/cpp"/>
</export>
</package>
Copied: pkg/trunk/common/diagnostic_msgs/srv/SelfTest.srv (from rev 14615, pkg/trunk/common/robot_srvs/srv/SelfTest.srv)
===================================================================
--- pkg/trunk/common/diagnostic_msgs/srv/SelfTest.srv (rev 0)
+++ pkg/trunk/common/diagnostic_msgs/srv/SelfTest.srv 2009-06-05 23:40:09 UTC (rev 16796)
@@ -0,0 +1,4 @@
+---
+string id
+byte passed
+DiagnosticStatus[] status
Modified: pkg/trunk/common/robot_actions/include/robot_actions/action.h
===================================================================
--- pkg/trunk/common/robot_actions/include/robot_actions/action.h 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/common/robot_actions/include/robot_actions/action.h 2009-06-05 23:40:09 UTC (rev 16796)
@@ -50,7 +50,7 @@
#include <boost/bind.hpp>
#include <boost/thread.hpp>
#include <ros/node.h>
-#include <robot_msgs/DiagnosticMessage.h>
+#include <diagnostic_msgs/DiagnosticMessage.h>
namespace robot_actions {
@@ -185,7 +185,7 @@
Action(const std::string& name)
: _name(name), _preempt_request(false), _result_status(SUCCESS), _terminated(false), _action_thread(NULL), _callback(NULL),_diagnostics_statuses(1){
_status.value = ActionStatus::UNDEFINED;
- ros::Node::instance()->advertise<robot_msgs::DiagnosticMessage> ("/diagnostics", 1) ;
+ ros::Node::instance()->advertise<diagnostic_msgs::DiagnosticMessage> ("/diagnostics", 1) ;
}
virtual ~Action(){
@@ -263,7 +263,7 @@
}
void publishDiagnostics(){
- robot_msgs::DiagnosticStatus diagnostics_status;
+ diagnostic_msgs::DiagnosticStatus diagnostics_status;
if (_status.value == ActionStatus::ACTIVE){
if (isPreemptRequested())
diagnostics_status.message = "Active and requested preempt";
@@ -300,8 +300,8 @@
bool _terminated;
boost::thread* _action_thread; /*!< Thread running the action */
boost::function< void(const ActionStatus&, const Goal&, const Feedback&) > _callback; /*!< Callback function for sending updates */
- robot_msgs::DiagnosticMessage _diagnostics_message;
- std::vector<robot_msgs::DiagnosticStatus> _diagnostics_statuses;
+ diagnostic_msgs::DiagnosticMessage _diagnostics_message;
+ std::vector<diagnostic_msgs::DiagnosticStatus> _diagnostics_statuses;
};
}
#endif
Modified: pkg/trunk/common/robot_actions/manifest.xml
===================================================================
--- pkg/trunk/common/robot_actions/manifest.xml 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/common/robot_actions/manifest.xml 2009-06-05 23:40:09 UTC (rev 16796)
@@ -7,6 +7,7 @@
<depend package="roscpp"/>
<depend package="robot_msgs"/>
+ <depend package="diagnostic_msgs"/>
<depend package="std_msgs"/>
<depend package="rospy" />
<depend package="rostopic" />
Deleted: pkg/trunk/common/robot_msgs/msg/DiagnosticMessage.msg
===================================================================
--- pkg/trunk/common/robot_msgs/msg/DiagnosticMessage.msg 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/common/robot_msgs/msg/DiagnosticMessage.msg 2009-06-05 23:40:09 UTC (rev 16796)
@@ -1,2 +0,0 @@
-Header header #for timestamp
-DiagnosticStatus[] status # an array of components being reported on
\ No newline at end of file
Deleted: pkg/trunk/common/robot_msgs/msg/DiagnosticStatus.msg
===================================================================
--- pkg/trunk/common/robot_msgs/msg/DiagnosticStatus.msg 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/common/robot_msgs/msg/DiagnosticStatus.msg 2009-06-05 23:40:09 UTC (rev 16796)
@@ -1,5 +0,0 @@
-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
-DiagnosticString[] strings # an array of string associated with the status
Deleted: pkg/trunk/common/robot_msgs/msg/DiagnosticString.msg
===================================================================
--- pkg/trunk/common/robot_msgs/msg/DiagnosticString.msg 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/common/robot_msgs/msg/DiagnosticString.msg 2009-06-05 23:40:09 UTC (rev 16796)
@@ -1,2 +0,0 @@
-string value # a string data type
-string label # what to label this value when viewing
Deleted: pkg/trunk/common/robot_msgs/msg/DiagnosticValue.msg
===================================================================
--- pkg/trunk/common/robot_msgs/msg/DiagnosticValue.msg 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/common/robot_msgs/msg/DiagnosticValue.msg 2009-06-05 23:40:09 UTC (rev 16796)
@@ -1,2 +0,0 @@
-float32 value # a value to track over time
-string label # what to label this value when viewing
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_trajectory_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_trajectory_controller.h 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/arm_trajectory_controller.h 2009-06-05 23:40:09 UTC (rev 16796)
@@ -58,7 +58,7 @@
#include <robot_msgs/JointTraj.h>
#include <robot_msgs/JointTrajPoint.h>
-#include <robot_msgs/DiagnosticMessage.h>
+#include <diagnostic_msgs/DiagnosticMessage.h>
#include <pr2_mechanism_controllers/TrajectoryStart.h>
#include <pr2_mechanism_controllers/TrajectoryQuery.h>
@@ -240,7 +240,7 @@
void publishDiagnostics();
- realtime_tools::RealtimePublisher <robot_msgs::DiagnosticMessage>* diagnostics_publisher_ ; //!< Publishes controller information
+ realtime_tools::RealtimePublisher <diagnostic_msgs::DiagnosticMessage>* diagnostics_publisher_ ; //!< Publishes controller information
/*!
* \brief mutex lock for setting and getting ros messages
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/joint_trajectory_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/joint_trajectory_controller.h 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/joint_trajectory_controller.h 2009-06-05 23:40:09 UTC (rev 16796)
@@ -43,7 +43,7 @@
// Services
#include <robot_msgs/JointTraj.h>
#include <robot_msgs/JointTrajPoint.h>
-#include <robot_msgs/DiagnosticMessage.h>
+#include <diagnostic_msgs/DiagnosticMessage.h>
#include <pr2_mechanism_controllers/TrajectoryStart.h>
#include <pr2_mechanism_controllers/TrajectoryQuery.h>
@@ -182,7 +182,7 @@
bool watch_dog_active_;
- realtime_tools::RealtimePublisher <robot_msgs::DiagnosticMessage>* diagnostics_publisher_ ; /**< Publishes controller information as a diagnostic message */
+ realtime_tools::RealtimePublisher <diagnostic_msgs::DiagnosticMessage>* diagnostics_publisher_ ; /**< Publishes controller information as a diagnostic message */
/*!
* \brief mutex lock for setting and getting ros messages
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/whole_body_trajectory_controller.h
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/whole_body_trajectory_controller.h 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/include/pr2_mechanism_controllers/whole_body_trajectory_controller.h 2009-06-05 23:40:09 UTC (rev 16796)
@@ -58,7 +58,7 @@
#include <robot_msgs/JointTraj.h>
#include <robot_msgs/JointTrajPoint.h>
-#include <robot_msgs/DiagnosticMessage.h>
+#include <diagnostic_msgs/DiagnosticMessage.h>
#include <pr2_mechanism_controllers/TrajectoryStart.h>
#include <pr2_mechanism_controllers/TrajectoryQuery.h>
@@ -287,7 +287,7 @@
void publishDiagnostics();
- realtime_tools::RealtimePublisher <robot_msgs::DiagnosticMessage>* diagnostics_publisher_ ; //!< Publishes controller information
+ realtime_tools::RealtimePublisher <diagnostic_msgs::DiagnosticMessage>* diagnostics_publisher_ ; //!< Publishes controller information
/*!
* \brief mutex lock for setting and getting ros messages
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/arm_trajectory_controller.cpp 2009-06-05 23:40:09 UTC (rev 16796)
@@ -409,7 +409,7 @@
if (diagnostics_publisher_ != NULL)// Make sure that we don't memory leak if initXml gets called twice
delete diagnostics_publisher_ ;
- diagnostics_publisher_ = new realtime_tools::RealtimePublisher <robot_msgs::DiagnosticMessage> ("/diagnostics", 2) ;
+ diagnostics_publisher_ = new realtime_tools::RealtimePublisher <diagnostic_msgs::DiagnosticMessage> ("/diagnostics", 2) ;
last_diagnostics_publish_time_ = c_->robot_->hw_->current_time_;
node_->param<double>(service_prefix_ + "/diagnostics_publish_delta_time",diagnostics_publish_delta_time_,0.05);
@@ -689,11 +689,11 @@
cmd.set_positions_size(1);
cmd.set_velocity_size(1);
- vector<robot_msgs::DiagnosticStatus> statuses;
- vector<robot_msgs::DiagnosticValue> values;
- vector<robot_msgs::DiagnosticString> strings;
- robot_msgs::DiagnosticStatus status;
- robot_msgs::DiagnosticValue v;
+ vector<diagnostic_msgs::DiagnosticStatus> statuses;
+ vector<diagnostic_msgs::DiagnosticValue> values;
+ vector<diagnostic_msgs::DiagnosticString> strings;
+ diagnostic_msgs::DiagnosticStatus status;
+ diagnostic_msgs::DiagnosticValue 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-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/base_trajectory_controller.cpp 2009-06-05 23:40:09 UTC (rev 16796)
@@ -35,8 +35,8 @@
* Author: Sachin Chitta
*********************************************************************/
#include <pr2_mechanism_controllers/base_trajectory_controller.h>
-#include <robot_msgs/DiagnosticMessage.h>
-#include <robot_msgs/DiagnosticStatus.h>
+#include <diagnostic_msgs/DiagnosticMessage.h>
+#include <diagnostic_msgs/DiagnosticStatus.h>
#include <ros/rate.h>
namespace pr2_mechanism_controllers
@@ -83,7 +83,7 @@
ros_node_.advertise<robot_msgs::PoseDot>(control_topic_name_, 1);
ros_node_.subscribe(path_input_topic_name_,path_msg_in_, &BaseTrajectoryController::pathCallback, this, 1);
- ros_node_.advertise<robot_msgs::DiagnosticMessage> ("/diagnostics", 1) ;
+ ros_node_.advertise<diagnostic_msgs::DiagnosticMessage> ("/diagnostics", 1) ;
last_diagnostics_publish_time_ = ros::Time::now();
current_time_ = ros::Time::now().toSec();
@@ -277,14 +277,14 @@
return;
}
- robot_msgs::DiagnosticMessage message;
- std::vector<robot_msgs::DiagnosticStatus> statuses;
- std::vector<robot_msgs::DiagnosticValue> values;
- std::vector<robot_msgs::DiagnosticString> strings;
+ diagnostic_msgs::DiagnosticMessage message;
+ std::vector<diagnostic_msgs::DiagnosticStatus> statuses;
+ std::vector<diagnostic_msgs::DiagnosticValue> values;
+ std::vector<diagnostic_msgs::DiagnosticString> strings;
- robot_msgs::DiagnosticStatus status;
- robot_msgs::DiagnosticValue v;
- robot_msgs::DiagnosticString s;
+ diagnostic_msgs::DiagnosticStatus status;
+ diagnostic_msgs::DiagnosticValue 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-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/joint_trajectory_controller.cpp 2009-06-05 23:40:09 UTC (rev 16796)
@@ -129,7 +129,7 @@
if (diagnostics_publisher_ != NULL)// Make sure that we don't memory leak if initXml gets called twice
delete diagnostics_publisher_ ;
- diagnostics_publisher_ = new realtime_tools::RealtimePublisher <robot_msgs::DiagnosticMessage> ("/diagnostics", 2) ;
+ diagnostics_publisher_ = new realtime_tools::RealtimePublisher <diagnostic_msgs::DiagnosticMessage> ("/diagnostics", 2) ;
last_diagnostics_publish_time_ = robot_->hw_->current_time_;
node_->param<double>(prefix_+"diagnostics_publish_delta_time",diagnostics_publish_delta_time_,0.05);
@@ -1018,12 +1018,12 @@
cmd.set_positions_size(1);
cmd.set_velocity_size(1);
- vector<robot_msgs::DiagnosticStatus> statuses;
- vector<robot_msgs::DiagnosticValue> values;
- vector<robot_msgs::DiagnosticString> strings;
- robot_msgs::DiagnosticStatus status;
- robot_msgs::DiagnosticValue v;
- robot_msgs::DiagnosticString s;
+ vector<diagnostic_msgs::DiagnosticStatus> statuses;
+ vector<diagnostic_msgs::DiagnosticValue> values;
+ vector<diagnostic_msgs::DiagnosticString> strings;
+ diagnostic_msgs::DiagnosticStatus status;
+ diagnostic_msgs::DiagnosticValue v;
+ diagnostic_msgs::DiagnosticString s;
status.name = "Whole Body Trajectory Controller";
status.level = 0;
if(watch_dog_active_)
Modified: pkg/trunk/controllers/pr2_mechanism_controllers/src/whole_body_trajectory_controller.cpp
===================================================================
--- pkg/trunk/controllers/pr2_mechanism_controllers/src/whole_body_trajectory_controller.cpp 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/controllers/pr2_mechanism_controllers/src/whole_body_trajectory_controller.cpp 2009-06-05 23:40:09 UTC (rev 16796)
@@ -639,7 +639,7 @@
if (diagnostics_publisher_ != NULL)// Make sure that we don't memory leak if initXml gets called twice
delete diagnostics_publisher_ ;
- diagnostics_publisher_ = new realtime_tools::RealtimePublisher <robot_msgs::DiagnosticMessage> ("/diagnostics", 2) ;
+ diagnostics_publisher_ = new realtime_tools::RealtimePublisher <diagnostic_msgs::DiagnosticMessage> ("/diagnostics", 2) ;
last_diagnostics_publish_time_ = c_->robot_->hw_->current_time_;
node_->param<double>(service_prefix_ + "/diagnostics_publish_delta_time",diagnostics_publish_delta_time_,0.05);
@@ -914,11 +914,11 @@
cmd.set_positions_size(1);
cmd.set_velocity_size(1);
- vector<robot_msgs::DiagnosticStatus> statuses;
- vector<robot_msgs::DiagnosticValue> values;
- vector<robot_msgs::DiagnosticString> strings;
- robot_msgs::DiagnosticStatus status;
- robot_msgs::DiagnosticValue v;
+ vector<diagnostic_msgs::DiagnosticStatus> statuses;
+ vector<diagnostic_msgs::DiagnosticValue> values;
+ vector<diagnostic_msgs::DiagnosticString> strings;
+ diagnostic_msgs::DiagnosticStatus status;
+ diagnostic_msgs::DiagnosticValue v;
status.name = "Whole Body Trajectory Controller";
status.level = 0;
Modified: pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/backlash_controller.h
===================================================================
--- pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/backlash_controller.h 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/backlash_controller.h 2009-06-05 23:40:09 UTC (rev 16796)
@@ -45,7 +45,7 @@
#include <ros/node.h>
#include <math.h>
-#include <robot_msgs/DiagnosticMessage.h>
+#include <diagnostic_msgs/DiagnosticMessage.h>
#include <realtime_tools/realtime_publisher.h>
#include <realtime_tools/realtime_srv_call.h>
#include <mechanism_model/controller.h>
@@ -87,7 +87,7 @@
inline bool done() { return done_; }
- robot_msgs::DiagnosticMessage diagnostic_message_;
+ diagnostic_msgs::DiagnosticMessage diagnostic_message_;
joint_qualification_controllers::TestData::Request test_data_;
private:
@@ -127,7 +127,7 @@
double last_publish_time_;
realtime_tools::RealtimeSrvCall<joint_qualification_controllers::TestData::Request, joint_qualification_controllers::TestData::Response> call_service_;
- realtime_tools::RealtimePublisher<robot_msgs::DiagnosticMessage> pub_diagnostics_;
+ realtime_tools::RealtimePublisher<diagnostic_msgs::DiagnosticMessage> pub_diagnostics_;
};
}
Modified: pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/hold_set_controller.h
===================================================================
--- pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/hold_set_controller.h 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/hold_set_controller.h 2009-06-05 23:40:09 UTC (rev 16796)
@@ -48,7 +48,6 @@
#include <vector>
#include <ros/node.h>
#include <math.h>
-#include <robot_msgs/DiagnosticMessage.h>
#include <joint_qualification_controllers/HoldSetData.h>
#include <realtime_tools/realtime_publisher.h>
#include <realtime_tools/realtime_srv_call.h>
Modified: pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/hysteresis_controller.h
===================================================================
--- pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/hysteresis_controller.h 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/controllers/qualification_controllers/joint_qualification_controllers/include/joint_qualification_controllers/hysteresis_controller.h 2009-06-05 23:40:09 UTC (rev 16796)
@@ -48,7 +48,7 @@
#include <ros/node.h>
#include <math.h>
#include <sstream>
-#include <robot_msgs/DiagnosticMessage.h>
+#include <diagnostic_msgs/DiagnosticMessage.h>
#include <joint_qualification_controllers/TestData.h>
#include <realtime_tools/realtime_publisher.h>
#include <realtime_tools/realtime_srv_call.h>
@@ -90,7 +90,7 @@
bool done() { return state_ == DONE; }
- robot_msgs::DiagnosticMessage diagnostic_message_;
+ diagnostic_msgs::DiagnosticMessage diagnostic_message_;
joint_qualification_controllers::TestData::Request test_data_;
private:
@@ -143,7 +143,7 @@
double last_publish_time_;
realtime_tools::RealtimeSrvCall<joint_qualification_controllers::TestData::Request, joint_qualification_controllers::TestData::Response> call_service_;
- //realtime_tools::RealtimePublisher<robot_msgs::DiagnosticMessage> pub_diagnostics_;
+ //realtime_tools::RealtimePublisher<diagnostic_msgs::DiagnosticMessage> pub_diagnostics_;
};
}
Modified: pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_wrench_controller.h
===================================================================
--- pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_wrench_controller.h 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/controllers/robot_mechanism_controllers/include/robot_mechanism_controllers/cartesian_wrench_controller.h 2009-06-05 23:40:09 UTC (rev 16796)
@@ -43,7 +43,7 @@
#include <mechanism_model/controller.h>
#include <mechanism_model/chain.h>
#include <tf/transform_datatypes.h>
-#include <robot_msgs/DiagnosticMessage.h>
+#include <diagnostic_msgs/DiagnosticMessage.h>
#include <realtime_tools/realtime_publisher.h>
#include <boost/scoped_ptr.hpp>
@@ -79,8 +79,8 @@
KDL::JntArray jnt_pos_, jnt_eff_;
KDL::Jacobian jacobian_;
- robot_msgs::DiagnosticMessage diagnostics_;
- realtime_tools::RealtimePublisher <robot_msgs::DiagnosticMessage> diagnostics_publisher_;
+ diagnostic_msgs::DiagnosticMessage diagnostics_;
+ realtime_tools::RealtimePublisher <diagnostic_msgs::DiagnosticMessage> diagnostics_publisher_;
ros::Time diagnostics_time_;
ros::Duration diagnostics_interval_;
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-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/cam/axis_cam/src/axis_cam/axis_cam.cpp 2009-06-05 23:40:09 UTC (rev 16796)
@@ -142,7 +142,7 @@
}
- void checkImage(robot_msgs::DiagnosticStatus& status)
+ void checkImage(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Image Test";
uint8_t *jpeg;
@@ -178,7 +178,7 @@
}
}
- void checkMac(robot_msgs::DiagnosticStatus& status)
+ void checkMac(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "MAC test";
char cmd[100];
Modified: pkg/trunk/drivers/cam/dcam/src/nodes/dcam.cpp
===================================================================
--- pkg/trunk/drivers/cam/dcam/src/nodes/dcam.cpp 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/cam/dcam/src/nodes/dcam.cpp 2009-06-05 23:40:09 UTC (rev 16796)
@@ -311,7 +311,7 @@
}
- void freqStatus(robot_msgs::DiagnosticStatus& status)
+ void freqStatus(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Frequency Status";
Modified: pkg/trunk/drivers/cam/dcam/src/nodes/stereodcam.cpp
===================================================================
--- pkg/trunk/drivers/cam/dcam/src/nodes/stereodcam.cpp 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/cam/dcam/src/nodes/stereodcam.cpp 2009-06-05 23:40:09 UTC (rev 16796)
@@ -415,7 +415,7 @@
return true;
}
- void freqStatus(robot_msgs::DiagnosticStatus& status)
+ void freqStatus(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Frequency Status";
Modified: pkg/trunk/drivers/cam/prosilica_cam/manifest.xml
===================================================================
--- pkg/trunk/drivers/cam/prosilica_cam/manifest.xml 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/cam/prosilica_cam/manifest.xml 2009-06-05 23:40:09 UTC (rev 16796)
@@ -8,6 +8,7 @@
<depend package="std_msgs" />
<depend package="image_msgs" />
<depend package="diagnostic_updater" />
+ <depend package="diagnostic_msgs" />
<depend package="image_view" />
<export>
<cpp lflags="-Wl,-rpath,${prefix}/lib -L${prefix}/lib -lprosilica" cflags="-I${prefix}/include -I${prefix}/srv/cpp"/>
Modified: pkg/trunk/drivers/cam/prosilica_cam/src/nodes/prosilica_node.cpp
===================================================================
--- pkg/trunk/drivers/cam/prosilica_cam/src/nodes/prosilica_node.cpp 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/cam/prosilica_cam/src/nodes/prosilica_node.cpp 2009-06-05 23:40:09 UTC (rev 16796)
@@ -40,6 +40,7 @@
#include <image_msgs/FillImage.h>
#include <opencv_latest/CvBridge.h>
#include <diagnostic_updater/diagnostic_updater.h>
+#include "diagnostic_msgs/DiagnosticStatus.h"
#include <cv.h>
#include <cvwimage.h>
@@ -291,7 +292,7 @@
return 0;
}
- void freqStatus(robot_msgs::DiagnosticStatus& status)
+ void freqStatus(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Frequency Status";
@@ -319,7 +320,7 @@
count_ = 0;
}
- void frameStatistics(robot_msgs::DiagnosticStatus& status)
+ void frameStatistics(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Frame Statistics";
@@ -369,7 +370,7 @@
status.values[4].value = dropped;
}
- void packetStatistics(robot_msgs::DiagnosticStatus& status)
+ void packetStatistics(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Packet Statistics";
@@ -444,7 +445,7 @@
status.values[6].value = data_rate;
}
- void packetErrorStatus(robot_msgs::DiagnosticStatus& status)
+ void packetErrorStatus(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Packet Error Status";
Modified: pkg/trunk/drivers/imu/imu_node/imu_node.cc
===================================================================
--- pkg/trunk/drivers/imu/imu_node/imu_node.cc 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/imu/imu_node/imu_node.cc 2009-06-05 23:40:09 UTC (rev 16796)
@@ -63,7 +63,7 @@
Publishes to (name / type):
- @b "imu_data"/<a href="../../std_msgs/html/classstd__msgs_1_1PoseWithRatesStamped.html">std_msgs/PoseWithRatesStamped</a> : the imu data
-- @b "/diagnostics"/<a href="../../robot_msgs/html/classrobot__msgs_1_1DiagnosticMessage.html">robot_msgs/DiagnosticMessage</a> : diagnostic status information.
+- @b "/diagnostics"/<a href="../../diagnostic_msgs/html/classrobot__msgs_1_1DiagnosticMessage.html">diagnostic_msgs/DiagnosticMessage</a> : diagnostic status information.
<hr>
@@ -93,6 +93,7 @@
#include "ros/node.h"
#include "ros/time.h"
#include "self_test/self_test.h"
+#include "diagnostic_msgs/DiagnosticStatus.h"
#include "diagnostic_updater/diagnostic_updater.h"
#include "diagnostic_updater/update_functions.h"
@@ -334,7 +335,7 @@
}
}
- void InterruptionTest(robot_msgs::DiagnosticStatus& status)
+ void InterruptionTest(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Interruption Test";
@@ -350,7 +351,7 @@
}
}
- void ConnectTest(robot_msgs::DiagnosticStatus& status)
+ void ConnectTest(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Connection Test";
@@ -360,7 +361,7 @@
status.message = "Connected successfully.";
}
- void GyroBiasTest(robot_msgs::DiagnosticStatus& status)
+ void GyroBiasTest(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Gyro Bias Test";
@@ -384,7 +385,7 @@
}
- void StreamedDataTest(robot_msgs::DiagnosticStatus& status)
+ void StreamedDataTest(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Streamed Data Test";
@@ -410,7 +411,7 @@
}
}
- void GravityTest(robot_msgs::DiagnosticStatus& status)
+ void GravityTest(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Streamed Data Test";
@@ -471,7 +472,7 @@
}
- void DisconnectTest(robot_msgs::DiagnosticStatus& status)
+ void DisconnectTest(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Disconnect Test";
@@ -481,7 +482,7 @@
status.message = "Disconnected successfully.";
}
- void ResumeTest(robot_msgs::DiagnosticStatus& status)
+ void ResumeTest(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Resume Test";
Modified: pkg/trunk/drivers/laser/hokuyo_node/src/node/hokuyo_node.cpp
===================================================================
--- pkg/trunk/drivers/laser/hokuyo_node/src/node/hokuyo_node.cpp 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/laser/hokuyo_node/src/node/hokuyo_node.cpp 2009-06-05 23:40:09 UTC (rev 16796)
@@ -112,6 +112,7 @@
#include "self_test/self_test.h"
#include "diagnostic_updater/diagnostic_updater.h"
+#include "diagnostic_msgs/DiagnosticStatus.h"
#include "hokuyo.h"
@@ -397,7 +398,7 @@
return true;
}
- void connectionStatus(robot_msgs::DiagnosticStatus& status)
+ void connectionStatus(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Connection Status";
@@ -424,7 +425,7 @@
status.strings[2].value = device_status_;
}
- void freqStatus(robot_msgs::DiagnosticStatus& status)
+ void freqStatus(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Frequency Status";
@@ -464,7 +465,7 @@
}
}
- void interruptionTest(robot_msgs::DiagnosticStatus& status)
+ void interruptionTest(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Interruption Test";
@@ -480,7 +481,7 @@
}
}
- void connectTest(robot_msgs::DiagnosticStatus& status)
+ void connectTest(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Connection Test";
@@ -490,7 +491,7 @@
status.message = "Connected successfully.";
}
- void IDTest(robot_msgs::DiagnosticStatus& status)
+ void IDTest(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "ID Test";
@@ -510,7 +511,7 @@
self_test_.setID(id);
}
- void statusTest(robot_msgs::DiagnosticStatus& status)
+ void statusTest(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Status Test";
@@ -526,7 +527,7 @@
status.message = stat;
}
- void laserTest(robot_msgs::DiagnosticStatus& status)
+ void laserTest(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Laser Test";
@@ -536,7 +537,7 @@
status.message = "Laser turned on successfully.";
}
- void polledDataTest(robot_msgs::DiagnosticStatus& status)
+ void polledDataTest(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Polled Data Test";
@@ -557,7 +558,7 @@
}
}
- void streamedDataTest(robot_msgs::DiagnosticStatus& status)
+ void streamedDataTest(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Streamed Data Test";
@@ -585,7 +586,7 @@
}
}
- void streamedIntensityDataTest(robot_msgs::DiagnosticStatus& status)
+ void streamedIntensityDataTest(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Streamed Intensity Data Test";
@@ -630,7 +631,7 @@
}
}
- void laserOffTest(robot_msgs::DiagnosticStatus& status)
+ void laserOffTest(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Laser Off Test";
@@ -640,7 +641,7 @@
status.message = "Laser turned off successfully.";
}
- void disconnectTest(robot_msgs::DiagnosticStatus& status)
+ void disconnectTest(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Disconnect Test";
@@ -650,7 +651,7 @@
status.message = "Disconnected successfully.";
}
- void resumeTest(robot_msgs::DiagnosticStatus& status)
+ void resumeTest(diagnostic_msgs::DiagnosticStatus& status)
{
status.name = "Resume Test";
Modified: pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/ek1122.h
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/ek1122.h 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/ek1122.h 2009-06-05 23:40:09 UTC (rev 16796)
@@ -48,7 +48,7 @@
void computeCurrent(ActuatorCommand &command) {}
void truncateCurrent(ActuatorCommand &command) {}
bool verifyState(ActuatorState &, unsigned char *this_buffer, unsigned char *prev_buffer) {return true;}
- void diagnostics(robot_msgs::DiagnosticStatus &d, unsigned char *);
+ void diagnostics(diagnostic_msgs::DiagnosticStatus &d, unsigned char *);
enum {PRODUCT_CODE = 0x4622c52};
Modified: pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/ethercat_device.h
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/ethercat_device.h 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/ethercat_device.h 2009-06-05 23:40:09 UTC (rev 16796)
@@ -44,7 +44,7 @@
#include <hardware_interface/hardware_interface.h>
-#include <robot_msgs/DiagnosticMessage.h>
+#include <diagnostic_msgs/DiagnosticMessage.h>
#include <loki/Factory.h>
@@ -69,7 +69,7 @@
virtual void truncateCurrent(ActuatorCommand &command) = 0;
virtual bool verifyState(ActuatorState &state, unsigned char *this_buffer, unsigned char *prev_buffer) = 0;
- virtual void diagnostics(robot_msgs::DiagnosticStatus &d, unsigned char *) = 0;
+ virtual void diagnostics(diagnostic_msgs::DiagnosticStatus &d, unsigned char *) = 0;
bool has_actuator_;
unsigned int command_size_;
Modified: pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/ethercat_hardware.h
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/ethercat_hardware.h 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/ethercat_hardware.h 2009-06-05 23:40:09 UTC (rev 16796)
@@ -107,7 +107,7 @@
bool halt_motors_;
unsigned int reset_state_;
- realtime_tools::RealtimePublisher<robot_msgs::DiagnosticMessage> publisher_;
+ realtime_tools::RealtimePublisher<diagnostic_msgs::DiagnosticMessage> publisher_;
struct {
accumulator_set<double, stats<tag::max, tag::mean> > acc_;
double max_roundtrip_;
@@ -115,9 +115,9 @@
} diagnostics_;
double last_published_;
- vector<robot_msgs::DiagnosticStatus> statuses_;
- vector<robot_msgs::DiagnosticValue> values_;
- vector<robot_msgs::DiagnosticString> strings_;
+ vector<diagnostic_msgs::DiagnosticStatus> statuses_;
+ vector<diagnostic_msgs::DiagnosticValue> values_;
+ vector<diagnostic_msgs::DiagnosticString> strings_;
};
Modified: pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/wg014.h
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/wg014.h 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/wg014.h 2009-06-05 23:40:09 UTC (rev 16796)
@@ -49,7 +49,7 @@
void computeCurrent(ActuatorCommand &command) {}
void truncateCurrent(ActuatorCommand &command) {}
bool verifyState(ActuatorState &, unsigned char *this_buffer, unsigned char *prev_buffer) {return true;}
- void diagnostics(robot_msgs::DiagnosticStatus &d, unsigned char *);
+ void diagnostics(diagnostic_msgs::DiagnosticStatus &d, unsigned char *);
enum {PRODUCT_CODE = 6805014};
};
Modified: pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/wg0x.h
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/wg0x.h 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/motor/ethercat_hardware/include/ethercat_hardware/wg0x.h 2009-06-05 23:40:09 UTC (rev 16796)
@@ -235,7 +235,7 @@
void program(WG0XActuatorInfo *);
bool isProgrammed() { return actuator_info_.crc32_ != 0;}
- void diagnostics(robot_msgs::DiagnosticStatus &d, unsigned char *);
+ void diagnostics(diagnostic_msgs::DiagnosticStatus &d, unsigned char *);
private:
string safetyDisableString(uint8_t status);
@@ -292,8 +292,8 @@
static const int ACTUATOR_INFO_PAGE = 4095;
// Diagnostic message values
- vector<robot_msgs::DiagnosticString> strings_;
- vector<robot_msgs::DiagnosticValue> values_;
+ vector<diagnostic_msgs::DiagnosticString> strings_;
+ vector<diagnostic_msgs::DiagnosticValue> values_;
string reason_;
int level_;
double voltage_error_, max_voltage_error_;
Modified: pkg/trunk/drivers/motor/ethercat_hardware/manifest.xml
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/manifest.xml 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/motor/ethercat_hardware/manifest.xml 2009-06-05 23:40:09 UTC (rev 16796)
@@ -12,7 +12,7 @@
<depend package='loki'/>
<depend package='roscpp' />
<depend package='realtime_tools' />
-<depend package='robot_msgs' />
+<depend package='diagnostic_msgs' />
<export>
<cpp cflags="-I${prefix}/include" lflags="-L${prefix}/lib -lethercat_hardware -Wl,-rpath,${prefix}/lib -lloki"/>
</export>
Modified: pkg/trunk/drivers/motor/ethercat_hardware/src/ek1122.cpp
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/src/ek1122.cpp 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/motor/ethercat_hardware/src/ek1122.cpp 2009-06-05 23:40:09 UTC (rev 16796)
@@ -52,12 +52,12 @@
ROS_DEBUG("Device #%02d: EK1122 (%#08x)", sh_->get_ring_position(), sh_->get_product_code());
return 0;
}
-void EK1122::diagnostics(robot_msgs::DiagnosticStatus &d, unsigned char *)
+void EK1122::diagnostics(diagnostic_msgs::DiagnosticStatus &d, unsigned char *)
{
- vector<robot_msgs::DiagnosticString> strings;
- vector<robot_msgs::DiagnosticValue> values;
- robot_msgs::DiagnosticValue v;
- robot_msgs::DiagnosticString s;
+ vector<diagnostic_msgs::DiagnosticString> strings;
+ vector<diagnostic_msgs::DiagnosticValue> values;
+ diagnostic_msgs::DiagnosticValue v;
+ diagnostic_msgs::DiagnosticString s;
stringstream str;
str << "EtherCAT Device #" << setw(2) << setfill('0') << sh_->get_ring_position() << " (EK1122)";
Modified: pkg/trunk/drivers/motor/ethercat_hardware/src/ethercat_hardware.cpp
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/src/ethercat_hardware.cpp 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/motor/ethercat_hardware/src/ethercat_hardware.cpp 2009-06-05 23:40:09 UTC (rev 16796)
@@ -250,9 +250,9 @@
void EthercatHardware::publishDiagnostics()
{
// Publish status of EtherCAT master
- robot_msgs::DiagnosticStatus status;
- robot_msgs::DiagnosticValue v;
- robot_msgs::DiagnosticString s;
+ diagnostic_msgs::DiagnosticStatus status;
+ diagnostic_msgs::DiagnosticValue v;
+ diagnostic_msgs::DiagnosticString s;
strings_.clear();
values_.clear();
Modified: pkg/trunk/drivers/motor/ethercat_hardware/src/wg014.cpp
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/src/wg014.cpp 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/motor/ethercat_hardware/src/wg014.cpp 2009-06-05 23:40:09 UTC (rev 16796)
@@ -66,12 +66,12 @@
} \
strings.push_back(s)
-void WG014::diagnostics(robot_msgs::DiagnosticStatus &d, unsigned char *)
+void WG014::diagnostics(diagnostic_msgs::DiagnosticStatus &d, unsigned char *)
{
- vector<robot_msgs::DiagnosticString> strings;
- vector<robot_msgs::DiagnosticValue> values;
- robot_msgs::DiagnosticValue v;
- robot_msgs::DiagnosticString s;
+ vector<diagnostic_msgs::DiagnosticString> strings;
+ vector<diagnostic_msgs::DiagnosticValue> values;
+ diagnostic_msgs::DiagnosticValue v;
+ diagnostic_msgs::DiagnosticString s;
stringstream str;
str << "EtherCAT Device #" << setw(2) << setfill('0') << sh_->get_ring_position() << " (WG014)";
Modified: pkg/trunk/drivers/motor/ethercat_hardware/src/wg0x.cpp
===================================================================
--- pkg/trunk/drivers/motor/ethercat_hardware/src/wg0x.cpp 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/motor/ethercat_hardware/src/wg0x.cpp 2009-06-05 23:40:09 UTC (rev 16796)
@@ -872,10 +872,10 @@
s.label = (lab); \
s.value = (val); \
strings_.push_back(s)
-void WG0X::diagnostics(robot_msgs::DiagnosticStatus &d, unsigned char *buffer)
+void WG0X::diagnostics(diagnostic_msgs::DiagnosticStatus &d, unsigned char *buffer)
{
- robot_msgs::DiagnosticValue v;
- robot_msgs::DiagnosticString s;
+ diagnostic_msgs::DiagnosticValue v;
+ diagnostic_msgs::DiagnosticString s;
//WG0XCommand *cmd = (WG0XCommand *)(buffer + sizeof(WG0XStatus));
WG0XStatus *status = (WG0XStatus *)buffer;
Modified: pkg/trunk/drivers/robot/pr2/ocean_battery_driver/manifest.xml
===================================================================
--- pkg/trunk/drivers/robot/pr2/ocean_battery_driver/manifest.xml 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/robot/pr2/ocean_battery_driver/manifest.xml 2009-06-05 23:40:09 UTC (rev 16796)
@@ -4,5 +4,5 @@
<license>BSD</license>
<review status="API cleared" notes=""/>
<depend package="rospy" />
- <depend package="robot_msgs" />
+ <depend package="diagnostic_msgs" />
</package>
Modified: pkg/trunk/drivers/robot/pr2/ocean_battery_driver/scripts/monitor
===================================================================
--- pkg/trunk/drivers/robot/pr2/ocean_battery_driver/scripts/monitor 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/robot/pr2/ocean_battery_driver/scripts/monitor 2009-06-05 23:40:09 UTC (rev 16796)
@@ -47,7 +47,7 @@
import rospy
-from robot_msgs.msg import *
+from diagnostic_msgs.msg import DiagnosticMessage, DiagnosticStatus, DiagnosticValue, DiagnosticString
NAME = 'monitor'
Modified: pkg/trunk/drivers/robot/pr2/pr2_power_board/manifest.xml
===================================================================
--- pkg/trunk/drivers/robot/pr2/pr2_power_board/manifest.xml 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/robot/pr2/pr2_power_board/manifest.xml 2009-06-05 23:40:09 UTC (rev 16796)
@@ -5,5 +5,5 @@
<review status="API cleared" notes=""/>
<depend package="roscpp" />
<depend package="rospy" />
- <depend package="robot_msgs" />
+ <depend package="diagnostic_msgs" />
</package>
Modified: pkg/trunk/drivers/robot/pr2/pr2_power_board/scripts/view_power
===================================================================
--- pkg/trunk/drivers/robot/pr2/pr2_power_board/scripts/view_power 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/robot/pr2/pr2_power_board/scripts/view_power 2009-06-05 23:40:09 UTC (rev 16796)
@@ -39,7 +39,7 @@
import sys
import rospy
-from robot_msgs.msg import *
+from diagnostic_msgs.msg import *
import wx
import threading, time
Modified: pkg/trunk/drivers/robot/pr2/pr2_power_board/src/power_node/power_node.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/pr2_power_board/src/power_node/power_node.cpp 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/robot/pr2/pr2_power_board/src/power_node/power_node.cpp 2009-06-05 23:40:09 UTC (rev 16796)
@@ -54,7 +54,7 @@
#include "power_comm.h"
#include "power_node.h"
-#include "robot_msgs/DiagnosticMessage.h"
+#include "diagnostic_msgs/DiagnosticMessage.h"
#include "rosconsole/macros_generated.h"
#include "ros/console.h"
@@ -615,7 +615,7 @@
}
advertiseService("power_board_control", &PowerBoard::commandCallback);
- advertise<robot_msgs::DiagnosticMessage>("/diagnostics", 2);
+ advertise<diagnostic_msgs::DiagnosticMessage>("/diagnostics", 2);
}
bool PowerBoard::commandCallback(pr2_power_board::PowerBoardCommand::Request &req_,
@@ -637,10 +637,10 @@
void PowerBoard::sendDiagnostic()
{
- robot_msgs::DiagnosticMessage msg_out;
- robot_msgs::DiagnosticStatus stat;
- robot_msgs::DiagnosticValue val;
- robot_msgs::DiagnosticString strval;
+ diagnostic_msgs::DiagnosticMessage msg_out;
+ diagnostic_msgs::DiagnosticStatus stat;
+ diagnostic_msgs::DiagnosticValue val;
+ diagnostic_msgs::DiagnosticString strval;
while(ok())
{
Modified: pkg/trunk/drivers/robot/pr2/pr2_power_board/src/power_node/power_node_simulator.cpp
===================================================================
--- pkg/trunk/drivers/robot/pr2/pr2_power_board/src/power_node/power_node_simulator.cpp 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/robot/pr2/pr2_power_board/src/power_node/power_node_simulator.cpp 2009-06-05 23:40:09 UTC (rev 16796)
@@ -53,7 +53,7 @@
#include "power_comm.h"
#include "power_node.h"
-#include "robot_msgs/DiagnosticMessage.h"
+#include "diagnostic_msgs/DiagnosticMessage.h"
#include "rosconsole/macros_generated.h"
#include "ros/console.h"
@@ -318,7 +318,7 @@
}
advertiseService("power_board_control", &PowerBoard::commandCallback);
- advertise<robot_msgs::DiagnosticMessage>("/diagnostics", 2);
+ advertise<diagnostic_msgs::DiagnosticMessage>("/diagnostics", 2);
}
bool PowerBoard::commandCallback(pr2_power_board::PowerBoardCommand::Request &req_,
@@ -331,10 +331,10 @@
void PowerBoard::sendDiagnostic()
{
- robot_msgs::DiagnosticMessage msg_out;
- robot_msgs::DiagnosticStatus stat;
- robot_msgs::DiagnosticValue val;
- robot_msgs::DiagnosticString strval;
+ diagnostic_msgs::DiagnosticMessage msg_out;
+ diagnostic_msgs::DiagnosticStatus stat;
+ diagnostic_msgs::DiagnosticValue val;
+ diagnostic_msgs::DiagnosticString strval;
while(ok())
{
@@ -550,7 +550,7 @@
msg_out.status.push_back(stat);
- robot_msgs::DiagnosticStatus stat;
+ diagnostic_msgs::DiagnosticStatus stat;
stat.name = "pr2_power_board";
stat.level = 0;
stat.message = "Running";
Modified: pkg/trunk/drivers/robot/pr2/pr2_power_board/src/pr2_power_board/power_wires.py
===================================================================
--- pkg/trunk/drivers/robot/pr2/pr2_power_board/src/pr2_power_board/power_wires.py 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/robot/pr2/pr2_power_board/src/pr2_power_board/power_wires.py 2009-06-05 23:40:09 UTC (rev 16796)
@@ -37,7 +37,7 @@
import sys
import rospy
-from robot_msgs.msg import *
+from diagnostic_msgs.msg import *
def recurse_tree(element, messages, wiremap):
Modified: pkg/trunk/drivers/robot/pr2/pr2_power_board/src/pr2_power_board/pr2_power_board_panel.py
===================================================================
--- pkg/trunk/drivers/robot/pr2/pr2_power_board/src/pr2_power_board/pr2_power_board_panel.py 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/robot/pr2/pr2_power_board/src/pr2_power_board/pr2_power_board_panel.py 2009-06-05 23:40:09 UTC (rev 16796)
@@ -40,7 +40,7 @@
import sys
import rospy
-from robot_msgs.msg import *
+from diagonstic_msgs.msg import *
from pr2_power_board.srv import *
import wx
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/gazebo_battery.h
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/gazebo_battery.h 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/include/gazebo_plugin/gazebo_battery.h 2009-06-05 23:40:09 UTC (rev 16796)
@@ -36,8 +36,8 @@
#include <gazebo/Entity.hh>
#include <gazebo/Model.hh>
#include <robot_msgs/BatteryState.h>
-#include <robot_msgs/DiagnosticMessage.h>
-#include <robot_msgs/DiagnosticStatus.h>
+#include <diagnostic_msgs/DiagnosticMessage.h>
+#include <diagnostic_msgs/DiagnosticStatus.h>
#include <gazebo_plugin/PlugCommand.h>
#include <ros/node.h>
#include <boost/thread/mutex.hpp>
@@ -111,8 +111,8 @@
robot_msgs::BatteryState battery_state_;
/// \brief ros message for diagnostic messages
- robot_msgs::DiagnosticMessage diagnostic_message_;
- robot_msgs::DiagnosticStatus diagnostic_status_;
+ diagnostic_msgs::DiagnosticMessage diagnostic_message_;
+ diagnostic_msgs::DiagnosticStatus diagnostic_status_;
/// \brief pointer to ros node
private: ros::Node *rosnode_;
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/manifest.xml 2009-06-05 23:40:09 UTC (rev 16796)
@@ -19,6 +19,7 @@
<depend package="laser_scan" />
<depend package="pr2_msgs" />
<depend package="robot_msgs" />
+ <depend package="diagnostic_msgs" />
<depend package="angles" />
<depend package="hardware_interface" />
<depend package="mechanism_control" />
Modified: pkg/trunk/drivers/simulator/gazebo_plugin/src/gazebo_battery.cpp
===================================================================
--- pkg/trunk/drivers/simulator/gazebo_plugin/src/gazebo_battery.cpp 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/drivers/simulator/gazebo_plugin/src/gazebo_battery.cpp 2009-06-05 23:40:09 UTC (rev 16796)
@@ -76,7 +76,7 @@
this->stateTopicName_ = node->GetString("stateTopicName","battery_state",0);
rosnode_->advertise<robot_msgs::BatteryState>(this->stateTopicName_,10);
//this->diagnosticMessageTopicName_ = node->GetString("diagnosticMessageTopicName","diagnostic",0);
- //rosnode_->advertise<robot_msgs::DiagnosticMessage>(this->diagnosticMessageTopicName_,10);
+ //rosnode_->advertise<diagnostic_msgs::DiagnosticMessage>(this->diagnosticMessageTopicName_,10);
/// faking the plug and unplug of robot
rosnode_->subscribe("plugged_in",this->plug_msg_,&GazeboBattery::SetPlug,this,10);
Modified: pkg/trunk/hardware_test/diagnostic_updater/include/diagnostic_updater/DiagnosticStatusWrapper.h
===================================================================
--- pkg/trunk/hardware_test/diagnostic_updater/include/diagnostic_updater/DiagnosticStatusWrapper.h 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/hardware_test/diagnostic_updater/include/diagnostic_updater/DiagnosticStatusWrapper.h 2009-06-05 23:40:09 UTC (rev 16796)
@@ -46,12 +46,12 @@
#include "ros/node.h"
-#include "robot_msgs/DiagnosticStatus.h"
+#include "diagnostic_msgs/DiagnosticStatus.h"
namespace diagnostic_updater
{
-class DiagnosticStatusWrapper : public robot_msgs::DiagnosticStatus
+class DiagnosticStatusWrapper : public diagnostic_msgs::DiagnosticStatus
{
public:
void summary(unsigned char lvl, const std::string s)
@@ -115,7 +115,7 @@
void addv(const std::string &key, double v)
{
- robot_msgs::DiagnosticValue dv;
+ diagnostic_msgs::DiagnosticValue dv;
dv.label = key;
dv.value = v;
values.push_back(dv);
@@ -125,7 +125,7 @@
template<>
void DiagnosticStatusWrapper::adds<std::string>(const std::string &key, const std::string &s)
{
- robot_msgs::DiagnosticString ds;
+ diagnostic_msgs::DiagnosticString ds;
ds.label = key;
ds.value = s;
strings.push_back(ds);
Modified: pkg/trunk/hardware_test/diagnostic_updater/include/diagnostic_updater/diagnostic_updater.h
===================================================================
--- pkg/trunk/hardware_test/diagnostic_updater/include/diagnostic_updater/diagnostic_updater.h 2009-06-05 22:36:30 UTC (rev 16795)
+++ pkg/trunk/hardware_test/diagnostic_updater/include/diagnostic_updater/diagnostic_updater.h 2009-06-05 23:40:09 UTC (rev 16796)
@@ -41,7 +41,7 @@
#include "ros/node_handle.h"
-#include "robot_msgs/DiagnosticMessage.h"
+#include "diagnostic_msgs/DiagnosticMessage.h"
#include "diagnostic_updater/DiagnosticStatusWrapper.h"
/**
@@ -80,7 +80,7 @@
{
typedef boost::function<void(DiagnosticStatusWrapper&)> TaskFunction;
-typedef boost::function<void(robot_msgs::DiagnosticStatus&)> UnwrappedTaskFunction;
+typedef boost::function<void(diagnostic_msgs::DiagnosticStatus&)> UnwrappedTaskFunction;
/**
* DiagnosticTask is an abstract base class for diagnostic tasks.
@@ -123,7 +123,7 @@
const TaskFunction fn_;
};
-typedef GenericFunctionDiagnosticTask<robot_msgs::DiagnosticStatus> UnwrappedFunctionDiagnosticTask;
+typedef GenericFunctionDiagnosticTask<diagnostic_msgs::DiagnosticStatus> UnwrappedFunctionDiagnosticTask;
typedef GenericFunctionDiagnosticTask<DiagnosticStatusWrapper> FunctionDiagnosticTask;
/**
@@ -290,7 +290,7 @@
if (node_handle_.ok())
{
- std::vector<robot_msgs::DiagnosticStatus> status_vec;
+ std::vector<diagnostic_msgs::DiagnosticStatus> status_vec;
boost::mutex::scoped_lock lock(lock_); // Make sure no adds happen while we are processing here.
const std::vector<DiagnosticTaskInternal> &tasks = getTasks();
@@ -327,13 +327,13 @@
ros::NodeHandle newnh;
node_handle_ = newnh;
- publisher_ = node_handle_.advertise<robot_msgs::DiagnosticMessage>("/diagnostics", 1);
+ publisher_ = node_handle_.advertise<diagnostic_msgs::DiagnosticMessage>("/diagnostics", 1);
broadcast(2...
[truncated message content] |