diagnostics.h
Go to the documentation of this file.
1 
31 /*-*-C++-*-*/
41 #ifndef SPINNAKER_CAMERA_DRIVER_DIAGNOSTICS_H
42 #define SPINNAKER_CAMERA_DRIVER_DIAGNOSTICS_H
43 
46 #include <diagnostic_msgs/DiagnosticArray.h>
47 #include <diagnostic_msgs/DiagnosticStatus.h>
48 #include <diagnostic_msgs/AddDiagnostics.h>
49 #include <ros/ros.h>
50 #include <bondcpp/bond.h>
51 
52 #include <memory>
53 #include <string>
54 #include <utility>
55 #include <vector>
56 
58 {
60 {
61 public:
62  DiagnosticsManager(const std::string name, const std::string serial,
63  std::shared_ptr<ros::Publisher> const& pub,
64  const ros::NodeHandle& nh);
66 
76  void processDiagnostics(SpinnakerCamera* spinnaker);
77 
86  template <typename T>
87  void addDiagnostic(const Spinnaker::GenICam::gcstring name);
88 
97  void addDiagnostic(const Spinnaker::GenICam::gcstring name, bool check_ranges = false,
98  std::pair<int, int> operational = std::make_pair(0, 0), int lower_bound = 0, int upper_bound = 0);
99  void addDiagnostic(const Spinnaker::GenICam::gcstring name, bool check_ranges = false,
100  std::pair<float, float> operational = std::make_pair(0.0, 0.0), float lower_bound = 0,
101  float upper_bound = 0);
102 
103  void addAnalyzers();
104 
105 private:
106  /*
107  * diagnostic_params is aData Structure to represent a parameter and its
108  * bounds
109  */
110  template <typename T>
112  {
113  Spinnaker::GenICam::gcstring parameter_name; // This should be the same as written in the User Manual
115  std::pair<T, T> operational_range; // Normal operatinal range
118  };
119 
130  template <typename T>
131  diagnostic_msgs::DiagnosticStatus getDiagStatus(const diagnostic_params<T>& param, const T value);
132 
133  // constuctor parameters
134  std::string camera_name_;
135  std::string serial_number_;
136  std::shared_ptr<ros::Publisher> diagnostics_pub_;
138  std::shared_ptr<bond::Bond> bond_ = nullptr;
139 
140  // vectors to keep track of the items to publish
141  std::vector<diagnostic_params<int>> integer_params_;
142  std::vector<diagnostic_params<float>> float_params_;
143  // Information about the device model, firmware, etc
144  // TODO(mlowe): Allow these to be configured
145  // clang-format off
146  const std::vector<std::string> manufacturer_params_
147  {
148  "DeviceVendorName", "DeviceModelName", "SensorDescription", "DeviceFirmwareVersion"
149  };
150  // clang-format on
151 };
152 } // namespace spinnaker_camera_driver
153 
154 #endif // SPINNAKER_CAMERA_DRIVER_DIAGNOSTICS_H
spinnaker_camera_driver::DiagnosticsManager
Definition: diagnostics.h:59
spinnaker_camera_driver::DiagnosticsManager::nh_
ros::NodeHandle nh_
Definition: diagnostics.h:137
spinnaker_camera_driver::DiagnosticsManager::diagnostics_pub_
std::shared_ptr< ros::Publisher > diagnostics_pub_
Definition: diagnostics.h:136
spinnaker_camera_driver::DiagnosticsManager::diagnostic_params
Definition: diagnostics.h:111
spinnaker_camera_driver::DiagnosticsManager::processDiagnostics
void processDiagnostics(SpinnakerCamera *spinnaker)
Read the property of given parameters and push to aggregator.
Definition: diagnostics.cpp:196
spinnaker_camera_driver::SpinnakerCamera
Definition: SpinnakerCamera.h:69
spinnaker_camera_driver::DiagnosticsManager::float_params_
std::vector< diagnostic_params< float > > float_params_
Definition: diagnostics.h:142
ros.h
spinnaker_camera_driver::DiagnosticsManager::DiagnosticsManager
DiagnosticsManager(const std::string name, const std::string serial, std::shared_ptr< ros::Publisher > const &pub, const ros::NodeHandle &nh)
Definition: diagnostics.cpp:39
bond.h
spinnaker_camera_driver::DiagnosticsManager::manufacturer_params_
const std::vector< std::string > manufacturer_params_
Definition: diagnostics.h:147
spinnaker_camera_driver::DiagnosticsManager::~DiagnosticsManager
~DiagnosticsManager()
Definition: diagnostics.cpp:46
spinnaker_camera_driver::DiagnosticsManager::camera_name_
std::string camera_name_
Definition: diagnostics.h:134
spinnaker_camera_driver
Definition: camera.h:45
spinnaker_camera_driver::DiagnosticsManager::diagnostic_params::check_ranges
bool check_ranges
Definition: diagnostics.h:114
spinnaker_camera_driver::DiagnosticsManager::diagnostic_params::operational_range
std::pair< T, T > operational_range
Definition: diagnostics.h:115
spinnaker_camera_driver::DiagnosticsManager::getDiagStatus
diagnostic_msgs::DiagnosticStatus getDiagStatus(const diagnostic_params< T > &param, const T value)
Function to push the diagnostic to the publisher.
Definition: diagnostics.cpp:150
spinnaker_camera_driver::DiagnosticsManager::bond_
std::shared_ptr< bond::Bond > bond_
Definition: diagnostics.h:138
diagnostics.h
Class to support ROS Diagnostics Aggregator for Spinnaker Camera.
spinnaker_camera_driver::DiagnosticsManager::addAnalyzers
void addAnalyzers()
Definition: diagnostics.cpp:77
spinnaker_camera_driver::DiagnosticsManager::diagnostic_params::warn_range_lower
T warn_range_lower
Definition: diagnostics.h:116
spinnaker_camera_driver::DiagnosticsManager::diagnostic_params::warn_range_upper
T warn_range_upper
Definition: diagnostics.h:117
spinnaker_camera_driver::DiagnosticsManager::integer_params_
std::vector< diagnostic_params< int > > integer_params_
Definition: diagnostics.h:141
spinnaker_camera_driver::DiagnosticsManager::serial_number_
std::string serial_number_
Definition: diagnostics.h:135
spinnaker_camera_driver::DiagnosticsManager::diagnostic_params::parameter_name
Spinnaker::GenICam::gcstring parameter_name
Definition: diagnostics.h:113
SpinnakerCamera.h
Interface to Point Grey cameras.
ros::NodeHandle
spinnaker_camera_driver::DiagnosticsManager::addDiagnostic
void addDiagnostic(const Spinnaker::GenICam::gcstring name)
Add a diagnostic with name only (no warning checks)
Definition: diagnostics.cpp:51


spinnaker_camera_driver
Author(s): Chad Rockey
autogenerated on Mon Sep 25 2023 02:56:14