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
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
00094 for(unsigned int i=1 ; i < SENSORS_NUM_0220 + 2; ++i)
00095 {
00096
00097 status_data->sensors[i] = i;
00098 }
00099
00100 status_data->motor_data_type = MOTOR_DATA_SGR;
00101
00102
00103 status_data->which_motors = 0;
00104
00105
00106 status_data->which_motor_data_arrived = 0x00055555;
00107 status_data->which_motor_data_had_errors = 0;
00108
00109
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
00116 status_data->idle_time_us = 1;
00117
00118
00119 lib_test->sr_hand_lib->update(status_data);
00120
00121
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
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
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);
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
00154 for(unsigned int i=0 ; i < SENSORS_NUM_0220 + 1; ++i)
00155 {
00156
00157 status_data->sensors[i] = i+1;
00158 }
00159
00160 status_data->motor_data_type = MOTOR_DATA_VOLTAGE;
00161
00162
00163 status_data->which_motors = 0;
00164
00165
00166 status_data->which_motor_data_arrived = 0x00055555;
00167 status_data->which_motor_data_had_errors = 0;
00168
00169
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
00176 status_data->idle_time_us = 1;
00177
00178
00179 lib_test->sr_hand_lib->update(status_data);
00180
00181
00182 lib_test->check_hw_actuator("FFJ4", 7, 3, 4.0);
00183
00184
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
00218
00219
00220
00221
00222
00223
00224
00225
00226
00227
00228
00229
00230
00231
00232
00233
00234
00235
00236
00237
00238
00239
00240
00241
00242
00243
00244
00245
00246
00247
00248
00249
00250
00251
00252
00253
00254
00255
00256
00257
00258
00259
00260
00261
00262
00263
00264
00265
00266
00267
00268
00269
00270
00271
00272
00273
00274
00275
00276
00277
00278
00279
00280
00281
00282
00283
00284
00285
00286
00287
00288
00289
00290
00291
00292
00293
00294
00295
00296
00297
00298
00299
00300
00301
00302
00303
00304
00305
00306
00307
00308
00309
00310
00311
00312
00313
00314
00315
00316
00317
00318
00319
00320
00321
00322
00323
00324
00325
00326
00327
00328
00329
00330
00331
00332
00333
00334
00335
00336
00337
00338
00339
00340
00341
00342
00343
00344
00345
00346
00347
00348
00349
00350
00351
00352
00353
00354
00355
00356
00357
00358
00359
00360
00361
00362
00363
00364
00365
00366
00367
00368
00369
00370
00371
00372
00373
00374
00375
00376
00377
00378
00379
00380
00381
00382
00383
00384
00385
00386
00387
00388
00389
00390
00391
00392
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
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
00414 EXPECT_TRUE(flags[13].second);
00415 EXPECT_TRUE(flags[14].second);
00416 EXPECT_TRUE(flags[15].second);
00417 }
00418
00420
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
00431
00432
00433
00434
00435