41 #ifndef SPINNAKER_CAMERA_DRIVER_DIAGNOSTICS_H    42 #define SPINNAKER_CAMERA_DRIVER_DIAGNOSTICS_H    46 #include <diagnostic_msgs/DiagnosticArray.h>    47 #include <diagnostic_msgs/DiagnosticStatus.h>    59   DiagnosticsManager(
const std::string name, 
const std::string serial, std::shared_ptr<ros::Publisher> 
const& pub);
    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);
   103   template <
typename T>
   123   template <
typename T>
   139     "DeviceVendorName", 
"DeviceModelName", 
"SensorDescription", 
"DeviceFirmwareVersion"   145 #endif  // SPINNAKER_CAMERA_DRIVER_DIAGNOSTICS_H 
Spinnaker::GenICam::gcstring parameter_name
diagnostic_msgs::DiagnosticStatus getDiagStatus(const diagnostic_params< T > ¶m, const T value)
Function to push the diagnostic to the publisher. 
std::vector< diagnostic_params< int > > integer_params_
void addDiagnostic(const Spinnaker::GenICam::gcstring name)
Add a diagnostic with name only (no warning checks) 
std::shared_ptr< ros::Publisher > diagnostics_pub_
DiagnosticsManager(const std::string name, const std::string serial, std::shared_ptr< ros::Publisher > const &pub)
Class to support ROS Diagnostics Aggregator for Spinnaker Camera. 
std::vector< diagnostic_params< float > > float_params_
void processDiagnostics(SpinnakerCamera *spinnaker)
Read the property of given parameters and push to aggregator. 
std::string serial_number_
std::pair< T, T > operational_range
Interface to Point Grey cameras. 
const std::vector< std::string > manufacturer_params_