DiscardAnalyzer is does not report any values. It is a subclass of GenericAnalyzer. More...
#include <discard_analyzer.h>
Public Member Functions | |
DiscardAnalyzer () | |
Default constructor loaded by pluginlib. More... | |
virtual std::vector< boost::shared_ptr< diagnostic_msgs::DiagnosticStatus > > | report () |
Reports current state, returns vector of formatted status messages. More... | |
virtual | ~DiscardAnalyzer () |
Public Member Functions inherited from diagnostic_aggregator::GenericAnalyzer | |
GenericAnalyzer () | |
Default constructor loaded by pluginlib. More... | |
bool | init (const std::string base_path, const ros::NodeHandle &n) |
Initializes GenericAnalyzer from namespace. Returns true if s. More... | |
virtual bool | match (const std::string name) |
Returns true if item matches any of the given criteria. More... | |
virtual | ~GenericAnalyzer () |
Public Member Functions inherited from diagnostic_aggregator::GenericAnalyzerBase | |
virtual bool | analyze (const boost::shared_ptr< StatusItem > item) |
Update state with new StatusItem. More... | |
GenericAnalyzerBase () | |
virtual std::string | getName () const |
Returns nice name (ex: "Power System") More... | |
virtual std::string | getPath () const |
Returns full prefix (ex: "/Robot/Power System") More... | |
bool | init (const std::string path, const std::string nice_name, double timeout=-1.0, int num_items_expected=-1, bool discard_stale=false) |
virtual | ~GenericAnalyzerBase () |
Public Member Functions inherited from diagnostic_aggregator::Analyzer | |
Analyzer () | |
Default constructor, called by pluginlib. More... | |
virtual | ~Analyzer () |
Additional Inherited Members | |
Protected Member Functions inherited from diagnostic_aggregator::GenericAnalyzerBase | |
void | addItem (std::string name, boost::shared_ptr< StatusItem > item) |
Subclasses can add items to analyze. More... | |
Protected Attributes inherited from diagnostic_aggregator::GenericAnalyzerBase | |
std::string | nice_name_ |
int | num_items_expected_ |
std::string | path_ |
double | timeout_ |
DiscardAnalyzer is does not report any values. It is a subclass of GenericAnalyzer.
DiscardAnalyzer is a subclass of GenericAnalyzer. It will ignore any value that it matches. It takes the any of the parameters of a GenericAnalyzer.
It is useful for configuring an aggregator_node to ignore certain values in the diagnostics.
*<launch> * <include file="$(find my_pkg)/my_analyzers.launch" /> * * <!-- Overwrite a specific Analyzer to discard all --> * <param name="diag_agg/analyzers/motors/type" value="DiscardAnalyzer" /> *</launch> *
Definition at line 68 of file discard_analyzer.h.
diagnostic_aggregator::DiscardAnalyzer::DiscardAnalyzer | ( | ) |
Default constructor loaded by pluginlib.
|
virtual |
Definition at line 49 of file discard_analyzer.cpp.
|
virtual |
Reports current state, returns vector of formatted status messages.
Reimplemented from diagnostic_aggregator::GenericAnalyzer.
Definition at line 53 of file discard_analyzer.cpp.