test
Dependencies: mbed ros_lib_kinetic nhk19mr2_can_info splitData SerialHalfDuplex_HM
main.cpp
- Committer:
- shimizuta
- Date:
- 2019-02-28
- Revision:
- 32:dc684a0b8448
- Parent:
- 31:86eb746eaed4
- Child:
- 33:945d634d4c9b
File content as of revision 32:dc684a0b8448:
//NHK2019MR2 馬型機構プログラム. //#define VSCODE #ifdef VSCODE #define _USE_MATH_DEFINES #include <math.h> #include <stdio.h> #else #include "mbed.h" #include "pinnames.h" #include "KondoServo.h" #include "pi.h" #include "can.h" #define USE_CAN //can通信するならdefine.しないなら切らないとエラー出る //#define USE_ROS #include <ros.h> #include <geometry_msgs/Vector3.h> #endif //#define DEBUG_ON //デバッグ用。使わないときはコメントアウト #include "debug.h" #include "OneLeg.h" ///足先の座標を保存するクラス。x,yやサーボの角度の保存、サーボの駆動も行う。他の足を考慮した処理は別のクラスに任せる。 #include "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 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, }, { (6431 - 3500) * kServoValToDegree, (8135 - 3500) * kServoValToDegree - 180, }, }; /////////////// #ifndef VSCODE Timer timer; KondoServo servo[2] = { KondoServo(pin_serial_servo_tx[0], pin_serial_servo_rx[0]), KondoServo(pin_serial_servo_tx[1], pin_serial_servo_rx[1]), }; DigitalOut led[4] = {DigitalOut(LED1), DigitalOut(LED2), DigitalOut(LED3), DigitalOut(LED4)}; #endif #ifdef USE_ROS ros::NodeHandle nh_mbed; //ROSからのコールバック関数 void callback(const geometry_msgs::Vector3 &cmd_vel); //LPからの左右速度比を受けとり、それをもとに歩行パターンを決定する //1サイクルの間、通信は遮断され、サイクル終了後に通信を受け付ける ros::Subscriber<geometry_msgs::Vector3> sub_vel("/cmd_vel", &callback); #endif OneLeg leg[4]; //各足の位置 enum LegNum //足とシリアルサーボの番号 { RIGHT_B, RIGHT_F, LEFT_B, LEFT_F, }; FILE *fp; const float kRadToDegree = 180.0 / M_PI; int MoveOneCycle(Walk walkway, OneLeg leg[4]); 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, //足を伸ばして立つ OVERCOME, //前足を乗せる SANDDUNE, //前足だけがsandduneに乗った状態で進む OVERCOME_BACK, //後ろ足を乗せる STRAIGHT_W, //両足がsandduneに乗った状態で進む ROPE_F, //ropeをまたぐ(前足) ROPE_B, //ropeをまたぐ(後ろ足) END, STRAIGHT_W2, //後足が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 = 0.3, toptime_s = 0.07, 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]) //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, //足を伸ばして立つ 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_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に乗った状態で進む 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足一括で設定 (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[] = { {.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[] = { {.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])); walks[OVERCOME_BACK].SetOneLegFreeLinesParam(LEFT_B, overcomebackParams, sizeof(overcomebackParams) / sizeof(overcomebackParams[0])); walks[OVERCOME_BACK].SetOneLegFreeLinesParam(RIGHT_B, overcomebackParams, sizeof(overcomebackParams) / sizeof(overcomebackParams[0])); walks[OVERCOME_BACK].SetOffsetTime(0, 0, 0.5, 0); // STRAIGHT_W, //両足がsandduneに乗った状態で進む 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足一括で設定 (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をまたぐ(前足) 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足一括で設定 (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をまたぐ(後ろ足) 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足一括で設定 (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, 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() { #ifdef VSCODE if (FileOpen()) //csv fileに書き込み return 1; //異常終了したら強制終了 #endif DEBUG("param set start"); ParamsSetup(walks, leg); //各動きの際の足の軌道を設定。パラメータはこの関数内に打ち込む for (int i = 0; i < END; i++) //軌道のチェック { if (walks[i].CheckOrbit(leg[0]) == 1) //軌道が定義外なら { printf("error: move pattern %d\r\n", i); return 1; //強制終了.errorは内部の関数からprintfで知らせる } } printf("Stand up?\r\n"); WaitStdin('y'); // ボタンを押したら立つ MoveOneCycle(walks[STANDUP], leg); printf("Move?\r\n"); WaitStdin('y'); // ボタンを押したらスタート #ifdef USE_ROS nh_mbed.getHardware()->setBaud(115200); nh_mbed.initNode(); nh_mbed.subscribe(sub_vel); 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の順に動作 { 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"); #ifdef VSCODE fclose(fp); #endif #endif } //一サイクル分進む.return 1:異常終了 int MoveOneCycle(Walk walkway, OneLeg leg[4]) { #ifndef VSCODE timer.reset(); timer.start(); #endif int count = walkway.GetOneWalkTime() / walkway.calctime_s_; for (int i = 0; i < count; i++) { #ifndef VSCODE float time_s = timer.read(); #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 //自身が動かす足のサーボを動かす MoveServo(leg[0], 0, 0); MoveServo(leg[1], 1, 0); #ifndef VSCODE wait_ms(kServoSpan_ms); #endif MoveServo(leg[0], 0, 1); MoveServo(leg[1], 1, 1); #ifdef VSCODE //ファイルに書き込み。time[s],x[0],y[0],x[1],y[1],x[2],y[2],x[3],y[3]の順 fprintf(fp, "%f", i * walkway.calctime_s_); for (int i = 0; i < 4; i++) fprintf(fp, ",%f,%f", leg[i].GetX_m(), leg[i].GetY_m()); fprintf(fp, "\r\n"); #else //計算周期がwalkway.calctime_s_になるようwait float rest_time_s = walkway.calctime_s_ - (timer.read() - time_s); if (rest_time_s > 0) wait(rest_time_s); else { //計算周期が達成できないときはDEBUGで知らせるだけ。動きはする。 DEBUG("error: rest_time_s = %f in Move()\r\n", rest_time_s); led[0] = 1; } #endif } return 0; } void MoveServo(OneLeg leg, int serial_num, int servo_id) { #ifndef VSCODE float degree = leg.GetRad(servo_id) * kRadToDegree; //サーボの座標系に変更 float servo_degree = kServoSign[serial_num][servo_id] * degree + kOriginDegree[serial_num][servo_id]; // DEBUG("servo_degree[%d][%d],%f\r\n", serial_num, servo_id, servo_degree); servo[serial_num].set_degree(servo_id, servo_degree); #endif } void WaitStdin(char startchar) { #ifndef USE_ROS char str[255] = {}; do { printf("put '%c', then start\r\n", startchar); scanf("%s", str); } while (str[0] != startchar); #endif } int FileOpen() //1:異常終了 { if ((fp = fopen("data.csv", "w")) == NULL) { printf("error : FileSave()\r\n"); return 1; } fprintf(fp, "time[s],x[0],y[0],x[1],y[1],x[2],y[2],x[3],y[3]\r\n"); return 0; } #ifdef USE_ROS void callback(const geometry_msgs::Vector3 &cmd_vel) { float left_vel = cmd_vel.x; float right_vel = cmd_vel.y; //閾値は要検討 if (right_vel < left_vel) MoveOneCycle(walks[TURNRIGHT], leg); else if (left_vel < right_vel) MoveOneCycle(walks[TURNLEFT], leg); else MoveOneCycle(walks[STRAIGHT], 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; }