00001 00028 #ifndef SR_TEST_RUNNER_HPP_ 00029 #define SR_TEST_RUNNER_HPP_ 00030 00031 #include <self_test/self_test.h> 00032 #include "sr_self_test/gnuplot-iostream.h" 00033 #include "sr_self_test/diagnostic_parser.hpp" 00034 #include "sr_self_test/manual_test.hpp" 00035 00036 #include "sr_self_test/sensor_noise_test.hpp" 00037 00038 namespace shadow_robot 00039 { 00040 class SrTestRunner : public self_test::TestRunner 00041 { 00042 public: 00043 SrTestRunner(); 00044 00045 virtual ~SrTestRunner(); 00046 00047 using DiagnosticTaskVector::add; 00048 using TestRunner::setID; 00049 00050 void addTopicTest(std::string topic_name, double frequency); 00051 void addServicesTest(std::vector<std::string> services_to_test); 00053 void addManualTests(); 00054 00056 void addSensorNoiseTest(); 00057 00058 void plot(std::map<std::string, std::vector<double> > joints); 00059 void plot(std::map<std::string, std::vector<double> > joints, bool testing); 00060 void plot(std::map<std::string, std::vector<double> > joints, std::string path); 00061 void plot(std::map<std::string, std::vector<double> > joints, std::string path, bool testing); 00062 00064 void add_diagnostic_parser(); 00065 00066 private: 00067 static const double SERVICE_TIMEOUT_CONST_; 00068 00069 std::vector<std::string> services_to_test_; 00070 void service_test_cb_(diagnostic_updater::DiagnosticStatusWrapper& status); 00071 size_t index_service_to_test_; 00072 00073 boost::shared_ptr<Gnuplot> gnuplot_; 00074 00076 boost::shared_ptr<DiagnosticParser> diagnostic_parser_; 00077 00079 std::vector<boost::shared_ptr<ManualTests> > manual_tests_; 00080 00081 boost::shared_ptr<SensorNoiseTest> sensor_noise_test_; 00082 }; 00083 00084 } 00085 00086 /* For the emacs weenies in the crowd. 00087 Local Variables: 00088 c-basic-offset: 2 00089 End: 00090 */ 00091 00092 #endif /* SR_TEST_RUNNER_HPP_ */