Classes | Public Member Functions | Private Member Functions | Private Attributes | List of all members
spinnaker_camera_driver::DiagnosticsManager Class Reference

#include <diagnostics.h>

Classes

struct  diagnostic_params
 

Public Member Functions

template<typename T >
void addDiagnostic (const Spinnaker::GenICam::gcstring name)
 Add a diagnostic with name only (no warning checks) More...
 
void addDiagnostic (const Spinnaker::GenICam::gcstring name, bool check_ranges=false, std::pair< int, int > operational=std::make_pair(0, 0), int lower_bound=0, int upper_bound=0)
 Add a diagnostic with warning checks. More...
 
void addDiagnostic (const Spinnaker::GenICam::gcstring name, bool check_ranges=false, std::pair< float, float > operational=std::make_pair(0.0, 0.0), float lower_bound=0, float upper_bound=0)
 
 DiagnosticsManager (const std::string name, const std::string serial, std::shared_ptr< ros::Publisher > const &pub)
 
void processDiagnostics (SpinnakerCamera *spinnaker)
 Read the property of given parameters and push to aggregator. More...
 
 ~DiagnosticsManager ()
 

Private Member Functions

template<typename T >
diagnostic_msgs::DiagnosticStatus getDiagStatus (const diagnostic_params< T > &param, const T value)
 Function to push the diagnostic to the publisher. More...
 

Private Attributes

std::string camera_name_
 
std::shared_ptr< ros::Publisherdiagnostics_pub_
 
std::vector< diagnostic_params< float > > float_params_
 
std::vector< diagnostic_params< int > > integer_params_
 
const std::vector< std::string > manufacturer_params_
 
std::string serial_number_
 

Detailed Description

Definition at line 56 of file diagnostics.h.

Constructor & Destructor Documentation

spinnaker_camera_driver::DiagnosticsManager::DiagnosticsManager ( const std::string  name,
const std::string  serial,
std::shared_ptr< ros::Publisher > const &  pub 
)

Definition at line 38 of file diagnostics.cpp.

spinnaker_camera_driver::DiagnosticsManager::~DiagnosticsManager ( )

Definition at line 44 of file diagnostics.cpp.

Member Function Documentation

template<typename T >
void spinnaker_camera_driver::DiagnosticsManager::addDiagnostic ( const Spinnaker::GenICam::gcstring  name)

Add a diagnostic with name only (no warning checks)

Allows the user to add an integer or float parameter without having to give additional information. User must specify the type they are getting

Parameters
nameis the name of the parameter as writting in the User Manual

Definition at line 49 of file diagnostics.cpp.

void spinnaker_camera_driver::DiagnosticsManager::addDiagnostic ( const Spinnaker::GenICam::gcstring  name,
bool  check_ranges = false,
std::pair< int, int >  operational = std::make_pair(0, 0),
int  lower_bound = 0,
int  upper_bound = 0 
)

Add a diagnostic with warning checks.

Allows the user to add an integer or float parameter and values to check it against. Anything outside of these ranges will be considered an error.

Parameters
nameis the name of the parameter as writting in the User Manual

Definition at line 61 of file diagnostics.cpp.

void spinnaker_camera_driver::DiagnosticsManager::addDiagnostic ( const Spinnaker::GenICam::gcstring  name,
bool  check_ranges = false,
std::pair< float, float >  operational = std::make_pair(0.0, 0.0),
float  lower_bound = 0,
float  upper_bound = 0 
)

Definition at line 68 of file diagnostics.cpp.

template<typename T >
diagnostic_msgs::DiagnosticStatus spinnaker_camera_driver::DiagnosticsManager::getDiagStatus ( const diagnostic_params< T > &  param,
const T  value 
)
private

Function to push the diagnostic to the publisher.

Allows the user to add an integer or float parameter without having to give additional information. User must specify the type they are getting

Parameters
paramis the diagnostic parameter name and boundaries
valueis the current value of the parameter requested from the device

Definition at line 76 of file diagnostics.cpp.

void spinnaker_camera_driver::DiagnosticsManager::processDiagnostics ( SpinnakerCamera spinnaker)

Read the property of given parameters and push to aggregator.

Take all the collected parameters that were added read the values, then publish them to the allow the diagnostics aggreagtor to collect them

Parameters
spinnakerthe SpinnakerCamera object used for getting the parameters from the spinnaker API

Definition at line 107 of file diagnostics.cpp.

Member Data Documentation

std::string spinnaker_camera_driver::DiagnosticsManager::camera_name_
private

Definition at line 127 of file diagnostics.h.

std::shared_ptr<ros::Publisher> spinnaker_camera_driver::DiagnosticsManager::diagnostics_pub_
private

Definition at line 129 of file diagnostics.h.

std::vector<diagnostic_params<float> > spinnaker_camera_driver::DiagnosticsManager::float_params_
private

Definition at line 133 of file diagnostics.h.

std::vector<diagnostic_params<int> > spinnaker_camera_driver::DiagnosticsManager::integer_params_
private

Definition at line 132 of file diagnostics.h.

const std::vector<std::string> spinnaker_camera_driver::DiagnosticsManager::manufacturer_params_
private
Initial value:
{
"DeviceVendorName", "DeviceModelName", "SensorDescription", "DeviceFirmwareVersion"
}

Definition at line 138 of file diagnostics.h.

std::string spinnaker_camera_driver::DiagnosticsManager::serial_number_
private

Definition at line 128 of file diagnostics.h.


The documentation for this class was generated from the following files:


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