test

Dependencies:   mbed ros_lib_kinetic nhk19mr2_can_info splitData SerialHalfDuplex_HM

Revision:
32:dc684a0b8448
Parent:
31:86eb746eaed4
Child:
33:945d634d4c9b
--- a/main.cpp	Thu Feb 28 03:52:09 2019 +0000
+++ b/main.cpp	Thu Feb 28 08:48:21 2019 +0000
@@ -66,7 +66,7 @@
 };
 FILE *fp;
 const float kRadToDegree = 180.0 / M_PI;
-void MoveOneCycle(Walk walkway, OneLeg leg[4]);
+int MoveOneCycle(Walk walkway, OneLeg leg[4]);
 void MoveServo(OneLeg leg, int legnum, int servo_id);
 void WaitStdin(char startchar);
 int FileOpen();
@@ -100,71 +100,94 @@
         leg[i] = OneLeg(kBetweenServoHalf_m, kLegLength1, kLegLength2);
     walks[STANDUP].SetAllLegStandParam(0, 0.2, 0.5); //x,y,time_s.一括で設定できる
 
-    //STRAIGT 論文通りのとき、start_y_mは <=0.32
-    float start_x_m = 0.075, start_y_m = 0.2, stride_m = 0.15, height_m = 0.03, buffer_height_m = 0.01,
+    //STRAIGT 論文通りのとき、offset_y_mは <=0.32
+    float offset_x_m = -0.05, offset_y_m = 0.20, stride_m = 0.12, height_m = 0.05, buffer_height_m = 0.01,
           stridetime_s = 0.3, toptime_s = 0.07, buffer_time_s = 0.03;
     walks[STRAIGHT].SetAllLegTriangleParam // 4足を取り敢えず一括で設定してから
-        (start_x_m, start_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s);
+        (offset_x_m, offset_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s);
+    walks[STRAIGHT].ChangeOneParam(LEFT_F, OFFSET_X_M, 0);
+    walks[STRAIGHT].ChangeOneParam(RIGHT_F, OFFSET_X_M, 0);
+    walks[STRAIGHT].ChangeOneParam(LEFT_F, OFFSET_Y_M, 0.2);
+    walks[STRAIGHT].ChangeOneParam(RIGHT_F, OFFSET_Y_M, 0.2);
     walks[STRAIGHT].SetOffsetTime(0, 0.5, 0.5, 0);
-/*
+
     //TURNLEFTのparam
-    float stride_short_m = 0.2, stride_long_m = 0.1, start_x_short_m = 0.1, start_x_long_m = 0.051;
-    stridetime_s = 0.2, toptime_s = 0.07, buffer_time_s = 0.03,
-    start_y_m = 0.2, height_m = 0.03, buffer_height_m = 0.01;
+    float stride_short_m = 0.05, stride_long_m = 0.25;
+    stridetime_s = 0.3, toptime_s = 0.07, buffer_time_s = 0.03,
+    offset_x_m=0, offset_y_m = 0.2, height_m = 0.03, buffer_height_m = 0.01;
     walks[TURNLEFT].SetAllLegTriangleParam // 4足を取り敢えず一括で設定してから
-        (start_x_short_m, start_y_m, stride_short_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s);
-    walks[TURNLEFT].ChangeOneParam(LEFT_F, STRIDE_M, stride_long_m); //一部のパラメータを変更
-    walks[TURNLEFT].ChangeOneParam(LEFT_B, STRIDE_M, stride_long_m);
-    walks[TURNLEFT].ChangeOneParam(LEFT_F, STRAT_X_M, start_x_long_m); //一部のパラメータを変更
-    walks[TURNLEFT].ChangeOneParam(LEFT_B, STRAT_X_M, start_x_long_m);
+        (offset_x_m, offset_y_m, stride_long_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s);
+    walks[TURNLEFT].ChangeOneParam(LEFT_F, STRIDE_M, stride_short_m); //一部のパラメータを変更
+    walks[TURNLEFT].ChangeOneParam(LEFT_B, STRIDE_M, stride_short_m);
     walks[TURNLEFT].SetOffsetTime(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1])
 
     //TURNRIGHT1のparam
     walks[TURNRIGHT].SetAllLegTriangleParam // 4足を取り敢えず一括で設定してから
-      (start_x_short_m, start_y_m, stride_short_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s);
-    walks[TURNRIGHT].ChangeOneParam(RIGHT_F, STRIDE_M, stride_long_m); //一部のパラメータを変更
-    walks[TURNRIGHT].ChangeOneParam(RIGHT_B, STRIDE_M, stride_long_m);
-    walks[TURNLEFT].ChangeOneParam(RIGHT_F, STRAT_X_M, start_x_long_m); //一部のパラメータを変更
-    walks[TURNLEFT].ChangeOneParam(RIGHT_B, STRAT_X_M, start_x_long_m);
+      (offset_x_m, offset_y_m, stride_long_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s);
+    walks[TURNRIGHT].ChangeOneParam(RIGHT_F, STRIDE_M, stride_short_m); //一部のパラメータを変更
+    walks[TURNRIGHT].ChangeOneParam(RIGHT_B, STRIDE_M, stride_short_m);
     walks[TURNRIGHT].SetOffsetTime(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1])
 
     // UP, //足を伸ばして立つ
+    LineParam up[] = {
+        {.time_s = 1, .x_m = 0, .y_m = 0.3},
+        {.time_s = 0, .x_m = 0, .y_m = 0.3}};
     walks[UP].SetAllLegStandParam(0, 0.3, 1.2); //x,y,time_s.一括で設定できる
 
     // OVERCOME 前足を乗せる
-    LineParam over_come_front[] = {
-        {.time_s = 0.6, .x_m = -0.1, .y_m = 0.3},
-        {.time_s = 0.2, .x_m = -0.1, .y_m = 0.3},
-        {.time_s = 0.2, .x_m = -0.13, .y_m = 0.16},
-        {.time_s = 0.2, .x_m = 0.08, .y_m = 0.16},
-        {.time_s = 0.6, .x_m = 0.08, .y_m = 0.2},
-        {.time_s = 0, .x_m = 0.08, .y_m = 0.2}};
-    walks[OVERCOME].SetAllLegFreeLinesParam(over_come_front, sizeof(over_come_front)/sizeof(over_come_front[0])); //前足設定
-    walks[OVERCOME].SetOneLegStandParam(LEFT_B, 0, 0.3, frontleg.GetOneWalkTime());
-    walks[OVERCOME].SetOneLegStandParam(RIGHT_B, 0, 0.3, frontleg.GetOneWalkTime());
-    walks[OVERCOME].SetOffsetTime(0, 0.5, 0, 0);
+    
+    LineParam over_come_front_r[] = {
+        {.time_s = 0.6, .x_m = -0, .y_m = 0.32},
+        {.time_s = 0.2, .x_m = -0, .y_m = 0.32},
+        {.time_s = 0.2, .x_m = -0.13, .y_m = 0.15},
+        {.time_s = 0.2, .x_m = 0.12, .y_m = 0.15},
+        {.time_s = 0.6, .x_m = 0.12, .y_m = 0.15},
+        {.time_s = 0, .x_m = 0.12, .y_m = 0.2}};
+    LineParam over_come_front_l[] = {
+        {.time_s = 0.6, .x_m = -0, .y_m = 0.32},
+        {.time_s = 0.6, .x_m = -0, .y_m = 0.32},
+        {.time_s = 0.2, .x_m = -0, .y_m = 0.32},
+        {.time_s = 0.2, .x_m = -0.13, .y_m = 0.15},
+        {.time_s = 0.2, .x_m = 0.2, .y_m = 0.15},
+        {.time_s = 0, .x_m = 0.2, .y_m = 0.2}};
+    LineParam over_come_back[] = {
+        {.time_s = 0.6, .x_m = 0, .y_m = 0.3},
+        {.time_s = 0.2, .x_m = 0, .y_m = 0.3},
+        {.time_s = 1, .x_m = -0.1,.y_m = 0.3},
+        {.time_s = 0, .x_m = -0.1,.y_m = 0.3},
+    };
+    walks[OVERCOME].SetOneLegFreeLinesParam(RIGHT_F,  over_come_front_r, sizeof(over_come_front_r)/ sizeof(over_come_front_r[0]));
+    walks[OVERCOME].SetOneLegFreeLinesParam(LEFT_F,  over_come_front_l, sizeof(over_come_front_l)/sizeof(over_come_front_l[0]));
+    walks[OVERCOME].SetOneLegFreeLinesParam(LEFT_B,  over_come_back, sizeof(over_come_back)/sizeof(over_come_back[0]));
+    walks[OVERCOME].SetOneLegFreeLinesParam(RIGHT_B,  over_come_back, sizeof(over_come_back)/sizeof(over_come_back[0]));
 
     // SANDDUNE, //前足だけがsandduneに乗った状態で進む
-    start_x_m = 0.02, start_y_m = 0.3, stride_m = 0.1, height_m = 0.03, buffer_height_m = 0.01,
+    offset_x_m = -0.03, offset_y_m = 0.3, stride_m = 0.1, height_m = 0.03, buffer_height_m = 0.01,
     stridetime_s = 0.2, toptime_s = 0.07, buffer_time_s = 0.03;
     walks[SANDDUNE].SetAllLegTriangleParam // 4足一括で設定
-        (start_x_m, start_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s);
+        (offset_x_m, offset_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s);
+    walks[SANDDUNE].ChangeOneParam(LEFT_F, OFFSET_X_M, 0);
+    walks[SANDDUNE].ChangeOneParam(RIGHT_F, OFFSET_X_M, 0);
+    walks[SANDDUNE].ChangeOneParam(LEFT_F, OFFSET_Y_M, offset_y_m - 0.1);
+    walks[SANDDUNE].ChangeOneParam(RIGHT_F, OFFSET_Y_M, offset_y_m - 0.1);
     walks[SANDDUNE].SetOffsetTime(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1])
 
     // OVERCOME_BACK, //後ろ足を乗せる
     float offset_x_back = -0.05;
-    Lineparam overcomebackParams[6] = {
-        {.time_s = 0.8, .x_m = -0.05 + offset_x_back, .y_m = 0.3},
-        {.time_s = 0.2, .x_m = -0.05 + offset_x_back, .y_m = 0.3},
-        {.time_s = 0.2, .x_m = -0.1 + offset_x_back, .y_m = 0.16},
-        {.time_s = 0.2, .x_m = 0.1 + offset_x_back, .y_m = 0.16},
-        {.time_s = 0.2, .x_m = 0.1 + offset_x_back, .y_m = 0.2},
-        {.time_s = 0.6, .x_m = 0.05 + offset_x_back, .y_m = 0.2},
+    LineParam overcomebackParams[] = {
+        {.time_s = 0.8, .x_m = -0.05f + offset_x_back, .y_m = 0.3},
+        {.time_s = 0.2, .x_m = -0.05f + offset_x_back, .y_m = 0.3},
+        {.time_s = 0.2, .x_m = -0.1f + offset_x_back, .y_m = 0.16},
+        {.time_s = 0.2, .x_m = 0.1f + offset_x_back, .y_m = 0.16},
+        {.time_s = 0.2, .x_m = 0.1f + offset_x_back, .y_m = 0.2},
+        {.time_s = 0.8, .x_m = 0.05f + offset_x_back, .y_m = 0.2},
+        {.time_s = 0, .x_m = 0.05f + offset_x_back, .y_m = 0.2},
     };
-    Lineparam standbackParams[3] = {
-        {.time_s = 0.6, .x_m = 0.0 + offset_x_back, .y_m = 0.2},
-        {.time_s = 0.2, .x_m = 0.0 + offset_x_back, .y_m = 0.2},
-        {.time_s = 0.6, .x_m = -0.05 + offset_x_back, .y_m = 0.2},
+    LineParam standbackParams[] = {
+        {.time_s = 0.6, .x_m = 0.0f + offset_x_back, .y_m = 0.2},
+        {.time_s = 0.2, .x_m = 0.0f + offset_x_back, .y_m = 0.2},
+        {.time_s = 0.6, .x_m = -0.05f + offset_x_back, .y_m = 0.2},
+        {.time_s = 0, .x_m = -0.05f + offset_x_back, .y_m = 0.2},
     };
     walks[OVERCOME_BACK].SetOneLegFreeLinesParam(LEFT_F, standbackParams, sizeof(standbackParams) / sizeof(standbackParams[0]));
     walks[OVERCOME_BACK].SetOneLegFreeLinesParam(RIGHT_F, standbackParams, sizeof(standbackParams) / sizeof(standbackParams[0]));
@@ -173,35 +196,33 @@
     walks[OVERCOME_BACK].SetOffsetTime(0, 0, 0.5, 0);
 
     // STRAIGHT_W, //両足がsandduneに乗った状態で進む
-    start_x_m = -0.04, start_y_m = 0.2, stride_m = 0.1, height_m = 0.03, buffer_height_m = 0.01,
+    offset_x_m = -0.09, offset_y_m = 0.2, stride_m = 0.1, height_m = 0.03, buffer_height_m = 0.01,
     stridetime_s = 0.2, toptime_s = 0.07, buffer_time_s = 0.03;
     walks[STRAIGHT_W].SetAllLegTriangleParam // 4足一括で設定
-        (start_x_m, start_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s);
-    walks[STRAIGHT_W].ChangeOneParam(LEFT_F, STRAT_X_M, 0.05);
-    walks[STRAIGHT_W].ChangeOneParam(RIGHT_F, STRAT_X_M, 0.05);
+        (offset_x_m, offset_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s);
+    walks[STRAIGHT_W].ChangeOneParam(LEFT_F, OFFSET_X_M, 0);
+    walks[STRAIGHT_W].ChangeOneParam(RIGHT_F, OFFSET_X_M, 0);
     walks[STRAIGHT_W].SetOffsetTime(0, 0.5, 0.5, 0);
 
-    // ROPE_F, //ropeをまたぐ(前足)
-    float start_x_front_m = 0.05; //前足のstart_x
-    start_x_m = .72, start_y_m = 0.3, stride_m = .15, height_m = 0.03, buffer_height_m = 0.01,
+   // ROPE_F, //ropeをまたぐ(前足)
+    offset_x_m = 0, offset_y_m = 0.3, stride_m = .15, height_m = 0.03, buffer_height_m = 0.01,
     stridetime_s = 1, toptime_s = 0.35, buffer_time_s = 0.05;
     walks[ROPE_F].SetAllLegTriangleParam // 4足一括で設定
-        (start_x_m, start_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s);
+        (offset_x_m, offset_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s);
     walks[ROPE_F].ChangeOneParam(LEFT_F, HEIGHT_M, 0.15); //前足だけ足を延ばす
     walks[ROPE_F].ChangeOneParam(RIGHT_F, HEIGHT_M, 0.15);
     walks[ROPE_F].SetOffsetTime(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1])
 
     // ROPE_B,   //ropeをまたぐ(後ろ足)
-    start_x_m = 0, start_y_m = 0.3, stride_m = .15, height_m = 0.03, buffer_height_m = 0.01,
+    offset_x_m = -0.05, offset_y_m = 0.3, stride_m = .1, height_m = 0.03, buffer_height_m = 0.01,
     stridetime_s = 1, toptime_s = 0.35, buffer_time_s = 0.05;
     walks[ROPE_B].SetAllLegTriangleParam // 4足一括で設定
-        (start_x_m, start_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s);
+        (offset_x_m, offset_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s);
     walks[ROPE_B].ChangeOneParam(LEFT_B, HEIGHT_M, 0.15); //後ろ足だけ足を延ばす
     walks[ROPE_B].ChangeOneParam(RIGHT_B, HEIGHT_M, 0.15);
-    walks[ROPE_B].ChangeOneParam(LEFT_B, STRAT_X_M, -0.02);
-    walks[ROPE_B].ChangeOneParam(RIGHT_B, STRAT_X_M, -0.02);
+    walks[ROPE_B].ChangeOneParam(LEFT_B, OFFSET_X_M, -0.07);
+    walks[ROPE_B].ChangeOneParam(RIGHT_B, OFFSET_X_M, -0.07);
     walks[ROPE_B].SetOffsetTime(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1])
-    */
 }
 Walk walks[END]; //歩行法
 int main()
@@ -216,7 +237,7 @@
     {
         if (walks[i].CheckOrbit(leg[0]) == 1) //軌道が定義外なら
         {
-            printf("error: move pattern %d", i);
+            printf("error: move pattern %d\r\n", i);
             return 1; //強制終了.errorは内部の関数からprintfで知らせる
         }
     }
@@ -232,21 +253,36 @@
     while (1)
         nh_mbed.spinOnce();
 #else
+    
+        for(int k=0;k<5;k++)MoveOneCycle(walks[STRAIGHT], leg);
+        for(int k=0;k<1;k++)MoveOneCycle(walks[UP], leg);
+        for(int k=0;k<1;k++)MoveOneCycle(walks[OVERCOME],leg);
+        for(int k=0;k<5;k++) MoveOneCycle(walks[SANDDUNE],leg);
+        for(int k=0;k<1;k++)MoveOneCycle(walks[OVERCOME_BACK],leg);
+        for(int k=0;k<3;k++)MoveOneCycle(walks[STRAIGHT_W], leg);
+//        for(int k=0;k<5;k++)Move(*straight_w2, leg,(*straight_w2).GetTheta(0.1));
+//        for(int k=0;k<3;k++)Move(*straight, leg);
+/*
     for (int i = 1; i < END; i++) //ENDになるまでWalkWayの順に動作
     {
-        DEBUG("Move %d\r\n", i);
-        for (int j = 0; j < 50; j++) //debug用に2歩進む
-            MoveOneCycle(walks[i], leg);
+        printf("Move %d\r\n", i);
+        for (int j = 0; j < 20; j++) //debug用に2歩進む
+            {
+                if(MoveOneCycle(walks[i], leg) == 1)
+                    printf("error:In MoveOneCycle. WalkWay %d\r\n",i);
+            }
     }
+  
     MoveOneCycle(walks[STANDUP], leg); //最後はLRFを保護するためSTANDUPの状態で終わる
-    printf("program end\r\n");
+  
+  */  printf("program end\r\n");
 #ifdef VSCODE
     fclose(fp);
 #endif
 #endif
 }
-//一サイクル分進む
-void MoveOneCycle(Walk walkway, OneLeg leg[4])
+//一サイクル分進む.return 1:異常終了
+int MoveOneCycle(Walk walkway, OneLeg leg[4])
 {
 #ifndef VSCODE
     timer.reset();
@@ -260,7 +296,10 @@
 #endif
         //4本の足それぞれの足先サーボ角度更新
         if (walkway.Cal4LegsPosi(leg) == 1)
+        {
             printf("error: time = %f\r\n", i * walkway.calctime_s_);
+            return 1;
+        }
 #ifdef USE_CAN
         SendRad(leg[2], leg[3]); //slave_mbed分の足の目標位置を送信
 #endif
@@ -290,6 +329,7 @@
         }
 #endif
     }
+    return 0;
 }
 void MoveServo(OneLeg leg, int serial_num, int servo_id)
 {