test
Dependencies: mbed ros_lib_kinetic nhk19mr2_can_info splitData SerialHalfDuplex_HM
Diff: main.cpp
- Revision:
- 35:b4e1b8f25cd7
- Parent:
- 34:89d701e15cdf
- Child:
- 36:b0edccff7457
--- a/main.cpp Fri Mar 01 12:07:23 2019 +0000 +++ b/main.cpp Mon Mar 04 09:54:47 2019 +0000 @@ -1,7 +1,6 @@ //NHK2019MR2 馬型機構プログラム. //#define VSCODE #ifdef VSCODE -#define _USE_MATH_DEFINES #include <math.h> #include <stdio.h> #else @@ -19,24 +18,25 @@ #include "debug.h" #include "OneLeg.h" ///足先の座標を保存するクラス。x,yやサーボの角度の保存、サーボの駆動も行う。他の足を考慮した処理は別のクラスに任せる。 #include "Walk.h" //歩き方に関するファイル -#define USE_OVERCOME +#include "OverCome.h" +#include "change_walk.h" ////////////あまり変化させないパラメータ。この他は全てmainの上(ParamSetup())にある。 -const int kServoSpan_ms = 6; //サーボの送信間隔 -const float kBetweenServoHalf_m = 0.03 * 0.5; //サーボ間の距離の半分 -float kLegLength1[2] = {0.1, 0.1}; -float kLegLength2[2] = {0.2452 + 0.0025, 0.23}; +const int kServoSpan_ms = 6; //サーボの送信間隔 +const float kBetweenServoHalf_m = 0.034 * 0.5; //サーボ間の距離の半分 +float kLegLength1[2] = {0.15, 0.15}; +float kLegLength2[2] = {0.33, 0.34}; //サーボの正負と座標系の正負の補正.足で一セット。 -const int kServoSign[2][2] = {{1, -1}, {-1, 1}}; +const int kServoSign[2][2] = {{-1, -1}, {-1, -1}}; //欲しい座標系0度でのサーボのICSマネージャーの値 const double kServoValToDegree = 270.0 / (11500 - 3500); //ICSの値を度に変換 const double kOriginDegree[2][2] = { { - (7639 - 3500) * kServoValToDegree, - (7662 - 3500) * kServoValToDegree + 180, + (7300 - 3500) * kServoValToDegree, + (6995 - 3500) * kServoValToDegree + 180, }, { - (6431 - 3500) * kServoValToDegree, - (8135 - 3500) * kServoValToDegree - 180, + (7619 - 3500) * kServoValToDegree, + (7085 - 3500) * kServoValToDegree + 180, }, }; /////////////// @@ -56,7 +56,6 @@ //1サイクルの間、通信は遮断され、サイクル終了後に通信を受け付ける ros::Subscriber<geometry_msgs::Vector3> sub_vel("/cmd_vel", &callback); #endif -OneLeg leg[4]; //各足の位置 FILE *fp; const float kRadToDegree = 180.0 / M_PI; @@ -64,171 +63,96 @@ void MoveServo(OneLeg leg, int legnum, int servo_id); void WaitStdin(char startchar); int FileOpen(); -int IsArrived(int count, int finish); -//段差があるときの機体角度を計算 -//param back_height_on_step:段差の高さ。後ろにあるとする。前にあるときはマイナスを入れる -float GetSteepBodyRad(float back_height_on_step); - ////////調整するべきパラメータ enum WalkWay { STANDUP, - // STRAIGHT, - // TURNLEFT, - // TURNRIGHT, - UP, //足を伸ばして立つ - END, + LRFPOSTURE, + FRONTLEG_ON_SANDDUNE, //前足かける + TURNLEFT, + TURNRIGHT, + // MOVE_FRONTLEG_ON_SANDDUNE, }; -void ParamsSetup(Walk walks[END], OneLeg leg[4]) //各パラメータの設定。減らしていく必要あり -{ - Walk::calctime_s_ = 0.03; //計算周期 - //足の作成、サイズデータのみの足の骨組.4足同じにしている - for (int i = 0; i < 4; i++) - leg[i] = OneLeg(kBetweenServoHalf_m, kLegLength1, kLegLength2); - walks[STANDUP].SetAllLegStandParam(0, 0.2, 0.5); //x,y,time_s.一括で設定できる - /* - //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 = 1, toptime_s = 0.1, buffer_time_s = 0.03; - walks[STRAIGHT].SetAllLegTriangleParam // 4足を取り敢えず一括で設定してから - (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.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足を取り敢えず一括で設定してから - (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]) +float offset_x_m[4] = {-0.1, 0.1, -0.1, 0.1}, + offset_y_m[4] = {0.35, 0.35, 0.35, 0.35}; +//strideはLRFから変更するようにする +float stride_m[4] = {0.2, 0.2, 0.2, 0.2}, + height_m[4] = {0.1, 0.1, 0.1, 0.1}, buffer_height_m = 0.05, + stridetime_s = 1, toptime_s = 0.4, buffer_time_s = 0.2; +/* + LineParam over_come_front[]{ + {.time_s = 0, .x_m = -0.075, .y_m = 0.41}, + {.time_s = 0.2, .x_m = -0.175, .y_m = 0.26}, + {.time_s = 0.4, .x_m = 0.075, .y_m = 0.26}, + {.time_s = 0.6, .x_m = 0.075, .y_m = 0.41}, + {.time_s = 1.6, .x_m = -0.075, .y_m = 0.41}, + }; +*/ +float d_x_m = 0.1; +float start_y_m[4] = {0.41, 0.41, 0.41, 0.41}; +float goal_y_m[4] = {0.41, 0.29, 0.41, 0.29}; +float overcome_height_m[] = {0.1, 0.2, 0.1, 0.2}; +float gravity_dist[] = {0.01, -0.01, 0.01, -0.01}; +int SetWalk(Walk &walk, WalkWay way) +{ + switch (way) + { + case STANDUP: + for (int i = 0; i < 4; i++) + SetOneLegStandParam(walk, i, offset_x_m[i], offset_y_m[i], 0.5); + break; + case LRFPOSTURE: + for (int i = 0; i < 4; i++) + SetOneLegTriangleParam(walk, i, offset_x_m[i], offset_y_m[i], + stride_m[i], height_m[i], buffer_height_m, + stridetime_s, toptime_s, buffer_time_s); + walk.SetOffsetTime(0, 0.5, 0.5, 0); + break; - //TURNRIGHT1のparam - walks[TURNRIGHT].SetAllLegTriangleParam // 4足を取り敢えず一括で設定してから - (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, //足を伸ばして立つ - walks[UP].SetAllLegStandParam(0, 0.30, 2); //x,y,time_s.一括で設定できる - // walks[UP].SetOneLegStandParam(RIGHT_B, 0, 0.30, 2); //x,y,time_s - // walks[UP].SetOneLegStandParam(RIGHT_F, 0, 0.30, 2); //x,y,time_s - // walks[UP].SetOneLegStandParam(LEFT_B, 0, 0.30, 2); //x,y,time_s - // walks[UP].SetOneLegStandParam(RIGHT_B, 0, 0.30, 2); //x,y,time_s + case FRONTLEG_ON_SANDDUNE: //前足かける + // for(int q = 0; q < 4; q++) + // SetOneLegFreeLinesParam(walk, q, over_come_front, sizeof(over_come_front) / sizeof(over_come_front[0])); + // walk.SetOffsetTime(0, 0.5, 0.5, 0); + + OverCome overcome(offset_x_m, start_y_m, d_x_m, goal_y_m, overcome_height_m, gravity_dist, walk.leg); + walk.Copy(overcome.walk); + break; + case TURNLEFT: + for (int i = 0; i < 4; i++) + SetOneLegStandParam(walk, i, offset_x_m[i], offset_y_m[i], 0.5); + break; + case TURNRIGHT: + for (int i = 0; i < 4; i++) + SetOneLegStandParam(walk, i, offset_x_m[i], offset_y_m[i], 0.5); + break; + } + return walk.CheckOrbit(); } -Walk walks[END]; //歩行法 + int main() { - - //足とシリアルサーボの番号 - // RIGHT_B, RIGHT_F, LEFT_B, LEFT_F,}; - //前足かける - float start_x_m[4] = {-0, 0, -0, 0}; //足のoffset - float start_y_m[4] = {.3, .3, .31, .3}; - float d_x_m = 0.15; - float goal_y_m[4] = {.3, 0.2, .31, 0.2}; - float height_m[] = {0.03, 0.13, 0.03, 0.13}; - float gravity_dist[] = {0.075, 0, 0.075, 0}; - OverCome overcome(start_x_m, start_y_m, d_x_m, goal_y_m, height_m, gravity_dist); - //そのまま進む - float d_x_m2 = 0.075; - float height1_m[] = {0.05, 0.05, 0.05, 0.05}; - OverCome overcome1(start_x_m, goal_y_m, d_x_m2, goal_y_m, height1_m, gravity_dist); - //後ろ脚載せる - float height2_m[] = {0.08, 0.08, 0.08, 0.08}; - float start2_y_m[] = {.25, .3, .25, .3}; - float goal2_y_m[] = {.2, .3, .2, .3}; - OverCome overcome2(start_x_m, start2_y_m, d_x_m2, goal2_y_m, height2_m, gravity_dist); - // - float height3_m[] = {0.05, 0.05, 0.05, 0.05}; - float start3_x_m[] = {0, 0, 0, 0.05}; - OverCome overcome3(start3_x_m, goal2_y_m, d_x_m2, goal2_y_m, height3_m, gravity_dist); - //後ろ脚を落とす - float d_x_m4 = 0.1; - float goal4_y_m[] = {.3, .3, .3, .3}; - OverCome overcome4(start_x_m, goal2_y_m, d_x_m4, goal4_y_m, height3_m, gravity_dist); - OverCome overcome5(start_x_m, goal4_y_m, d_x_m4, goal4_y_m, height3_m, gravity_dist); - -/*ROPEを超えた - //足とシリアルサーボの番号 - // RIGHT_B, RIGHT_F, LEFT_B, LEFT_F,}; - //上手く行った - float start_x_m[4] = {-0, 0, -0, 0}; - float start_y_m[4] = {.3, .28, .3, .28}; - float d_x_m = 0.1; - float goal_y_m[4] = {.3, .28, .3, .28}; - float height_m = 0.13; - float gravity_dist[] = {0.075, -0.03, 0.105, 0}; - OverCome rope[] = { - OverCome(start_x_m, start_y_m, d_x_m, goal_y_m, height_m, gravity_dist), - }; -*/ #ifdef VSCODE if (FileOpen()) //csv fileに書き込み return 1; //異常終了したら強制終了 #endif - printf("param set start\r\n"); - ParamsSetup(walks, leg); //各動きの際の足の軌道を設定。パラメータはこの関数内に打ち込む - for (int i = 0; i < END; i++) //軌道のチェック + OneLeg leg[4]; //各足の位置 + for (int i = 0; i < 4; i++) + leg[i] = OneLeg(kBetweenServoHalf_m, kLegLength1, kLegLength2); + Walk walk(leg); //歩行法はここに入れていく + Walk::calctime_s_ = 0.03; + printf("Stand up?\r\n"); + WaitStdin('y'); // ボタンを押したら立つ + if (SetWalk(walk, STANDUP) == 1) { - if (walks[i].CheckOrbit(leg[0]) == 1) //軌道が定義外なら - { - printf("error: move pattern %d\r\n", i); - return 1; //強制終了.errorは内部の関数からprintfで知らせる - } - } - /*ROPEのチェック - for (int i = 0; i < sizeof(rope) / sizeof(rope[0]); i++) - { - if (rope[i].walk.CheckOrbit(leg[0]) == 1) //軌道が定義外なら - { - printf("error: rope pattern %d\r\n", i); - return 1; //強制終了.errorは内部の関数からprintfで知らせる - } - } -*/ - if (overcome.walk.CheckOrbit(leg[0]) == 1) //軌道が定義外なら - { - printf("error: move pattern overcome0\r\n"); + printf("error: stand move\r\n"); return 1; //強制終了.errorは内部の関数からprintfで知らせる } - if (overcome1.walk.CheckOrbit(leg[0]) == 1) //軌道が定義外なら + if (MoveOneCycle(walk, leg) == 1) { - printf("error: move pattern overcome1\r\n"); - return 1; //強制終了.errorは内部の関数からprintfで知らせる - } - - if (overcome2.walk.CheckOrbit(leg[0]) == 1) //軌道が定義外なら - { - printf("error: move pattern overcome 2\r\n"); - return 1; //強制終了.errorは内部の関数からprintfで知らせる - } - if (overcome3.walk.CheckOrbit(leg[0]) == 1) //軌道が定義外なら - { - printf("error: move pattern overcome 3\r\n"); + printf("error: stand move\r\n"); return 1; //強制終了.errorは内部の関数からprintfで知らせる } - - if (overcome4.walk.CheckOrbit(leg[0]) == 1) //軌道が定義外なら - { - printf("error: move pattern overcome 4\r\n"); - return 1; //強制終了.errorは内部の関数からprintfで知らせる - } - - if (overcome5.walk.CheckOrbit(leg[0]) == 1) //軌道が定義外なら - { - printf("error: move pattern overcome 5\r\n"); - return 1; //強制終了.errorは内部の関数からprintfで知らせる - } - printf("Stand up?\r\n"); - WaitStdin('y'); // ボタンを押したら立つ - MoveOneCycle(walks[STANDUP], leg); printf("Move?\r\n"); WaitStdin('y'); // ボタンを押したらスタート #ifdef USE_ROS @@ -239,25 +163,37 @@ nh_mbed.spinOnce(); #else - // for (int k = 0; k < 5; k++)//壁あて.機体保護のため抜いておく - // MoveOneCycle(walks[STRAIGHT], leg); - MoveOneCycle(walks[UP], leg); //立つ - for (int k = 0; k < 1; k++) //前足かける - MoveOneCycle(overcome.walk, leg); - for (int k = 0; k < 5; k++) //そのまま進む - MoveOneCycle(overcome1.walk, leg); - for (int k = 0; k < 1; k++) //後ろ足載せる - MoveOneCycle(overcome2.walk, leg); - for (int k = 0; k < 3; k++) //そのまま進む - MoveOneCycle(overcome3.walk, leg); - for (int k = 0; k < 1; k++) //後ろ足を落とす - MoveOneCycle(overcome4.walk, leg); - for (int k = 0; k < 5; k++) //足上げたまま動く - MoveOneCycle(overcome5.walk, leg); - /*rope用 - for (int k = 0; k < 10; k++) //前足かける - MoveOneCycle(rope[0].walk, leg); -*/ + if (SetWalk(walk, FRONTLEG_ON_SANDDUNE) == 1) + { + printf("error: triangle\r\n"); + return 1; //強制終了.errorは内部の関数からprintfで知らせる + } + + for (int i = 0; i < 2; i++) + { + if (MoveOneCycle(walk, leg) == 1) + { + printf("error: triangle move\r\n"); + return 1; //強制終了.errorは内部の関数からprintfで知らせる + } + } + offset_y_m[LEFT_F] = 0.29; + offset_y_m[RIGHT_F] = 0.29; + if (SetWalk(walk, LRFPOSTURE) == 1) + { + printf("error: triangle\r\n"); + return 1; //強制終了.errorは内部の関数からprintfで知らせる + } + + for (int i = 0; i < 20; i++) + { + if (MoveOneCycle(walk, leg) == 1) + { + printf("error: triangle move\r\n"); + return 1; //強制終了.errorは内部の関数からprintfで知らせる + } + } + printf("program end\r\n"); #ifdef VSCODE fclose(fp); @@ -271,7 +207,7 @@ timer.reset(); timer.start(); #endif - int count = walkway.GetOneWalkTime() / walkway.calctime_s_; + int count = walkway.orbit[0].GetOneWalkTime() / walkway.calctime_s_; for (int i = 0; i < count; i++) { #ifndef VSCODE @@ -353,19 +289,20 @@ int state = cmd_vel.z; //閾値は要検討 if (right_vel < left_vel) - MoveOneCycle(walks[TURNRIGHT], leg); - else if (left_vel < right_vel) - MoveOneCycle(walks[TURNLEFT], leg); + { + stride_m[LEFT_F] = 0.2; + stride_m[RIGHT_F] = 0.2; + stride_m[LEFT_B] = 0.1; + stride_m[RIGHT_B] = 0.1; + } else - MoveOneCycle(walks[STRAIGHT], leg); + { + stride_m[LEFT_F] = 0.1; + stride_m[RIGHT_F] = 0.1; + stride_m[LEFT_B] = 0.2; + stride_m[RIGHT_B] = 0.2; + } + SetWalk(walk, LRFPOSTURE); + MoveOneCycle(walk, leg); } -#endif -/* -//param back_height_on_step:段差の高さ。後ろにあるとする。前にあるときはマイナスを入れる -float GetSteepBodyRad(float back_height_on_step) -{ - float offset_hight = back_height_on_step + leg[LEFT_B].GetY_m() - leg[LEFT_B].GetY_m(); - float theta = atan2(offset_hight, (float)(sqrt(0.09 - offset_hight * offset_hight))); - return theta; -} -*/ \ No newline at end of file +#endif \ No newline at end of file