00001 #include <iostream>
00002 #include <string>
00003 #include <vector>
00004
00005 #include <ros/ros.h>
00006 #include <ros_client.cpp>
00007 #include <testutil/abst_acceptancetest.hpp>
00008 #include <testutil/acceptancetest_ros.hpp>
00009
00010 #include <sstream>
00011
00012 template <class T>
00013 std::string to_string(T a){
00014 std::stringstream ss;
00015 ss << a;
00016 return ss.str();
00017 }
00018
00019 class AcceptanceTest_Hiro{
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 public:
00039 typedef std::vector<double> DVEC;
00040 typedef std::vector<DVEC> DMAT;
00041
00042 static const double positions_larm_deg_up[6];
00043 static const double positions_larm_deg_down[6];
00044 static const double positions_rarm_deg_down[6];
00045 static const double positions_larm_deg_up_sync[6];
00046 static const double positions_rarm_deg_up_sync[6];
00047 static const double rotation_angles_head_1[2][2];
00048 static const double rotation_angles_head_2[2][2];
00049 static const double positions_torso_deg[2][1];
00050 static const double R_Z_SMALLINCREMENT;
00051
00052 static const double pos_l_x_near_y_far[3];
00053 static const double rpy_l_x_near_y_far[3];
00054 static const double pos_r_x_near_y_far[3];
00055 static const double rpy_r_x_near_y_far[3];
00056
00057 static const double pos_l_x_far_y_far[3];
00058 static const double rpy_l_x_far_y_far[3];
00059 static const double pos_r_x_far_y_far[3];
00060 static const double rpy_r_x_far_y_far[3];
00061
00062
00063 static const double TASK_DURATION_DEFAULT;
00064 static const double TASK_DURATION_TORSO;
00065 static const double DURATION_EACH_SMALLINCREMENT;
00066 static const double TASK_DURATION_HEAD;
00067 static const int SLEEP_TIME;
00068 static const int SLEEP_OVERWRITE;
00069
00070 static const int DURATION_TOTAL_SMALLINCREMENT;
00071
00072 DVEC POSITIONS_LARM_DEG_UP;
00073 DVEC POSITIONS_LARM_DEG_DOWN;
00074 DVEC POSITIONS_RARM_DEG_DOWN;
00075 DVEC POSITIONS_LARM_DEG_UP_SYNC;
00076 DVEC POSITIONS_RARM_DEG_UP_SYNC;
00077 DMAT ROTATION_ANGLES_HEAD_1;
00078 DMAT ROTATION_ANGLES_HEAD_2;
00079 DMAT POSITIONS_TORSO_DEG;
00080
00081
00082 DVEC POS_L_X_NEAR_Y_FAR;
00083 DVEC RPY_L_X_NEAR_Y_FAR;
00084 DVEC POS_R_X_NEAR_Y_FAR;
00085 DVEC RPY_R_X_NEAR_Y_FAR;
00086
00087 DVEC POS_L_X_FAR_Y_FAR;
00088 DVEC RPY_L_X_FAR_Y_FAR;
00089 DVEC POS_R_X_FAR_Y_FAR;
00090 DVEC RPY_R_X_FAR_Y_FAR;
00091
00092 #define INIT_VEC(name,num) name,name+num
00093 #define VEC_COPY(from,to,N1,N2) for(int i=0;i<N1;++i)for(int j=0;j<N2;++j)to[i][j]=from[i][j];
00094 AcceptanceTest_Hiro(std::string name="Hironx(Robot)0",
00095 std::string url="")
00096 :rtm_robotname(name),rtm_url(url),
00097 ros(ROS_Client()),acceptance_ros_client(ros),
00098 POSITIONS_LARM_DEG_UP( INIT_VEC(positions_larm_deg_up,6) ),
00099 POSITIONS_LARM_DEG_DOWN( INIT_VEC(positions_larm_deg_down,6) ),
00100 POSITIONS_RARM_DEG_DOWN( INIT_VEC(positions_rarm_deg_down,6) ),
00101 POSITIONS_LARM_DEG_UP_SYNC( INIT_VEC(positions_larm_deg_up_sync,6) ),
00102 POSITIONS_RARM_DEG_UP_SYNC( INIT_VEC(positions_rarm_deg_up_sync,6) ),
00103
00104 ROTATION_ANGLES_HEAD_1(2,DVEC(2)),
00105 ROTATION_ANGLES_HEAD_2(2,DVEC(2)),
00106 POSITIONS_TORSO_DEG(2,DVEC(1)),
00107
00108
00109 POS_L_X_NEAR_Y_FAR( INIT_VEC(pos_l_x_near_y_far,3) ),
00110 RPY_L_X_NEAR_Y_FAR( INIT_VEC(rpy_l_x_near_y_far,3) ),
00111 POS_R_X_NEAR_Y_FAR( INIT_VEC(pos_r_x_near_y_far,3) ),
00112 RPY_R_X_NEAR_Y_FAR( INIT_VEC(rpy_r_x_near_y_far,3) ),
00113
00114 POS_L_X_FAR_Y_FAR( INIT_VEC(pos_l_x_far_y_far,3) ),
00115 RPY_L_X_FAR_Y_FAR( INIT_VEC(rpy_l_x_far_y_far,3) ),
00116 POS_R_X_FAR_Y_FAR( INIT_VEC(pos_r_x_far_y_far,3) ),
00117 RPY_R_X_FAR_Y_FAR( INIT_VEC(rpy_r_x_far_y_far,3) )
00118 {
00119 VEC_COPY(rotation_angles_head_1,ROTATION_ANGLES_HEAD_1,2,2)
00120 VEC_COPY(rotation_angles_head_2,ROTATION_ANGLES_HEAD_2,2,2)
00121 VEC_COPY(positions_torso_deg,POSITIONS_TORSO_DEG,2,1)
00122 };
00123
00124 std::string retName(){
00125 return rtm_robotname;
00126 }
00127
00128 void wait_input(std::string msg, bool do_wait_input = false){
00129
00130
00131
00132
00133
00134
00135 if(!msg.empty())
00136 msg = "\n" + msg + "= ";
00137 if(do_wait_input){
00138
00139 }
00140 }
00141
00142 void run_test_ros(bool do_wait_input = false){
00143
00144
00145
00146
00147
00148 ROS_INFO("********RUN_TEST_ROS************");
00149 run_tests(acceptance_ros_client,do_wait_input);
00150 }
00151
00152 void run_tests(AbstAcceptanceTest& test_client,bool do_wait_input = false){
00153 std::string msg_type_client = "";
00154 if(typeid(test_client) == typeid(AcceptanceTestRos))
00155 msg_type_client = "(ROS) ";
00156
00157
00158 std::string msg = msg_type_client;
00159
00160 test_client.go_initpos();
00161
00162 std::string msg_task = "TASK-1. Move each arm separately to the given pose by passing joint space.";
00163 msg = msg_type_client + msg_task;
00164 wait_input(msg, do_wait_input);
00165 move_armbyarm_jointangles(test_client);
00166
00167 msg_task = "TASK-1. Move each arm separately to the given pose by passing pose in hand space (i.e. orthogonal coordinate of eef).";
00168 ROS_INFO("%s",msg_task.c_str());
00169 msg = msg_type_client + msg_task;
00170 wait_input(msg, do_wait_input);
00171 move_armbyarm_pose(test_client);
00172
00173 msg_task = "TASK-2. Move both arms at the same time using relative distance and angle from the current pose.";
00174 ROS_INFO("%s",msg_task.c_str());
00175 msg = msg_type_client + msg_task;
00176 wait_input(msg, do_wait_input);
00177 movearms_together(test_client);
00178
00179 msg_task = "TASK-3. Move arm with very small increment (0.1mm/sec).\n\tRight hand 3 cm upward over 30 seconds.";
00180 msg = msg_type_client + msg_task;
00181 wait_input(msg, do_wait_input);
00182 set_pose_relative(test_client);
00183
00184 msg_task = "In the beginning you\"ll see the displacement of the previous task.\nTASK-4. Move head using Joint angles in degree.";
00185 ROS_INFO("%s",msg_task.c_str());
00186 msg = msg_type_client + msg_task;
00187 wait_input(msg, do_wait_input);
00188 move_head(test_client);
00189
00190 msg_task = "TASK-5. Rotate torso to the left and right 130 degree.";
00191 ROS_INFO("%s",msg_task.c_str());
00192 msg = msg_type_client + msg_task;
00193 wait_input(msg, do_wait_input);
00194 move_torso(test_client);
00195
00196 msg_task = std::string("TASK-6. Overwrite ongoing action.\n\t6-1.") +
00197 "While rotating torso toward left, it getscanceled and rotate toward" +
00198 "right.\n\t6-2. While lifting left hand, right hand also tries to reach"
00199 "the same height that gets cancelled so that it stays lower than the left hand.";
00200 ROS_INFO("%s",msg_task.c_str());
00201 msg = msg_type_client + msg_task;
00202 wait_input(msg, do_wait_input);
00203 overwrite_torso(test_client);
00204
00205 overwrite_arm(test_client);
00206
00207 msg_task = "TASK-7. Show the capable workspace on front side of the robot.";
00208 msg = msg_type_client + msg_task;
00209 wait_input(msg, do_wait_input);
00210 show_workspace(test_client);
00211 }
00212
00213 void move_armbyarm_jointangles(AbstAcceptanceTest& test_client){
00214
00215
00216
00217 test_client.go_initpos(7.0);
00218 std::string arm = AbstAcceptanceTest::GRNAME_LEFT_ARM;
00219 test_client.set_joint_angles(arm, POSITIONS_LARM_DEG_UP,
00220 "Task1 " + to_string(arm));
00221
00222 arm = AbstAcceptanceTest::GRNAME_RIGHT_ARM;
00223 test_client.set_joint_angles(arm, POSITIONS_RARM_DEG_DOWN,
00224 "Task1 "+to_string(arm));
00225 ros::Duration(SLEEP_TIME).sleep();
00226 }
00227
00228 void move_armbyarm_pose(AbstAcceptanceTest& test_client){
00229 ROS_INFO("** _move_armbyarm_pose isn\"t yet implemented");
00230 }
00231
00232 void movearms_together(AbstAcceptanceTest& test_client){
00233
00234 test_client.go_initpos();
00235 std::string arm = AbstAcceptanceTest::GRNAME_LEFT_ARM;
00236 test_client.set_joint_angles(arm, POSITIONS_LARM_DEG_UP_SYNC,
00237 to_string(arm),
00238 TASK_DURATION_DEFAULT, false);
00239
00240
00241
00242
00243 arm = AbstAcceptanceTest::GRNAME_RIGHT_ARM;
00244 test_client.set_joint_angles(arm, POSITIONS_RARM_DEG_DOWN,
00245 to_string(arm),
00246 TASK_DURATION_DEFAULT, false);
00247 ros::Duration(SLEEP_TIME).sleep();
00248 }
00249
00250 void set_pose_relative(AbstAcceptanceTest& test_client){
00251 test_client.go_initpos();
00252 double delta = R_Z_SMALLINCREMENT;
00253 double t = DURATION_EACH_SMALLINCREMENT;
00254 double t_total_sec = DURATION_TOTAL_SMALLINCREMENT;
00255 int total_increment = t_total_sec / t;
00256 std::string msg_1 = "Right arm is moving upward with " + to_string(delta) + "mm increment per "
00257 + to_string(t) + "s.";
00258 std::string msg_2 = " (Total " + to_string(delta * total_increment) + "cm over " + to_string(t_total_sec) + "s).";
00259 ROS_INFO("%s",(msg_1 + msg_2).c_str());
00260 for(int i=0;i<total_increment;++i){
00261 std::string msg_eachloop = to_string(i);
00262 msg_eachloop += "th loop;";
00263 test_client.set_pose_relative(AbstAcceptanceTest::GRNAME_RIGHT_ARM,
00264 0,0,delta,0,0,0,
00265 msg_eachloop, t, true);
00266 }
00267 }
00268
00269 void move_head(AbstAcceptanceTest& test_client){
00270 test_client.go_initpos();
00271
00272 for(std::vector< std::vector<double> >::iterator positions = ROTATION_ANGLES_HEAD_1.begin();
00273 positions != ROTATION_ANGLES_HEAD_1.end();
00274 ++positions){
00275 test_client.set_joint_angles(AbstAcceptanceTest::GRNAME_HEAD,
00276 *positions,
00277 "(1);",
00278 TASK_DURATION_HEAD);
00279 }
00280 for(std::vector< std::vector<double> >::iterator positions = ROTATION_ANGLES_HEAD_2.begin();
00281 positions != ROTATION_ANGLES_HEAD_2.end();
00282 ++positions){
00283 test_client.set_joint_angles(AbstAcceptanceTest::GRNAME_HEAD,
00284 *positions,
00285 "(2);",
00286 TASK_DURATION_HEAD);
00287 }
00288 }
00289
00290 void move_torso(AbstAcceptanceTest& test_client){
00291 test_client.go_initpos();
00292 for(std::vector< std::vector<double> >::iterator positions = POSITIONS_TORSO_DEG.begin();
00293 positions != POSITIONS_TORSO_DEG.end();
00294 ++positions){
00295 test_client.set_joint_angles(AbstAcceptanceTest::GRNAME_TORSO,
00296 *positions);
00297 }
00298 }
00299
00300 void overwrite_torso(AbstAcceptanceTest& test_client){
00301 test_client.go_initpos();
00302 test_client.set_joint_angles(
00303 AbstAcceptanceTest::GRNAME_TORSO,
00304 POSITIONS_TORSO_DEG[0],
00305 "(1)",
00306 TASK_DURATION_TORSO,
00307 false);
00308
00309 ros::Duration(SLEEP_OVERWRITE).sleep();
00310
00311 test_client.set_joint_angles(
00312 AbstAcceptanceTest::GRNAME_TORSO,
00313 POSITIONS_TORSO_DEG[1],
00314 "(2)",
00315 TASK_DURATION_TORSO,
00316 true);
00317
00318 ros::Duration(SLEEP_OVERWRITE).sleep();
00319 }
00320
00321 void overwrite_arm(AbstAcceptanceTest& test_client){
00322 test_client.go_initpos();
00323 test_client.set_joint_angles(AbstAcceptanceTest::GRNAME_LEFT_ARM, POSITIONS_LARM_DEG_UP_SYNC,
00324 "(1)",
00325 TASK_DURATION_DEFAULT,
00326 false);
00327 test_client.set_joint_angles(AbstAcceptanceTest::GRNAME_RIGHT_ARM,
00328 POSITIONS_RARM_DEG_UP_SYNC,
00329 std::string("(2) begins. Overwrite previous arm command.\n\t") +
00330 "In the beginning both arm starts to move to the\n\tsame height" +
00331 "but to the left arm interrupting\ncommand is sent and it goes downward.",
00332 TASK_DURATION_DEFAULT,
00333 false);
00334
00335 ros::Duration(SLEEP_OVERWRITE).sleep();
00336
00337 test_client.set_joint_angles(AbstAcceptanceTest::GRNAME_LEFT_ARM,
00338 POSITIONS_LARM_DEG_DOWN,
00339 "(3)",
00340 TASK_DURATION_DEFAULT,
00341 false);
00342
00343 ros::Duration((int)TASK_DURATION_DEFAULT).sleep();
00344
00345 }
00346
00347 void show_workspace(AbstAcceptanceTest& test_client){
00348 test_client.go_initpos();
00349 std::string msg = "; ";
00350
00351 std::string larm = AbstAcceptanceTest::GRNAME_LEFT_ARM;
00352 std::string rarm = AbstAcceptanceTest::GRNAME_RIGHT_ARM;
00353
00354 test_client.set_pose(larm, POS_L_X_NEAR_Y_FAR, RPY_L_X_NEAR_Y_FAR,
00355 msg + to_string(larm), TASK_DURATION_DEFAULT, false);
00356 test_client.set_pose(rarm, POS_R_X_NEAR_Y_FAR, RPY_R_X_NEAR_Y_FAR,
00357 msg + to_string(rarm), TASK_DURATION_DEFAULT, true);
00358
00359 test_client.set_pose(larm, POS_L_X_FAR_Y_FAR, RPY_L_X_FAR_Y_FAR,
00360 msg + to_string(larm), TASK_DURATION_DEFAULT, false);
00361 test_client.set_pose(rarm, POS_R_X_FAR_Y_FAR, RPY_R_X_FAR_Y_FAR,
00362 msg + to_string(rarm), TASK_DURATION_DEFAULT, true);
00363 }
00364
00365 private:
00366 const std::string rtm_robotname;
00367 const std::string rtm_url;
00368
00369 ROS_Client ros;
00370 AcceptanceTestRos acceptance_ros_client;
00371
00372 };
00373
00374
00375 const double AcceptanceTest_Hiro::positions_larm_deg_up[6] = {-4.697, -2.012, -117.108, -17.180, 29.146, -3.739};
00376 const double AcceptanceTest_Hiro::positions_larm_deg_down[6] = {6.196, -5.311, -73.086, -15.287, -12.906, -2.957};
00377 const double AcceptanceTest_Hiro::positions_rarm_deg_down[6] = {-4.949, -3.372, -80.050, 15.067, -7.734, 3.086};
00378 const double AcceptanceTest_Hiro::positions_larm_deg_up_sync[6] = {-4.695, -2.009, -117.103, -17.178, 29.138, -3.738};
00379 const double AcceptanceTest_Hiro::positions_rarm_deg_up_sync[6] = {4.695, -2.009, -117.103, 17.178, 29.138, 3.738};
00380 const double AcceptanceTest_Hiro::rotation_angles_head_1[2][2] = {{0.1, 0.0}, {50.0, 10.0}};
00381 const double AcceptanceTest_Hiro::rotation_angles_head_2[2][2] = { {-50, -10}, {0, 0}};
00382 const double AcceptanceTest_Hiro::positions_torso_deg[2][1] = {{130.0}, {-130.0}};
00383
00384 const double AcceptanceTest_Hiro::R_Z_SMALLINCREMENT = 0.0001;
00385
00386 const double AcceptanceTest_Hiro::pos_l_x_near_y_far[3] = {0.326, 0.474, 1.038};
00387 const double AcceptanceTest_Hiro::rpy_l_x_near_y_far[3] = {-3.075, -1.569, 3.074};
00388 const double AcceptanceTest_Hiro::pos_r_x_near_y_far[3] = {0.326, -0.472, 1.048};
00389 const double AcceptanceTest_Hiro::rpy_r_x_near_y_far[3] = {3.073, -1.569, -3.072};
00390
00391 const double AcceptanceTest_Hiro::pos_l_x_far_y_far[3] = {0.47548142379781055, 0.17430276793604782, 1.0376878025614884};
00392 const double AcceptanceTest_Hiro::rpy_l_x_far_y_far[3] = {-3.075954857224205, -1.5690261926181046, 3.0757659493049574};
00393 const double AcceptanceTest_Hiro::pos_r_x_far_y_far[3] = {0.4755337947019357, -0.17242322190721648, 1.0476395479774052};
00394 const double AcceptanceTest_Hiro::rpy_r_x_far_y_far[3] = {3.0715850722714944, -1.5690204449882248, -3.071395243174742};
00395
00396 const double AcceptanceTest_Hiro::TASK_DURATION_DEFAULT = 4.0;
00397 const double AcceptanceTest_Hiro::DURATION_EACH_SMALLINCREMENT = 0.1;
00398 const double AcceptanceTest_Hiro::TASK_DURATION_TORSO = AcceptanceTest_Hiro::TASK_DURATION_DEFAULT;
00399 const double AcceptanceTest_Hiro::TASK_DURATION_HEAD = AcceptanceTest_Hiro::TASK_DURATION_DEFAULT;
00400 const int AcceptanceTest_Hiro::SLEEP_TIME = 2;
00401 const int AcceptanceTest_Hiro::SLEEP_OVERWRITE = 2;
00402
00403 const int AcceptanceTest_Hiro::DURATION_TOTAL_SMALLINCREMENT = 30;
00404 int main(int argc,char* argv[]){
00405
00406 ros::init(argc,argv,"hironx_ros_client");
00407
00408 AcceptanceTest_Hiro test;
00409 test.run_test_ros();
00410 return 0;
00411 }