Public Member Functions | Private Member Functions | Private Attributes | List of all members
diagnostic_aggregator::Aggregator Class Reference

Aggregator processes /diagnostics, republishes on /diagnostics_agg. More...

#include <aggregator.h>

Public Member Functions

 Aggregator ()
 Constructor initializes with main prefix (ex: '/Robot') More...
 
double getPubRate () const
 Publish rate defaults to 1Hz, but can be set with ~pub_rate param. More...
 
bool ok () const
 True if the NodeHandle reports OK. More...
 
void publishData ()
 Processes, publishes data. Should be called at pub_rate. More...
 
 ~Aggregator ()
 

Private Member Functions

bool addDiagnostics (diagnostic_msgs::AddDiagnostics::Request &req, diagnostic_msgs::AddDiagnostics::Response &res)
 Service request callback for addition of diagnostics. Creates a bond between the calling node and the aggregator, and loads information about new diagnostics into added_analyzers_, keeping track of the formed bond in bonds_. More...
 
void bondBroken (std::string bond_id, boost::shared_ptr< Analyzer > analyzer)
 
void bondFormed (boost::shared_ptr< Analyzer > group)
 
void checkTimestamp (const diagnostic_msgs::DiagnosticArray::ConstPtr &diag_msg)
 
void diagCallback (const diagnostic_msgs::DiagnosticArray::ConstPtr &diag_msg)
 Callback for incoming "/diagnostics". More...
 

Private Attributes

ros::ServiceServer add_srv_
 
ros::Publisher agg_pub_
 
AnalyzerGroupanalyzer_group_
 
std::string base_path_
 Prepended to all status names of aggregator. More...
 
std::vector< boost::shared_ptr< bond::Bond > > bonds_
 Contains all bonds for additional diagnostics. More...
 
ros::Subscriber diag_sub_
 
boost::mutex mutex_
 
ros::NodeHandle n_
 
OtherAnalyzerother_analyzer_
 
double pub_rate_
 
std::set< std::string > ros_warnings_
 Records all ROS warnings. No warnings are repeated. More...
 
ros::Publisher toplevel_state_pub_
 

Detailed Description

Aggregator processes /diagnostics, republishes on /diagnostics_agg.

Aggregator is a node that subscribes to /diagnostics, processes it and republishes aggregated data on /diagnostics_agg. The aggregator creates a series of analyzers according to the specifications of its private parameters. The aggregated diagnostics data is organized in a tree structure. For example:

Input (status names):
  tilt_hokuyo_node: Frequency
  tilt_hokuyo_node: Connection
Output:
  /Robot
  /Robot/Sensors
  /Robot/Sensors/Tilt Hokuyo/Frequency
  /Robot/Sensors/Tilt Hokuyo/Connection

The analyzer should always output a DiagnosticStatus with the name of the prefix. Any other data output is up to the analyzer developer.

Analyzer's are loaded by specifying the private parameters of the aggregator.

base_path: My Robot
pub_rate: 1.0
other_as_errors: false
analyzers:
  sensors:
    type: GenericAnalyzer
    path: Tilt Hokuyo
    find_and_remove_prefix: tilt_hokuyo_node
  motors:
    type: PR2MotorsAnalyzer
  joints:
    type: PR2JointsAnalyzer

Each analyzer is created according to the "type" parameter in its namespace. Any other parameters in the namespace can by used to specify the analyzer. If any analyzer is not properly specified, or returns false on initialization, the aggregator will report the error and publish it in the aggregated output.

Definition at line 137 of file aggregator.h.

Constructor & Destructor Documentation

◆ Aggregator()

Aggregator::Aggregator ( )

Constructor initializes with main prefix (ex: '/Robot')

Definition at line 42 of file aggregator.cpp.

◆ ~Aggregator()

Aggregator::~Aggregator ( )

Definition at line 117 of file aggregator.cpp.

Member Function Documentation

◆ addDiagnostics()

bool Aggregator::addDiagnostics ( diagnostic_msgs::AddDiagnostics::Request &  req,
diagnostic_msgs::AddDiagnostics::Response &  res 
)
private

Service request callback for addition of diagnostics. Creates a bond between the calling node and the aggregator, and loads information about new diagnostics into added_analyzers_, keeping track of the formed bond in bonds_.

Definition at line 151 of file aggregator.cpp.

◆ bondBroken()

void Aggregator::bondBroken ( std::string  bond_id,
boost::shared_ptr< Analyzer analyzer 
)
private

Definition at line 125 of file aggregator.cpp.

◆ bondFormed()

void Aggregator::bondFormed ( boost::shared_ptr< Analyzer group)
private

Definition at line 144 of file aggregator.cpp.

◆ checkTimestamp()

void Aggregator::checkTimestamp ( const diagnostic_msgs::DiagnosticArray::ConstPtr &  diag_msg)
private

Definition at line 74 of file aggregator.cpp.

◆ diagCallback()

void Aggregator::diagCallback ( const diagnostic_msgs::DiagnosticArray::ConstPtr &  diag_msg)
private

Callback for incoming "/diagnostics".

Definition at line 95 of file aggregator.cpp.

◆ getPubRate()

double diagnostic_aggregator::Aggregator::getPubRate ( ) const
inline

Publish rate defaults to 1Hz, but can be set with ~pub_rate param.

Definition at line 192 of file aggregator.h.

◆ ok()

bool diagnostic_aggregator::Aggregator::ok ( ) const
inline

True if the NodeHandle reports OK.

Definition at line 187 of file aggregator.h.

◆ publishData()

void Aggregator::publishData ( )

Processes, publishes data. Should be called at pub_rate.

Definition at line 202 of file aggregator.cpp.

Member Data Documentation

◆ add_srv_

ros::ServiceServer diagnostic_aggregator::Aggregator::add_srv_
private

AddDiagnostics, /diagnostics_agg/add_diagnostics

Definition at line 196 of file aggregator.h.

◆ agg_pub_

ros::Publisher diagnostic_aggregator::Aggregator::agg_pub_
private

DiagnosticArray, /diagnostics_agg

Definition at line 198 of file aggregator.h.

◆ analyzer_group_

AnalyzerGroup* diagnostic_aggregator::Aggregator::analyzer_group_
private

Definition at line 217 of file aggregator.h.

◆ base_path_

std::string diagnostic_aggregator::Aggregator::base_path_
private

Prepended to all status names of aggregator.

Definition at line 244 of file aggregator.h.

◆ bonds_

std::vector<boost::shared_ptr<bond::Bond> > diagnostic_aggregator::Aggregator::bonds_
private

Contains all bonds for additional diagnostics.

Definition at line 221 of file aggregator.h.

◆ diag_sub_

ros::Subscriber diagnostic_aggregator::Aggregator::diag_sub_
private

DiagnosticArray, /diagnostics

Definition at line 197 of file aggregator.h.

◆ mutex_

boost::mutex diagnostic_aggregator::Aggregator::mutex_
private

Definition at line 200 of file aggregator.h.

◆ n_

ros::NodeHandle diagnostic_aggregator::Aggregator::n_
private

Definition at line 195 of file aggregator.h.

◆ other_analyzer_

OtherAnalyzer* diagnostic_aggregator::Aggregator::other_analyzer_
private

Definition at line 219 of file aggregator.h.

◆ pub_rate_

double diagnostic_aggregator::Aggregator::pub_rate_
private

Definition at line 201 of file aggregator.h.

◆ ros_warnings_

std::set<std::string> diagnostic_aggregator::Aggregator::ros_warnings_
private

Records all ROS warnings. No warnings are repeated.

Definition at line 246 of file aggregator.h.

◆ toplevel_state_pub_

ros::Publisher diagnostic_aggregator::Aggregator::toplevel_state_pub_
private

DiagnosticStatus, /diagnostics_toplevel_state

Definition at line 199 of file aggregator.h.


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


diagnostic_aggregator
Author(s): Kevin Watts, Brice Rebsamen
autogenerated on Tue Nov 15 2022 03:17:13