test_robot_lib.cpp
Go to the documentation of this file.
00001 
00027 #include "sr_robot_lib/sr_hand_lib.hpp"
00028 #include <gtest/gtest.h>
00029 #include <ros/ros.h>
00030 
00031 class HandLibTestProtected : public shadow_robot::SrHandLib
00032 {
00033 public:
00034   HandLibTestProtected(pr2_hardware_interface::HardwareInterface *hw)
00035     : shadow_robot::SrHandLib(hw)
00036   {};
00037 
00038   ~HandLibTestProtected()
00039   {};
00040 
00041 public: using shadow_robot::SrHandLib::joints_vector;
00042 };
00043 
00044 class HandLibTest
00045 {
00046 public:
00047   pr2_hardware_interface::HardwareInterface *hw;
00048   boost::shared_ptr<HandLibTestProtected> sr_hand_lib;
00049   sr_actuator::SrActuator* actuator;
00050 
00051   HandLibTest()
00052   {
00053     hw = new pr2_hardware_interface::HardwareInterface();
00054     sr_hand_lib= boost::shared_ptr<HandLibTestProtected>( new HandLibTestProtected(hw) );
00055   }
00056 
00057   ~HandLibTest()
00058   {
00059     delete hw;
00060   }
00061 
00062   void check_hw_actuator(std::string name, int motor_id, int id_in_enum, double expected_pos)
00063   {
00064     sr_actuator::SrActuatorState state;
00065 
00066     actuator = static_cast<sr_actuator::SrActuator*>(hw->getActuator(name));
00067     state = (actuator->state_);
00068 
00069     EXPECT_EQ(state.device_id_ , motor_id);
00070     //EXPECT_EQ(state.position_ , expected_pos);
00071   }
00072 
00073 };
00074 
00078 TEST(SrRobotLib, Initialization)
00079 {
00080   boost::shared_ptr< HandLibTest > lib_test = boost::shared_ptr< HandLibTest >( new HandLibTest() );
00081 
00082   EXPECT_TRUE(true);
00083 }
00084 
00088 TEST(SrRobotLib, UpdateMotor)
00089 {
00090   boost::shared_ptr< HandLibTest > lib_test = boost::shared_ptr< HandLibTest >( new HandLibTest() );
00091 
00092   ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS* status_data = new ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS();
00093   //add growing sensors values
00094   for(unsigned int i=1 ; i < SENSORS_NUM_0220 + 2; ++i)
00095   {
00096     //position = id in joint enum
00097     status_data->sensors[i] = i;
00098   }
00099 
00100   status_data->motor_data_type = MOTOR_DATA_SGR;
00101 
00102   //even motors
00103   status_data->which_motors = 0;
00104 
00105   //all motor data arrived with no errors
00106   status_data->which_motor_data_arrived = 0x00055555;
00107   status_data->which_motor_data_had_errors = 0;
00108 
00109   //add growing motor data packet values
00110   for(unsigned int i=0 ; i < 10; ++i)
00111   {
00112     status_data->motor_data_packet[i].torque = 4;
00113     status_data->motor_data_packet[i].misc = 2*i;
00114   }
00115   //filling the status data with known values
00116   status_data->idle_time_us = 1;
00117 
00118   //update the library
00119   lib_test->sr_hand_lib->update(status_data);
00120 
00121   //check the data we read back are correct.
00122   EXPECT_EQ(lib_test->sr_hand_lib->main_pic_idle_time, 1);
00123   EXPECT_EQ(lib_test->sr_hand_lib->main_pic_idle_time_min, 1);
00124 
00125   //check the sensors etc..
00126   boost::ptr_vector<shadow_joints::Joint>::iterator joint_tmp = lib_test->sr_hand_lib->joints_vector.begin();
00127   for(;joint_tmp != lib_test->sr_hand_lib->joints_vector.end(); ++joint_tmp)
00128   {
00129     if(joint_tmp->has_motor)
00130     {
00131       //we updated the even motors
00132       if(joint_tmp->motor->motor_id % 2 == 0)
00133       {
00134         ROS_ERROR_STREAM("last measured effort: " << joint_tmp->motor->actuator->state_.last_measured_effort_ << " actuator: " << joint_tmp->motor->actuator);
00135 
00136         EXPECT_FLOAT_EQ(joint_tmp->motor->actuator->state_.force_unfiltered_ , 4.0);//(double)joint_tmp->motor->motor_id/2.0);
00137         EXPECT_EQ(joint_tmp->motor->actuator->state_.strain_gauge_right_, joint_tmp->motor->motor_id);
00138       }
00139     }
00140   }
00141 }
00142 
00148 TEST(SrRobotLib, UpdateActuators)
00149 {
00150   boost::shared_ptr< HandLibTest > lib_test = boost::shared_ptr< HandLibTest >( new HandLibTest() );
00151 
00152   ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS* status_data = new ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS();
00153   //add growing sensors values
00154   for(unsigned int i=0 ; i < SENSORS_NUM_0220 + 1; ++i)
00155   {
00156     //position = id in joint enum
00157     status_data->sensors[i] = i+1;
00158   }
00159 
00160   status_data->motor_data_type = MOTOR_DATA_VOLTAGE;
00161 
00162   //even motors
00163   status_data->which_motors = 0;
00164 
00165   //all motor data arrived with no errors
00166   status_data->which_motor_data_arrived = 0x00055555;
00167   status_data->which_motor_data_had_errors = 0;
00168 
00169   //add growing motor data packet values
00170   for(unsigned int i=0 ; i < 10; ++i)
00171   {
00172     status_data->motor_data_packet[i].torque = i;
00173     status_data->motor_data_packet[i].misc = 10*i;
00174   }
00175   //filling the status data with known values
00176   status_data->idle_time_us = 1;
00177 
00178   //update the library
00179   lib_test->sr_hand_lib->update(status_data);
00180 
00181   // name, motor_id, id_in_enum, expected_pos
00182   lib_test->check_hw_actuator("FFJ4", 7, 3, 4.0);
00183 
00184   //cleanup
00185   delete status_data;
00186 }
00187 
00194 class TestHandLib
00195   : public HandLibTestProtected
00196 {
00197 public:
00198   TestHandLib(pr2_hardware_interface::HardwareInterface* hw)
00199     : HandLibTestProtected(hw)
00200   {}
00201 
00202   using HandLibTestProtected::calibrate_joint;
00203 
00204   using HandLibTestProtected::status_data;
00205 
00206   using HandLibTestProtected::actuator;
00207 
00208   using HandLibTestProtected::humanize_flags;
00209 };
00210 
00211 
00217 // TEST(SrRobotLib, CalibrationOneMotor)
00218 // {
00219 
00220 //   pr2_hardware_interface::HardwareInterface *hw;
00221 //   boost::shared_ptr<TestHandLib> sr_hand_lib = boost::shared_ptr<TestHandLib>( new TestHandLib(hw) );
00222 
00223 //   ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS status_data;
00224 
00225 //   //set all the sensors to 0
00226 //   for(unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
00227 //     status_data.sensors[i] = 0;
00228 
00229 //   sr_hand_lib->status_data = &status_data;
00230 //   for(unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
00231 //     EXPECT_EQ(sr_hand_lib->status_data->sensors[i], 0);
00232 
00233 //   //let's find FFJ3 in the vector
00234 //   boost::ptr_vector<shadow_joints::Joint>::iterator ffj3 = sr_hand_lib->joints_vector.begin();
00235 //   std::string name_tmp = ffj3->joint_name;
00236 //   bool ffj3_found = false;
00237 //   int index_ffj3 = 0;
00238 
00239 //   for(; ffj3 != sr_hand_lib->joints_vector.end(); ++ffj3)
00240 //   {
00241 //     name_tmp = ffj3->joint_name;
00242 
00243 //     if( name_tmp.compare("FFJ3") == 0)
00244 //     {
00245 //       ffj3_found = true;
00246 //       break;
00247 //     }
00248 
00249 //     ++index_ffj3;
00250 //   }
00251 
00252 //   EXPECT_TRUE(ffj3_found);
00253 //   EXPECT_EQ(index_ffj3, 3);
00254 
00255 //   sr_hand_lib->actuator = (ffj3->motor->actuator);
00256 
00257 //   sr_hand_lib->calibrate_joint(ffj3);
00258 //   //all the sensors at 0 -> should be 0
00259 //   EXPECT_EQ( ffj3->motor->actuator->state_.position_unfiltered_ , 0.0);
00260 
00261 //   for(unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
00262 //   sr_hand_lib->status_data->sensors[i] = 1;
00263 
00264 //   //now ffj3 position should be 1
00265 //   sr_hand_lib->calibrate_joint(ffj3);
00266 //   //all the sensors at 1 -> should be 1
00267 //   EXPECT_EQ( ffj3->motor->actuator->state_.position_unfiltered_ , 1.0);
00268 
00269 //   delete hw;
00270 // }
00271 
00272 
00273 // /**
00274 //  * Testing the calibration procedure for
00275 //  * a joint having calibrating the sensors first
00276 //  * and then combining them (FFJ0)
00277 //  *
00278 //  */
00279 // TEST(SrRobotLib, CalibrationFFJ0)
00280 // {
00281 
00282 //   pr2_hardware_interface::HardwareInterface *hw;
00283 //   boost::shared_ptr<TestHandLib> sr_hand_lib = boost::shared_ptr<TestHandLib>( new TestHandLib(hw) );
00284 
00285 //   ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS status_data;
00286 
00287 //   //set all the sensors to 0
00288 //   for(unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
00289 //     status_data.sensors[i] = 0;
00290 
00291 //   sr_hand_lib->status_data = &status_data;
00292 //   for(unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
00293 //     EXPECT_EQ(sr_hand_lib->status_data->sensors[i], 0);
00294 
00295 //   //let's find FFJ0 in the vector
00296 //   boost::ptr_vector<shadow_joints::Joint>::iterator ffj0 = sr_hand_lib->joints_vector.begin();
00297 //   std::string name_tmp = ffj0->joint_name;
00298 //   bool ffj0_found = false;
00299 //   int index_ffj0 = 0;
00300 
00301 //   for(; ffj0 != sr_hand_lib->joints_vector.end(); ++ffj0)
00302 //   {
00303 //     name_tmp = ffj0->joint_name;
00304 
00305 //     if( name_tmp.compare("FFJ0") == 0)
00306 //     {
00307 //       ffj0_found = true;
00308 //       break;
00309 //     }
00310 
00311 //     ++index_ffj0;
00312 //   }
00313 
00314 //   EXPECT_TRUE(ffj0_found);
00315 //   EXPECT_EQ(index_ffj0, 0);
00316 
00317 //   sr_hand_lib->actuator = (ffj0->motor->actuator);
00318 
00319 //   sr_hand_lib->calibrate_joint(ffj0);
00320 //   //all the sensors at 0 -> should be 0
00321 //   EXPECT_EQ( ffj0->motor->actuator->state_.position_unfiltered_ , 0.0);
00322 
00323 //   for(unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
00324 //     sr_hand_lib->status_data->sensors[i] = 1;
00325 
00326 //   //now ffj0 position should be 1
00327 //   sr_hand_lib->calibrate_joint(ffj0);
00328 //   //all the sensors at 1 -> should be 2
00329 //   EXPECT_EQ( ffj0->motor->actuator->state_.position_unfiltered_ , 2.0);
00330 
00331 //   delete hw;
00332 // }
00333 
00334 // /**
00335 //  * Testing the calibration procedure for
00336 //  * a compound joint combining the sensors
00337 //  * and then calibrating the total (THJ5)
00338 //  *
00339 //  */
00340 // TEST(SrRobotLib, CalibrationTHJ5)
00341 // {
00342 
00343 //   pr2_hardware_interface::HardwareInterface *hw;
00344 //   boost::shared_ptr<TestHandLib> sr_hand_lib = boost::shared_ptr<TestHandLib>( new TestHandLib(hw) );
00345 
00346 //   ETHERCAT_DATA_STRUCTURE_0200_PALM_EDC_STATUS status_data;
00347 
00348 //   //set all the sensors to 0
00349 //   for(unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
00350 //     status_data.sensors[i] = 0;
00351 
00352 //   sr_hand_lib->status_data = &status_data;
00353 //   for(unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
00354 //     EXPECT_EQ(sr_hand_lib->status_data->sensors[i], 0);
00355 
00356 //   //let's find THJ5 in the vector
00357 //   boost::ptr_vector<shadow_joints::Joint>::iterator thj5 = sr_hand_lib->joints_vector.begin();
00358 //   std::string name_tmp = thj5->joint_name;
00359 //   bool thj5_found = false;
00360 //   int index_thj5 = 0;
00361 
00362 //   for(; thj5 != sr_hand_lib->joints_vector.end(); ++thj5)
00363 //   {
00364 //     name_tmp = thj5->joint_name;
00365 
00366 //     if( name_tmp.compare("THJ5") == 0)
00367 //     {
00368 //       thj5_found = true;
00369 //       break;
00370 //     }
00371 
00372 //     ++index_thj5;
00373 //   }
00374 
00375 //   EXPECT_TRUE(thj5_found);
00376 //   EXPECT_EQ(index_thj5, 25);
00377 
00378 //   sr_hand_lib->actuator = (thj5->motor->actuator);
00379 
00380 //   sr_hand_lib->calibrate_joint(thj5);
00381 //   //all the sensors at 0 -> should be 0
00382 //   EXPECT_EQ( thj5->motor->actuator->state_.position_unfiltered_ , 0.0);
00383 
00384 //   for(unsigned int i = 0; i < SENSORS_NUM_0220 + 1; ++i)
00385 //     sr_hand_lib->status_data->sensors[i] = 1;
00386 
00387 //   //now thj5 position should be 1
00388 //   sr_hand_lib->calibrate_joint(thj5);
00389 //   //all the sensors at 1 -> should be 1 (THJ5 = .5 THJ5A + .5 THJ5B)
00390 //   EXPECT_EQ( thj5->motor->actuator->state_.position_unfiltered_ , 1.0);
00391 
00392 //   delete hw;
00393 // }
00394 
00399 TEST(SrRobotLib, HumanizeFlags)
00400 {
00401   pr2_hardware_interface::HardwareInterface *hw;
00402   boost::shared_ptr<TestHandLib> sr_hand_lib = boost::shared_ptr<TestHandLib>( new TestHandLib(hw) );
00403 
00404   std::vector<std::pair<std::string, bool> > flags;
00405   //all flags set
00406   flags = sr_hand_lib->humanize_flags(0xFFFF);
00407 
00408   EXPECT_EQ(flags.size(), 16);
00409 
00410   for(unsigned int i=0; i < 16; ++i)
00411     EXPECT_EQ(flags[i].first.compare(error_flag_names[i]) , 0);
00412 
00413   //The last three flags are serious
00414   EXPECT_TRUE(flags[13].second);
00415   EXPECT_TRUE(flags[14].second);
00416   EXPECT_TRUE(flags[15].second);
00417 }
00418 
00420 //     MAIN       //
00422 
00423 int main(int argc, char **argv)
00424 {
00425   ros::init(argc, argv, "calibration_test");
00426 
00427   testing::InitGoogleTest(&argc, argv);
00428   return RUN_ALL_TESTS();
00429 }
00430 /* For the emacs weenies in the crowd.
00431    Local Variables:
00432    c-basic-offset: 2
00433    End:
00434 */
00435 


sr_robot_lib
Author(s): Ugo Cupcic / ugo@shadowrobot.com , software@shadowrobot.com
autogenerated on Thu Jan 2 2014 12:02:17