Aggregator processes /diagnostics, republishes on /diagnostics_agg. More...
#include <aggregator.h>
Public Member Functions | |
Aggregator () | |
Constructor initializes with main prefix (ex: '/Robot'). | |
double | getPubRate () const |
Publish rate defaults to 1Hz, but can be set with ~pub_rate param. | |
bool | ok () const |
True if the NodeHandle reports OK. | |
void | publishData () |
Processes, publishes data. Should be called at pub_rate. | |
~Aggregator () | |
Private Member Functions | |
void | checkTimestamp (const diagnostic_msgs::DiagnosticArray::ConstPtr &diag_msg) |
void | diagCallback (const diagnostic_msgs::DiagnosticArray::ConstPtr &diag_msg) |
Callback for incoming "/diagnostics". | |
Private Attributes | |
ros::Publisher | agg_pub_ |
AnalyzerGroup * | analyzer_group_ |
std::string | base_path_ |
Prepended to all status names of aggregator. | |
ros::Subscriber | diag_sub_ |
ros::NodeHandle | n_ |
OtherAnalyzer * | other_analyzer_ |
double | pub_rate_ |
std::set< std::string > | ros_warnings_ |
Records all ROS warnings. No warnings are repeated. |
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 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 parametes 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 99 of file aggregator.h.
Aggregator::Aggregator | ( | ) |
Constructor initializes with main prefix (ex: '/Robot').
Definition at line 42 of file aggregator.cpp.
Aggregator::~Aggregator | ( | ) |
Definition at line 109 of file aggregator.cpp.
void Aggregator::checkTimestamp | ( | const diagnostic_msgs::DiagnosticArray::ConstPtr & | diag_msg | ) | [private] |
Definition at line 71 of file aggregator.cpp.
void Aggregator::diagCallback | ( | const diagnostic_msgs::DiagnosticArray::ConstPtr & | diag_msg | ) | [private] |
Callback for incoming "/diagnostics".
Definition at line 92 of file aggregator.cpp.
double diagnostic_aggregator::Aggregator::getPubRate | ( | ) | const [inline] |
Publish rate defaults to 1Hz, but can be set with ~pub_rate param.
Definition at line 78 of file aggregator.h.
bool diagnostic_aggregator::Aggregator::ok | ( | ) | const [inline] |
True if the NodeHandle reports OK.
Definition at line 73 of file aggregator.h.
void Aggregator::publishData | ( | ) |
Processes, publishes data. Should be called at pub_rate.
Definition at line 116 of file aggregator.cpp.
ros::Publisher diagnostic_aggregator::Aggregator::agg_pub_ [private] |
DiagnosticArray, /diagnostics_agg
Definition at line 83 of file aggregator.h.
Definition at line 91 of file aggregator.h.
std::string diagnostic_aggregator::Aggregator::base_path_ [private] |
Prepended to all status names of aggregator.
Definition at line 95 of file aggregator.h.
ros::Subscriber diagnostic_aggregator::Aggregator::diag_sub_ [private] |
DiagnosticArray, /diagnostics
Definition at line 82 of file aggregator.h.
ros::NodeHandle diagnostic_aggregator::Aggregator::n_ [private] |
Definition at line 81 of file aggregator.h.
Definition at line 93 of file aggregator.h.
double diagnostic_aggregator::Aggregator::pub_rate_ [private] |
Definition at line 84 of file aggregator.h.
std::set<std::string> diagnostic_aggregator::Aggregator::ros_warnings_ [private] |
Records all ROS warnings. No warnings are repeated.
Definition at line 97 of file aggregator.h.