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


sr_self_test
Author(s): Ugo Cupcic
autogenerated on Fri Aug 21 2015 12:25:57