#include <diagnostic_parser.hpp>
Public Member Functions | |
| DiagnosticParser (self_test::TestRunner *test_runner) | |
| ~DiagnosticParser () | |
Private Types | |
| typedef boost::ptr_map < std::string, BaseDiagnostics > | DiagnosticsMap |
Private Member Functions | |
| void | diagnostics_agg_cb_ (const diagnostic_msgs::DiagnosticArray::ConstPtr &msg) |
| void | run_tests_ () |
| Wait for the diagnostics to be received then run all tests on them. | |
Private Attributes | |
| DiagnosticsMap | all_diagnostics_ |
| ros::Subscriber | diag_sub_ |
| ROS subscriber to the diagnostics_agg topic. | |
| boost::ptr_vector < BaseDiagnostics > | diagnostics_ |
| ros::NodeHandle | nh_ |
| self_test::TestRunner * | test_runner_ |
| Pointer to the test runner to be able to add new tests for each parser. | |
Definition at line 44 of file diagnostic_parser.hpp.
typedef boost::ptr_map<std::string, BaseDiagnostics> shadow_robot::DiagnosticParser::DiagnosticsMap [private] |
Definition at line 71 of file diagnostic_parser.hpp.
| shadow_robot::DiagnosticParser::DiagnosticParser | ( | self_test::TestRunner * | test_runner | ) |
Definition at line 32 of file diagnostic_parser.cpp.
| shadow_robot::DiagnosticParser::~DiagnosticParser | ( | ) | [inline] |
Definition at line 48 of file diagnostic_parser.hpp.
| void shadow_robot::DiagnosticParser::diagnostics_agg_cb_ | ( | const diagnostic_msgs::DiagnosticArray::ConstPtr & | msg | ) | [private] |
Susbscribed to the diagnostics_agg topic.
| msg | new incoming msg |
Definition at line 64 of file diagnostic_parser.cpp.
| void shadow_robot::DiagnosticParser::run_tests_ | ( | ) | [private] |
Wait for the diagnostics to be received then run all tests on them.
Definition at line 44 of file diagnostic_parser.cpp.
Definition at line 72 of file diagnostic_parser.hpp.
ROS subscriber to the diagnostics_agg topic.
Definition at line 58 of file diagnostic_parser.hpp.
boost::ptr_vector<BaseDiagnostics> shadow_robot::DiagnosticParser::diagnostics_ [private] |
Definition at line 69 of file diagnostic_parser.hpp.
Definition at line 49 of file diagnostic_parser.hpp.
Pointer to the test runner to be able to add new tests for each parser.
Definition at line 55 of file diagnostic_parser.hpp.