39 #ifndef OTHER_ANALYZER_H 40 #define OTHER_ANALYZER_H 89 ROS_ERROR(
"OtherAnalyzer was attempted to initialize with a NodeHandle. This analyzer cannot be used as a plugin.");
104 std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> >
report()
109 if (processed.size() == 1)
116 std::vector<boost::shared_ptr<diagnostic_msgs::DiagnosticStatus> >::iterator it = processed.begin();
117 for (; it != processed.end(); ++it)
119 if ((*it)->name ==
path_)
122 (*it)->message =
"Unanalyzed items found in \"Other\"";
138 #endif // OTHER_ANALYZER_H
bool match(std::string name)
Match function isn't implemented by GenericAnalyzerBase.
bool init(std::string path)
virtual std::vector< boost::shared_ptr< diagnostic_msgs::DiagnosticStatus > > report()
Reports current state, returns vector of formatted status messages.
std::vector< boost::shared_ptr< diagnostic_msgs::DiagnosticStatus > > report()
Reports current state, returns vector of formatted status messages.
bool init(const std::string path, const ros::NodeHandle &n)=0
Analyzer is initialized with base path and namespace.
OtherAnalyzer(bool other_as_errors=false)
Default constructor. OtherAnalyzer isn't loaded by pluginlib.
bool init(const std::string base_path, const ros::NodeHandle &n)
Analyzer is initialized with base path and namespace.
GenericAnalyzerBase is the base class for GenericAnalyzer and OtherAnalyzer.