sr_self_test.cpp
Go to the documentation of this file.
00001 
00027 #include "sr_self_test/sr_self_test.hpp"
00028 #include <sr_utilities/sr_math_utils.hpp>
00029 #include <boost/filesystem.hpp>
00030 
00031 namespace shadow_robot
00032 {
00033   const double SrSelfTest::MAX_MSE_CONST_ = 0.18;
00034 
00035   SrSelfTest::SrSelfTest(bool simulated)
00036     : nh_tilde_("~")
00037   {
00038     simulated_ = simulated;
00039 
00040     //rename existing folder if it exists
00041     if( boost::filesystem::exists("/tmp/self_tests") )
00042     {
00043       //delete the last backup if it exists
00044       if( boost::filesystem::exists("/tmp/self_tests.bk") )
00045         boost::filesystem::remove_all("/tmp/self_tests.bk");
00046 
00047       //backup last test plots
00048       boost::filesystem::rename("/tmp/self_tests", "/tmp/self_tests.bk");
00049     }
00050     //create folder in /tmp for storing the plots
00051     path_to_plots_ = "/tmp/self_tests/"+ros::this_node::getName() + "/";
00052     boost::filesystem::create_directories(path_to_plots_);
00053 
00054     test_runner_.setID("12345");
00055 
00056     //add the different tests
00057     test_services_();
00058 
00059     //some tests can only be run on the real hand
00060     if(!simulated_)
00061     {
00062       //parses the diagnostics to find common problems
00063       test_runner_.add_diagnostic_parser();
00064 
00065       //manual tests come after diagnostic parsing
00066       // as we notify the user that the hand
00067       // connection seems to be fine if the previous
00068       // tests passed
00069       //add manual tests (tactile, calibration)
00070       test_runner_.addManualTests();
00071       //test the noise of the sensors
00072       test_runner_.addSensorNoiseTest();
00073     }
00074 
00075     //calling this from a oneshot timer because we're using the
00076     // hand commander which needs the hand to be fully initialised
00077     // before we can instantiate it.
00078     // Using 30s sleep here is a pain... not sure how to best get
00079     // rid of that... testing for availability of some services may
00080     // be not enough.
00081     test_movement_timer_ = nh_tilde_.createTimer( ros::Duration(30.0),
00082                                                   &SrSelfTest::add_all_movements_tests_, this,
00083                                                   true );
00084   }
00085 
00086   void SrSelfTest::test_services_()
00087   {
00088     std::vector<std::string> services_to_test;
00089     services_to_test.push_back("pr2_controller_manager/list_controller_types");
00090     services_to_test.push_back("pr2_controller_manager/list_controllers");
00091     services_to_test.push_back("pr2_controller_manager/load_controller");
00092     services_to_test.push_back("pr2_controller_manager/reload_controller_libraries");
00093     services_to_test.push_back("pr2_controller_manager/switch_controller");
00094     services_to_test.push_back("pr2_controller_manager/unload_controller");
00095 
00096     test_runner_.addServicesTest(services_to_test);
00097   }
00098 
00100   // TESTING MOVEMENTS
00101 
00102   void SrSelfTest::add_all_movements_tests_(const ros::TimerEvent& event)
00103   {
00104     if(simulated_)
00105     {
00106       if( hand_commander_ == NULL )
00107         hand_commander_.reset(new shadowrobot::HandCommander());
00108 
00109       joints_to_test_ = hand_commander_->get_all_joints();
00110     }
00111     else
00112     {
00113       joints_to_test_.clear();
00114       //we're adding all the possible joints here. They're checked against
00115       // controlled joints from hand commander later in the movement test.
00116       joints_to_test_.push_back("FFJ0");
00117       joints_to_test_.push_back("FFJ3");
00118       joints_to_test_.push_back("FFJ4");
00119 
00120       joints_to_test_.push_back("MFJ0");
00121       joints_to_test_.push_back("MFJ3");
00122       joints_to_test_.push_back("MFJ4");
00123 
00124       joints_to_test_.push_back("RFJ0");
00125       joints_to_test_.push_back("RFJ3");
00126       joints_to_test_.push_back("RFJ4");
00127 
00128       joints_to_test_.push_back("LFJ0");
00129       joints_to_test_.push_back("LFJ3");
00130       joints_to_test_.push_back("LFJ4");
00131       joints_to_test_.push_back("LFJ5");
00132 
00133       joints_to_test_.push_back("THJ1");
00134       joints_to_test_.push_back("THJ2");
00135       joints_to_test_.push_back("THJ3");
00136       joints_to_test_.push_back("THJ4");
00137       joints_to_test_.push_back("THJ5");
00138 
00139       joints_to_test_.push_back("WRJ1");
00140       joints_to_test_.push_back("WRJ2");
00141     }
00142 
00143     motor_tests_.clear();
00144 
00145     index_joints_to_test_ = 0;
00146     for(size_t i=0; i < joints_to_test_.size(); ++i)
00147     {
00148       //checking the movement of the finger
00149       test_runner_.add("Check movements ["+joints_to_test_[i]+"]", this, &SrSelfTest::test_movement_);
00150 
00151       if(!simulated_)
00152       {
00153         //running some tests on the motor (PWM mode, strain gauge response, etc...)
00154         motor_tests_.push_back(new MotorTest(&test_runner_, joints_to_test_[i], hand_commander_.get() ) );
00155       }
00156     }
00157   }
00158 
00159   void SrSelfTest::test_movement_(diagnostic_updater::DiagnosticStatusWrapper& status)
00160   {
00161     if( hand_commander_ == NULL )
00162       hand_commander_.reset(new shadowrobot::HandCommander());
00163 
00164     if(index_joints_to_test_ == 0)
00165     {
00166       //send all the joints to their safe positions:
00167       for( size_t i=0; i<joints_to_test_.size(); ++i)
00168       {
00169         send_safe_target_(joints_to_test_[i]);
00170         ros::Duration(0.4).sleep();
00171       }
00172     }
00173 
00174     std::string joint_name = joints_to_test_[index_joints_to_test_];
00175 
00176     if(!simulated_)
00177     {
00178       //only test the joint that are controlled from the hand commander
00179       bool test_joint = false;
00180       for(size_t i=0; i < hand_commander_->get_all_joints().size(); ++i)
00181       {
00182         if(joint_name.compare(hand_commander_->get_all_joints()[i]) == 0)
00183         {
00184           test_joint = true;
00185           break;
00186         }
00187       }
00188       if(!test_joint)
00189         status.summary(diagnostic_msgs::DiagnosticStatus::OK, "Not testing the joint.");
00190     }
00191 
00192     //sends the joint to a collision safe position
00193     send_safe_target_(joint_name);
00194     ros::Duration(0.5).sleep();
00195 
00196     std::string img_path;
00197     if( !nh_tilde_.getParam("image_path", img_path) )
00198     {
00199       status.summary(diagnostic_msgs::DiagnosticStatus::ERROR, "Parameter image_path not set, can't analyse movements.");
00200       return;
00201     }
00202     test_mvts_[joint_name].reset( new TestJointMovement(joint_name, hand_commander_.get()) );
00203 
00204     //wait a bit for mse to be received
00205     ros::Duration(1.0).sleep();
00206 
00207     //plot the data
00208     test_runner_.plot(test_mvts_[joint_name]->values, path_to_plots_+joint_name+".png");
00209 
00210     //check they are correct
00211     std::stringstream diag_msg;
00212     diag_msg << "Movement for " << joint_name << " (mse = " << test_mvts_[joint_name]->mse <<")";
00213     if(test_mvts_[joint_name]->mse < MAX_MSE_CONST_)
00214       status.summary(diagnostic_msgs::DiagnosticStatus::OK, diag_msg.str());
00215     else
00216       status.summary(diagnostic_msgs::DiagnosticStatus::ERROR, diag_msg.str());
00217 
00218     if( index_joints_to_test_ + 1 < joints_to_test_.size() )
00219       ++index_joints_to_test_;
00220     else
00221       index_joints_to_test_ = 0;
00222   }
00223 
00224   void SrSelfTest::send_safe_target_(std::string joint_name)
00225   {
00226     if( safe_targets_ == NULL )
00227       init_safe_targets_();
00228 
00229     update_safe_targets_(joint_name);
00230 
00231     std::vector<sr_robot_msgs::joint> joint_vector;
00232     joint_vector.resize( joints_to_test_.size() );
00233 
00234     for( size_t i=0; i<joints_to_test_.size(); ++i)
00235     {
00236       std::map<std::string, sr_robot_msgs::joint>::iterator safe_target;
00237       safe_target = safe_targets_->find( joints_to_test_[i] );
00238       if( safe_target == safe_targets_->end() )
00239       {
00240         //joint not found in the map -> use the min
00241         joint_vector[i].joint_name = joints_to_test_[i];
00242         joint_vector[i].joint_target = sr_math_utils::to_degrees( hand_commander_->get_min_max( joints_to_test_[i] ).first );
00243       }
00244       else
00245       {
00246         joint_vector[i].joint_name = joints_to_test_[i];
00247         joint_vector[i].joint_target = safe_target->second.joint_target;
00248       }
00249     }
00250 
00251     hand_commander_->sendCommands(joint_vector);
00252     ros::spinOnce();
00253   }
00254 
00255   void SrSelfTest::update_safe_targets_(std::string joint_name)
00256   {
00257     //This is very hugly.... not sure how to make it prettier easily - haven't much time...
00258     if( joint_name.compare("FFJ4") == 0 )
00259     {
00260       (*safe_targets_.get())["FFJ3"].joint_target = 45.0;
00261       (*safe_targets_.get())["FFJ4"].joint_target = 0.0;
00262       (*safe_targets_.get())["MFJ4"].joint_target = sr_math_utils::to_degrees( hand_commander_->get_min_max("MFJ4").second );
00263       (*safe_targets_.get())["RFJ4"].joint_target = sr_math_utils::to_degrees( hand_commander_->get_min_max("RFJ4").first );
00264       (*safe_targets_.get())["LFJ4"].joint_target = sr_math_utils::to_degrees( hand_commander_->get_min_max("LFJ4").first );
00265     }
00266     else
00267     {
00268       if( joint_name.compare("MFJ4") == 0 )
00269       {
00270         (*safe_targets_.get())["FFJ3"].joint_target = 0.0;
00271         (*safe_targets_.get())["MFJ3"].joint_target = 45.0;
00272         (*safe_targets_.get())["FFJ4"].joint_target = sr_math_utils::to_degrees( hand_commander_->get_min_max("FFJ4").first );
00273         (*safe_targets_.get())["MFJ4"].joint_target = 0.0;
00274         (*safe_targets_.get())["RFJ4"].joint_target = sr_math_utils::to_degrees( hand_commander_->get_min_max("RFJ4").first );
00275         (*safe_targets_.get())["LFJ4"].joint_target = sr_math_utils::to_degrees( hand_commander_->get_min_max("LFJ4").first );
00276       }
00277       else
00278       {
00279         if( joint_name.compare("RFJ4") == 0 )
00280         {
00281           (*safe_targets_.get())["MFJ3"].joint_target = 0.0;
00282           (*safe_targets_.get())["RFJ3"].joint_target = 45.0;
00283           (*safe_targets_.get())["FFJ4"].joint_target = sr_math_utils::to_degrees( hand_commander_->get_min_max("FFJ4").first );
00284           (*safe_targets_.get())["MFJ4"].joint_target = sr_math_utils::to_degrees( hand_commander_->get_min_max("MFJ4").first );
00285           (*safe_targets_.get())["RFJ4"].joint_target = 0.0;
00286           (*safe_targets_.get())["LFJ4"].joint_target = sr_math_utils::to_degrees( hand_commander_->get_min_max("LFJ4").first );
00287         }
00288         else
00289         {
00290           if( joint_name.compare("LFJ4") == 0 )
00291           {
00292             (*safe_targets_.get())["RFJ3"].joint_target = 0.0;
00293             (*safe_targets_.get())["LFJ3"].joint_target = 45.0;
00294             (*safe_targets_.get())["FFJ4"].joint_target = sr_math_utils::to_degrees( hand_commander_->get_min_max("FFJ4").first );
00295             (*safe_targets_.get())["MFJ4"].joint_target = sr_math_utils::to_degrees( hand_commander_->get_min_max("MFJ4").first );
00296             (*safe_targets_.get())["RFJ4"].joint_target = sr_math_utils::to_degrees( hand_commander_->get_min_max("RFJ4").second );
00297             (*safe_targets_.get())["LFJ4"].joint_target = 0.0;
00298           }
00299           else
00300           {
00301             (*safe_targets_.get())["FFJ3"].joint_target = 0.0;
00302             (*safe_targets_.get())["MFJ3"].joint_target = 0.0;
00303             (*safe_targets_.get())["RFJ3"].joint_target = 0.0;
00304             (*safe_targets_.get())["LFJ3"].joint_target = 0.0;
00305 
00306             (*safe_targets_.get())["FFJ4"].joint_target = 0.0;
00307             (*safe_targets_.get())["MFJ4"].joint_target = 0.0;
00308             (*safe_targets_.get())["RFJ4"].joint_target = 0.0;
00309             (*safe_targets_.get())["LFJ4"].joint_target = 0.0;
00310           }
00311         }
00312       }
00313     }
00314     //we ignore the other joints
00315   }
00316 
00317   void SrSelfTest::init_safe_targets_()
00318   {
00319     safe_targets_.reset( new std::map<std::string, sr_robot_msgs::joint>());
00320     sr_robot_msgs::joint safe_target;
00321 
00322     //??J4 -> min or max or 0... need to find a way to do that
00323     safe_target.joint_name = "FFJ4";
00324     safe_target.joint_target = 0.0;
00325     safe_targets_->insert( std::pair<std::string, sr_robot_msgs::joint>(safe_target.joint_name, safe_target) );
00326     safe_target.joint_name = "MFJ4";
00327     safe_target.joint_target = 0.0;
00328     safe_targets_->insert( std::pair<std::string, sr_robot_msgs::joint>(safe_target.joint_name, safe_target) );
00329     safe_target.joint_name = "RFJ4";
00330     safe_target.joint_target = 0.0;
00331     safe_targets_->insert( std::pair<std::string, sr_robot_msgs::joint>(safe_target.joint_name, safe_target) );
00332     safe_target.joint_name = "LFJ4";
00333     safe_target.joint_target = 0.0;
00334     safe_targets_->insert( std::pair<std::string, sr_robot_msgs::joint>(safe_target.joint_name, safe_target) );
00335 
00336     //wrist -> 0
00337     safe_target.joint_name = "WRJ1";
00338     safe_target.joint_target = 0.0;
00339     safe_targets_->insert( std::pair<std::string, sr_robot_msgs::joint>(safe_target.joint_name, safe_target) );
00340     safe_target.joint_name = "WRJ2";
00341     safe_target.joint_target = 0.0;
00342     safe_targets_->insert( std::pair<std::string, sr_robot_msgs::joint>(safe_target.joint_name, safe_target) );
00343 
00344     //thumb -> 0
00345     safe_target.joint_name = "THJ2";
00346     safe_target.joint_target = 0.0;
00347     safe_targets_->insert( std::pair<std::string, sr_robot_msgs::joint>(safe_target.joint_name, safe_target) );
00348     safe_target.joint_name = "THJ3";
00349     safe_target.joint_target = 0.0;
00350     safe_targets_->insert( std::pair<std::string, sr_robot_msgs::joint>(safe_target.joint_name, safe_target) );
00351     safe_target.joint_name = "THJ4";
00352     safe_target.joint_target = 0.0;
00353     safe_targets_->insert( std::pair<std::string, sr_robot_msgs::joint>(safe_target.joint_name, safe_target) );
00354     safe_target.joint_name = "THJ5";
00355     safe_target.joint_target = 0.0;
00356     safe_targets_->insert( std::pair<std::string, sr_robot_msgs::joint>(safe_target.joint_name, safe_target) );
00357   }
00358 
00359 }  // namespace shadow_robot
00360 
00361 
00362 /* For the emacs weenies in the crowd.
00363    Local Variables:
00364    c-basic-offset: 2
00365    End:
00366 */
00367 
00368 


sr_self_test
Author(s): Ugo Cupcic
autogenerated on Mon Oct 6 2014 07:52:52