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

void addAnalyzers ()
 
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< float, float > operational=std::make_pair(0.0, 0.0), float lower_bound=0, float upper_bound=0)
 
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...
 
 DiagnosticsManager (const std::string name, const std::string serial, std::shared_ptr< ros::Publisher > const &pub, const ros::NodeHandle &nh)
 
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::shared_ptr< bond::Bondbond_ = nullptr
 
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_
 
ros::NodeHandle nh_
 
std::string serial_number_
 

Detailed Description

Definition at line 59 of file diagnostics.h.

Constructor & Destructor Documentation

◆ DiagnosticsManager()

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

Definition at line 39 of file diagnostics.cpp.

◆ ~DiagnosticsManager()

spinnaker_camera_driver::DiagnosticsManager::~DiagnosticsManager ( )

Definition at line 46 of file diagnostics.cpp.

Member Function Documentation

◆ addAnalyzers()

void spinnaker_camera_driver::DiagnosticsManager::addAnalyzers ( )

Definition at line 77 of file diagnostics.cpp.

◆ addDiagnostic() [1/3]

template<typename T >
template void spinnaker_camera_driver::DiagnosticsManager::addDiagnostic< float > ( 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 51 of file diagnostics.cpp.

◆ addDiagnostic() [2/3]

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 70 of file diagnostics.cpp.

◆ addDiagnostic() [3/3]

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 63 of file diagnostics.cpp.

◆ getDiagStatus()

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 150 of file diagnostics.cpp.

◆ processDiagnostics()

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 196 of file diagnostics.cpp.

Member Data Documentation

◆ bond_

std::shared_ptr<bond::Bond> spinnaker_camera_driver::DiagnosticsManager::bond_ = nullptr
private

Definition at line 138 of file diagnostics.h.

◆ camera_name_

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

Definition at line 134 of file diagnostics.h.

◆ diagnostics_pub_

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

Definition at line 136 of file diagnostics.h.

◆ float_params_

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

Definition at line 142 of file diagnostics.h.

◆ integer_params_

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

Definition at line 141 of file diagnostics.h.

◆ manufacturer_params_

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

Definition at line 147 of file diagnostics.h.

◆ nh_

ros::NodeHandle spinnaker_camera_driver::DiagnosticsManager::nh_
private

Definition at line 137 of file diagnostics.h.

◆ serial_number_

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

Definition at line 135 of file diagnostics.h.


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


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