diff --git a/CMakeLists.txt b/CMakeLists.txt index 9a3b0bf4..e0726870 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -9,12 +9,12 @@ set( camera_control_msgs camera_info_manager cv_bridge + diagnostic_updater image_geometry image_transport roscpp roslaunch sensor_msgs - #std_srvs ) find_package(Pylon QUIET) diff --git a/include/pylon_camera/pylon_camera_node.h b/include/pylon_camera/pylon_camera_node.h index 66386fc4..7bd70550 100644 --- a/include/pylon_camera/pylon_camera_node.h +++ b/include/pylon_camera/pylon_camera_node.h @@ -53,6 +53,9 @@ #include #include +#include +#include + namespace pylon_camera { @@ -372,6 +375,13 @@ class PylonCameraNode bool is_sleeping_; boost::recursive_mutex grab_mutex_; + + /// diagnostics: + diagnostic_updater::Updater diagnostics_updater_; + void diagnostics_timer_callback_(const ros::TimerEvent&); + ros::Timer diagnostics_trigger_; + void create_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat); + void create_camera_info_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat); }; } // namespace pylon_camera diff --git a/package.xml b/package.xml index 6144b360..9f545efe 100644 --- a/package.xml +++ b/package.xml @@ -25,6 +25,7 @@ camera_control_msgs camera_info_manager cv_bridge + diagnostic_updater image_geometry image_transport pylon @@ -37,6 +38,7 @@ actionlib camera_control_msgs camera_info_manager + diagnostic_updater cv_bridge image_geometry image_transport diff --git a/src/pylon_camera/pylon_camera_node.cpp b/src/pylon_camera/pylon_camera_node.cpp index c3227dcd..6e38f1bc 100644 --- a/src/pylon_camera/pylon_camera_node.cpp +++ b/src/pylon_camera/pylon_camera_node.cpp @@ -34,6 +34,8 @@ #include #include "boost/multi_array.hpp" +using diagnostic_msgs::DiagnosticStatus; + namespace pylon_camera { @@ -81,9 +83,48 @@ PylonCameraNode::PylonCameraNode() brightness_exp_lut_(), is_sleeping_(false) { + diagnostics_updater_.setHardwareID("none"); + diagnostics_updater_.add("camera_availability", this, &PylonCameraNode::create_diagnostics); + diagnostics_updater_.add("intrinsic_calibration", this, &PylonCameraNode::create_camera_info_diagnostics); + diagnostics_trigger_ = nh_.createTimer(ros::Duration(2), &PylonCameraNode::diagnostics_timer_callback_, this); + init(); } +void PylonCameraNode::create_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + if (pylon_camera_parameter_set_.deviceUserID().empty()) + { + return; + } + + if (pylon_camera_) + { + diagnostics_updater_.setHardwareID( pylon_camera_->deviceUserID()); + stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Device is connected"); + } + else + { + diagnostics_updater_.setHardwareID(pylon_camera_parameter_set_.deviceUserID()); + stat.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "No camera connected"); + } +} + +void PylonCameraNode::create_camera_info_diagnostics(diagnostic_updater::DiagnosticStatusWrapper &stat) +{ + if (camera_info_manager_->isCalibrated()) + { + stat.summaryf(DiagnosticStatus::OK, "Intrinsic calibration found"); + }else{ + stat.summaryf(DiagnosticStatus::ERROR, "No intrinsic calibration found"); + } +} + +void PylonCameraNode::diagnostics_timer_callback_(const ros::TimerEvent&) +{ + diagnostics_updater_.update(); +} + void PylonCameraNode::init() { // reading all necessary parameter to open the desired camera from the