sr_test_runner.cpp
Go to the documentation of this file.
00001 
00028 #include "sr_self_test/sr_test_runner.hpp"
00029 
00030 namespace shadow_robot
00031 {
00032 //const double SrTestRunner::SERVICE_TIMEOUT_CONST_ = 1.0;
00033 
00034   SrTestRunner::SrTestRunner() :
00035     self_test::TestRunner(), index_service_to_test_(0)
00036   {
00037   };
00038 
00039   SrTestRunner::~SrTestRunner()
00040   {
00041   };
00042 
00043   void SrTestRunner::addTopicTest(std::string topic_name, double frequency)
00044   {
00045   };
00046 
00047   void SrTestRunner::addServicesTest(std::vector<std::string> services_to_test)
00048   {
00049     services_to_test_ = services_to_test;
00050     index_service_to_test_=0;
00051 
00052     for (size_t i=0; i < services_to_test_.size(); ++i)
00053     {
00054       add("Testing "+services_to_test_[i]+" is present.", this,  &SrTestRunner::service_test_cb_);
00055     }
00056   };
00057 
00058   void SrTestRunner::addSensorNoiseTest()
00059   {
00060     sensor_noise_test_.reset(new SensorNoiseTest());
00061     add("Testing sensor noise.", sensor_noise_test_.get(), &SensorNoiseTest::test_sensor_noise);
00062   }
00063 
00064   void SrTestRunner::service_test_cb_(diagnostic_updater::DiagnosticStatusWrapper& status)
00065   {
00066     if( ros::service::exists(services_to_test_[index_service_to_test_], false) )
00067       status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Service "+services_to_test_[index_service_to_test_]+" exists.");
00068     else
00069       status.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Service "+services_to_test_[index_service_to_test_]+" not available.");
00070 
00071     if(index_service_to_test_ + 1 < services_to_test_.size())
00072       index_service_to_test_ ++;
00073   };
00074 
00075   void SrTestRunner::plot(std::map<std::string, std::vector<double> > joints)
00076   {
00077     plot(joints, "");
00078   }
00079 
00080   void SrTestRunner::plot(std::map<std::string, std::vector<double> > joints, bool testing)
00081   {
00082     plot(joints, "", testing);
00083   }
00084 
00085   void SrTestRunner::plot(std::map<std::string, std::vector<double> > joints, std::string path)
00086   {
00087     plot(joints, path, false);
00088   }
00089 
00090   void SrTestRunner::plot(std::map<std::string, std::vector<double> > joints, std::string path, bool testing)
00091   {
00092     if( testing )
00093       gnuplot_.reset(new Gnuplot("gnuplot"));//close the window right after the test when running a test
00094     else
00095       gnuplot_.reset(new Gnuplot("gnuplot -persist"));
00096 
00097     //saving the plot to file if path provided
00098     if( path != "" )
00099     {
00100       *gnuplot_.get() << "set terminal png\n";
00101       *gnuplot_.get() << "set output '"+path+"'\n";
00102     }
00103 
00104     //plot legend and style
00105     std::string cmd = "plot ";
00106     std::string title = "";
00107     std::map<std::string, std::vector<double> >::const_iterator last_it = joints.end();
00108     if( !joints.empty())
00109       --last_it;
00110     for (std::map<std::string, std::vector<double> >::const_iterator it = joints.begin(); it != joints.end(); ++it)
00111     {
00112       cmd += " '-' with lines title '"+it->first+"'";
00113       if( it == last_it)
00114         cmd += "\n";
00115       else
00116         cmd += ",";
00117 
00118       title += it->first + " ";
00119     }
00120 
00121     *gnuplot_.get() << "set title '"+title+"'\n";
00122     *gnuplot_.get() << cmd;
00123 
00124     //plotting the data
00125     for (std::map<std::string, std::vector<double> >::const_iterator it = joints.begin(); it != joints.end(); ++it)
00126     {
00127       gnuplot_->send(it->second);
00128     }
00129   }
00130 
00131   void SrTestRunner::add_diagnostic_parser()
00132   {
00133     diagnostic_parser_.reset( new DiagnosticParser(this) );
00134   }
00135 
00136   void SrTestRunner::addManualTests()
00137   {
00138     std::string msg;
00139 
00140     msg = "Please press on the tactile sensors one after the other.\n Check that they react using rxplot. \n\n";
00141     msg += "If you have a hand equipped with biotacs (cycle [0] to change the finger tip):\n";
00142     msg += "   > rxplot /tactile/tactiles[0]/pac0";
00143     msg += "\n";
00144     msg += "If you have a hand equipped with PSTs (cycle [0] to change the finger tip):\n";
00145     msg += "   > rxplot /tactile/pressure[0]\n";
00146     manual_tests_.push_back( boost::shared_ptr<ManualTests>(new ManualTests(msg, 1) ) );
00147     add("Manual Tests: tactiles.", manual_tests_.back().get(), &ManualTests::run_manual_tests);
00148 
00149     msg = "Please check that the positions of the joints in the 3d model\n of the hand (using rviz) match those in the real hand.";
00150     manual_tests_.push_back( boost::shared_ptr<ManualTests>(new ManualTests(msg, 2) ) );
00151     add("Manual Tests: joint positions - rviz.", manual_tests_.back().get(), &ManualTests::run_manual_tests);
00152   }
00153 } //end namespace
00154 
00155 
00156 /* For the emacs weenies in the crowd.
00157    Local Variables:
00158    c-basic-offset: 2
00159    End:
00160 */


sr_self_test
Author(s): Ugo Cupcic
autogenerated on Fri Aug 28 2015 13:09:38