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 <ros/ros.h>
49 
50 #include <utility>
51 #include <string>
52 #include <vector>
53 
55 {
57 {
58 public:
59  DiagnosticsManager(const std::string name, const std::string serial, std::shared_ptr<ros::Publisher> const& pub);
61 
71  void processDiagnostics(SpinnakerCamera* spinnaker);
72 
81  template <typename T>
82  void addDiagnostic(const Spinnaker::GenICam::gcstring name);
83 
92  void addDiagnostic(const Spinnaker::GenICam::gcstring name, bool check_ranges = false,
93  std::pair<int, int> operational = std::make_pair(0, 0), int lower_bound = 0, int upper_bound = 0);
94  void addDiagnostic(const Spinnaker::GenICam::gcstring name, bool check_ranges = false,
95  std::pair<float, float> operational = std::make_pair(0.0, 0.0), float lower_bound = 0,
96  float upper_bound = 0);
97 
98 private:
99  /*
100  * diagnostic_params is aData Structure to represent a parameter and its
101  * bounds
102  */
103  template <typename T>
105  {
106  Spinnaker::GenICam::gcstring parameter_name; // This should be the same as written in the User Manual
108  std::pair<T, T> operational_range; // Normal operatinal range
111  };
112 
123  template <typename T>
124  diagnostic_msgs::DiagnosticStatus getDiagStatus(const diagnostic_params<T>& param, const T value);
125 
126  // constuctor parameters
127  std::string camera_name_;
128  std::string serial_number_;
129  std::shared_ptr<ros::Publisher> diagnostics_pub_;
130 
131  // vectors to keep track of the items to publish
132  std::vector<diagnostic_params<int>> integer_params_;
133  std::vector<diagnostic_params<float>> float_params_;
134  // Information about the device model, firmware, etc
135  // TODO(mlowe): Allow these to be configured
136  // clang-format off
137  const std::vector<std::string> manufacturer_params_
138  {
139  "DeviceVendorName", "DeviceModelName", "SensorDescription", "DeviceFirmwareVersion"
140  };
141  // clang-format on
142 };
143 } // namespace spinnaker_camera_driver
144 
145 #endif // SPINNAKER_CAMERA_DRIVER_DIAGNOSTICS_H
diagnostic_msgs::DiagnosticStatus getDiagStatus(const diagnostic_params< T > &param, const T value)
Function to push the diagnostic to the publisher.
Definition: diagnostics.cpp:76
std::vector< diagnostic_params< int > > integer_params_
Definition: diagnostics.h:132
void addDiagnostic(const Spinnaker::GenICam::gcstring name)
Add a diagnostic with name only (no warning checks)
Definition: diagnostics.cpp:49
std::shared_ptr< ros::Publisher > diagnostics_pub_
Definition: diagnostics.h:129
DiagnosticsManager(const std::string name, const std::string serial, std::shared_ptr< ros::Publisher > const &pub)
Definition: diagnostics.cpp:38
Class to support ROS Diagnostics Aggregator for Spinnaker Camera.
std::vector< diagnostic_params< float > > float_params_
Definition: diagnostics.h:133
void processDiagnostics(SpinnakerCamera *spinnaker)
Read the property of given parameters and push to aggregator.
Interface to Point Grey cameras.
const std::vector< std::string > manufacturer_params_
Definition: diagnostics.h:138


spinnaker_camera_driver
Author(s): Chad Rockey
autogenerated on Sun Feb 14 2021 03:47:26