test
Dependencies: mbed ros_lib_kinetic nhk19mr2_can_info splitData SerialHalfDuplex_HM
main.cpp@32:dc684a0b8448, 2019-02-28 (annotated)
- Committer:
- shimizuta
- Date:
- Thu Feb 28 08:48:21 2019 +0000
- Revision:
- 32:dc684a0b8448
- Parent:
- 31:86eb746eaed4
- Child:
- 33:945d634d4c9b
a
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
shimizuta | 11:e81425872740 | 1 | //NHK2019MR2 馬型機構プログラム. |
shimizuta | 28:8e1cbeffe6c2 | 2 | //#define VSCODE |
shimizuta | 27:79b4b932a6dd | 3 | #ifdef VSCODE |
shimizuta | 27:79b4b932a6dd | 4 | #define _USE_MATH_DEFINES |
shimizuta | 27:79b4b932a6dd | 5 | #include <math.h> |
shimizuta | 27:79b4b932a6dd | 6 | #include <stdio.h> |
shimizuta | 27:79b4b932a6dd | 7 | #else |
yuto17320508 | 0:f000d896d188 | 8 | #include "mbed.h" |
shimizuta | 9:905f93247688 | 9 | #include "pinnames.h" |
shimizuta | 11:e81425872740 | 10 | #include "KondoServo.h" |
shimizuta | 14:d7cb429946f4 | 11 | #include "pi.h" |
shimizuta | 16:0069a56f11a3 | 12 | #include "can.h" |
shimizuta | 27:79b4b932a6dd | 13 | #define USE_CAN //can通信するならdefine.しないなら切らないとエラー出る |
shimizuta | 29:7d8b8011a88d | 14 | //#define USE_ROS |
shimizuta | 27:79b4b932a6dd | 15 | #include <ros.h> |
shimizuta | 27:79b4b932a6dd | 16 | #include <geometry_msgs/Vector3.h> |
shimizuta | 27:79b4b932a6dd | 17 | #endif |
shimizuta | 27:79b4b932a6dd | 18 | //#define DEBUG_ON //デバッグ用。使わないときはコメントアウト |
shimizuta | 27:79b4b932a6dd | 19 | #include "debug.h" |
shimizuta | 11:e81425872740 | 20 | #include "OneLeg.h" ///足先の座標を保存するクラス。x,yやサーボの角度の保存、サーボの駆動も行う。他の足を考慮した処理は別のクラスに任せる。 |
shimizuta | 11:e81425872740 | 21 | #include "Walk.h" //歩き方に関するファイル |
yuto17320508 | 4:fffdb273836e | 22 | |
shimizuta | 27:79b4b932a6dd | 23 | ////////////あまり変化させないパラメータ。この他は全てmainの上(ParamSetup())にある。 |
shimizuta | 27:79b4b932a6dd | 24 | const int kServoSpan_ms = 6; //サーボの送信間隔 |
shimizuta | 19:1adc7302cfd9 | 25 | const float kBetweenServoHalf_m = 0.03 * 0.5; //サーボ間の距離の半分 |
shimizuta | 19:1adc7302cfd9 | 26 | float kLegLength1[2] = {0.1, 0.1}; |
shimizuta | 29:7d8b8011a88d | 27 | float kLegLength2[2] = {0.2452 + 0.0025, 0.23}; |
shimizuta | 14:d7cb429946f4 | 28 | //サーボの正負と座標系の正負の補正.足で一セット。 |
shimizuta | 27:79b4b932a6dd | 29 | const int kServoSign[2][2] = {{1, -1}, {-1, 1}}; |
shimizuta | 14:d7cb429946f4 | 30 | //欲しい座標系0度でのサーボのICSマネージャーの値 |
shimizuta | 27:79b4b932a6dd | 31 | const double kServoValToDegree = 270.0 / (11500 - 3500); //ICSの値を度に変換 |
shimizuta | 14:d7cb429946f4 | 32 | const double kOriginDegree[2][2] = { |
shimizuta | 14:d7cb429946f4 | 33 | { |
shimizuta | 31:86eb746eaed4 | 34 | (7639 - 3500) * kServoValToDegree, |
shimizuta | 31:86eb746eaed4 | 35 | (7662 - 3500) * kServoValToDegree + 180, |
shimizuta | 14:d7cb429946f4 | 36 | }, |
shimizuta | 14:d7cb429946f4 | 37 | { |
shimizuta | 31:86eb746eaed4 | 38 | (6431 - 3500) * kServoValToDegree, |
shimizuta | 31:86eb746eaed4 | 39 | (8135 - 3500) * kServoValToDegree - 180, |
shimizuta | 14:d7cb429946f4 | 40 | }, |
shimizuta | 14:d7cb429946f4 | 41 | }; |
shimizuta | 9:905f93247688 | 42 | /////////////// |
shimizuta | 27:79b4b932a6dd | 43 | #ifndef VSCODE |
shimizuta | 9:905f93247688 | 44 | Timer timer; |
shimizuta | 11:e81425872740 | 45 | KondoServo servo[2] = { |
shimizuta | 11:e81425872740 | 46 | KondoServo(pin_serial_servo_tx[0], pin_serial_servo_rx[0]), |
shimizuta | 11:e81425872740 | 47 | KondoServo(pin_serial_servo_tx[1], pin_serial_servo_rx[1]), |
shimizuta | 11:e81425872740 | 48 | }; |
shimizuta | 27:79b4b932a6dd | 49 | DigitalOut led[4] = {DigitalOut(LED1), DigitalOut(LED2), DigitalOut(LED3), DigitalOut(LED4)}; |
shimizuta | 27:79b4b932a6dd | 50 | #endif |
shimizuta | 27:79b4b932a6dd | 51 | #ifdef USE_ROS |
shimizuta | 27:79b4b932a6dd | 52 | ros::NodeHandle nh_mbed; |
shimizuta | 27:79b4b932a6dd | 53 | //ROSからのコールバック関数 |
shimizuta | 27:79b4b932a6dd | 54 | void callback(const geometry_msgs::Vector3 &cmd_vel); |
shimizuta | 27:79b4b932a6dd | 55 | //LPからの左右速度比を受けとり、それをもとに歩行パターンを決定する |
shimizuta | 27:79b4b932a6dd | 56 | //1サイクルの間、通信は遮断され、サイクル終了後に通信を受け付ける |
shimizuta | 27:79b4b932a6dd | 57 | ros::Subscriber<geometry_msgs::Vector3> sub_vel("/cmd_vel", &callback); |
shimizuta | 27:79b4b932a6dd | 58 | #endif |
shimizuta | 27:79b4b932a6dd | 59 | OneLeg leg[4]; //各足の位置 |
shimizuta | 27:79b4b932a6dd | 60 | enum LegNum //足とシリアルサーボの番号 |
shimizuta | 27:79b4b932a6dd | 61 | { |
shimizuta | 27:79b4b932a6dd | 62 | RIGHT_B, |
shimizuta | 27:79b4b932a6dd | 63 | RIGHT_F, |
shimizuta | 27:79b4b932a6dd | 64 | LEFT_B, |
shimizuta | 27:79b4b932a6dd | 65 | LEFT_F, |
shimizuta | 9:905f93247688 | 66 | }; |
shimizuta | 27:79b4b932a6dd | 67 | FILE *fp; |
shimizuta | 11:e81425872740 | 68 | const float kRadToDegree = 180.0 / M_PI; |
shimizuta | 32:dc684a0b8448 | 69 | int MoveOneCycle(Walk walkway, OneLeg leg[4]); |
shimizuta | 11:e81425872740 | 70 | void MoveServo(OneLeg leg, int legnum, int servo_id); |
shimizuta | 27:79b4b932a6dd | 71 | void WaitStdin(char startchar); |
shimizuta | 27:79b4b932a6dd | 72 | int FileOpen(); |
shimizuta | 27:79b4b932a6dd | 73 | int IsArrived(int count, int finish); |
shimizuta | 29:7d8b8011a88d | 74 | //段差があるときの機体角度を計算 |
shimizuta | 29:7d8b8011a88d | 75 | //param back_height_on_step:段差の高さ。後ろにあるとする。前にあるときはマイナスを入れる |
shimizuta | 29:7d8b8011a88d | 76 | float GetSteepBodyRad(float back_height_on_step); |
shimizuta | 27:79b4b932a6dd | 77 | |
shimizuta | 27:79b4b932a6dd | 78 | ////////調整するべきパラメータ |
shimizuta | 27:79b4b932a6dd | 79 | enum WalkWay |
shimizuta | 27:79b4b932a6dd | 80 | { |
shimizuta | 27:79b4b932a6dd | 81 | STANDUP, |
shimizuta | 27:79b4b932a6dd | 82 | STRAIGHT, |
shimizuta | 27:79b4b932a6dd | 83 | TURNLEFT, |
shimizuta | 27:79b4b932a6dd | 84 | TURNRIGHT, |
shimizuta | 29:7d8b8011a88d | 85 | UP, //足を伸ばして立つ |
shimizuta | 29:7d8b8011a88d | 86 | OVERCOME, //前足を乗せる |
shimizuta | 29:7d8b8011a88d | 87 | SANDDUNE, //前足だけがsandduneに乗った状態で進む |
shimizuta | 29:7d8b8011a88d | 88 | OVERCOME_BACK, //後ろ足を乗せる |
shimizuta | 29:7d8b8011a88d | 89 | STRAIGHT_W, //両足がsandduneに乗った状態で進む |
shimizuta | 29:7d8b8011a88d | 90 | ROPE_F, //ropeをまたぐ(前足) |
shimizuta | 29:7d8b8011a88d | 91 | ROPE_B, //ropeをまたぐ(後ろ足) |
shimizuta | 31:86eb746eaed4 | 92 | END, |
shimizuta | 31:86eb746eaed4 | 93 | STRAIGHT_W2, //後足がsandduneに乗った状態で進む |
shimizuta | 27:79b4b932a6dd | 94 | }; |
shimizuta | 27:79b4b932a6dd | 95 | void ParamsSetup(Walk walks[END], OneLeg leg[4]) //各パラメータの設定。減らしていく必要あり |
shimizuta | 19:1adc7302cfd9 | 96 | { |
shimizuta | 27:79b4b932a6dd | 97 | Walk::calctime_s_ = 0.03; //計算周期 |
shimizuta | 27:79b4b932a6dd | 98 | //足の作成、サイズデータのみの足の骨組.4足同じにしている |
shimizuta | 27:79b4b932a6dd | 99 | for (int i = 0; i < 4; i++) |
shimizuta | 27:79b4b932a6dd | 100 | leg[i] = OneLeg(kBetweenServoHalf_m, kLegLength1, kLegLength2); |
shimizuta | 29:7d8b8011a88d | 101 | walks[STANDUP].SetAllLegStandParam(0, 0.2, 0.5); //x,y,time_s.一括で設定できる |
shimizuta | 27:79b4b932a6dd | 102 | |
shimizuta | 32:dc684a0b8448 | 103 | //STRAIGT 論文通りのとき、offset_y_mは <=0.32 |
shimizuta | 32:dc684a0b8448 | 104 | float offset_x_m = -0.05, offset_y_m = 0.20, stride_m = 0.12, height_m = 0.05, buffer_height_m = 0.01, |
shimizuta | 31:86eb746eaed4 | 105 | stridetime_s = 0.3, toptime_s = 0.07, buffer_time_s = 0.03; |
shimizuta | 31:86eb746eaed4 | 106 | walks[STRAIGHT].SetAllLegTriangleParam // 4足を取り敢えず一括で設定してから |
shimizuta | 32:dc684a0b8448 | 107 | (offset_x_m, offset_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s); |
shimizuta | 32:dc684a0b8448 | 108 | walks[STRAIGHT].ChangeOneParam(LEFT_F, OFFSET_X_M, 0); |
shimizuta | 32:dc684a0b8448 | 109 | walks[STRAIGHT].ChangeOneParam(RIGHT_F, OFFSET_X_M, 0); |
shimizuta | 32:dc684a0b8448 | 110 | walks[STRAIGHT].ChangeOneParam(LEFT_F, OFFSET_Y_M, 0.2); |
shimizuta | 32:dc684a0b8448 | 111 | walks[STRAIGHT].ChangeOneParam(RIGHT_F, OFFSET_Y_M, 0.2); |
shimizuta | 29:7d8b8011a88d | 112 | walks[STRAIGHT].SetOffsetTime(0, 0.5, 0.5, 0); |
shimizuta | 32:dc684a0b8448 | 113 | |
shimizuta | 31:86eb746eaed4 | 114 | //TURNLEFTのparam |
shimizuta | 32:dc684a0b8448 | 115 | float stride_short_m = 0.05, stride_long_m = 0.25; |
shimizuta | 32:dc684a0b8448 | 116 | stridetime_s = 0.3, toptime_s = 0.07, buffer_time_s = 0.03, |
shimizuta | 32:dc684a0b8448 | 117 | offset_x_m=0, offset_y_m = 0.2, height_m = 0.03, buffer_height_m = 0.01; |
shimizuta | 31:86eb746eaed4 | 118 | walks[TURNLEFT].SetAllLegTriangleParam // 4足を取り敢えず一括で設定してから |
shimizuta | 32:dc684a0b8448 | 119 | (offset_x_m, offset_y_m, stride_long_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s); |
shimizuta | 32:dc684a0b8448 | 120 | walks[TURNLEFT].ChangeOneParam(LEFT_F, STRIDE_M, stride_short_m); //一部のパラメータを変更 |
shimizuta | 32:dc684a0b8448 | 121 | walks[TURNLEFT].ChangeOneParam(LEFT_B, STRIDE_M, stride_short_m); |
shimizuta | 31:86eb746eaed4 | 122 | walks[TURNLEFT].SetOffsetTime(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1]) |
shimizuta | 31:86eb746eaed4 | 123 | |
shimizuta | 31:86eb746eaed4 | 124 | //TURNRIGHT1のparam |
shimizuta | 31:86eb746eaed4 | 125 | walks[TURNRIGHT].SetAllLegTriangleParam // 4足を取り敢えず一括で設定してから |
shimizuta | 32:dc684a0b8448 | 126 | (offset_x_m, offset_y_m, stride_long_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s); |
shimizuta | 32:dc684a0b8448 | 127 | walks[TURNRIGHT].ChangeOneParam(RIGHT_F, STRIDE_M, stride_short_m); //一部のパラメータを変更 |
shimizuta | 32:dc684a0b8448 | 128 | walks[TURNRIGHT].ChangeOneParam(RIGHT_B, STRIDE_M, stride_short_m); |
shimizuta | 31:86eb746eaed4 | 129 | walks[TURNRIGHT].SetOffsetTime(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1]) |
shimizuta | 31:86eb746eaed4 | 130 | |
shimizuta | 31:86eb746eaed4 | 131 | // UP, //足を伸ばして立つ |
shimizuta | 32:dc684a0b8448 | 132 | LineParam up[] = { |
shimizuta | 32:dc684a0b8448 | 133 | {.time_s = 1, .x_m = 0, .y_m = 0.3}, |
shimizuta | 32:dc684a0b8448 | 134 | {.time_s = 0, .x_m = 0, .y_m = 0.3}}; |
shimizuta | 31:86eb746eaed4 | 135 | walks[UP].SetAllLegStandParam(0, 0.3, 1.2); //x,y,time_s.一括で設定できる |
shimizuta | 31:86eb746eaed4 | 136 | |
shimizuta | 31:86eb746eaed4 | 137 | // OVERCOME 前足を乗せる |
shimizuta | 32:dc684a0b8448 | 138 | |
shimizuta | 32:dc684a0b8448 | 139 | LineParam over_come_front_r[] = { |
shimizuta | 32:dc684a0b8448 | 140 | {.time_s = 0.6, .x_m = -0, .y_m = 0.32}, |
shimizuta | 32:dc684a0b8448 | 141 | {.time_s = 0.2, .x_m = -0, .y_m = 0.32}, |
shimizuta | 32:dc684a0b8448 | 142 | {.time_s = 0.2, .x_m = -0.13, .y_m = 0.15}, |
shimizuta | 32:dc684a0b8448 | 143 | {.time_s = 0.2, .x_m = 0.12, .y_m = 0.15}, |
shimizuta | 32:dc684a0b8448 | 144 | {.time_s = 0.6, .x_m = 0.12, .y_m = 0.15}, |
shimizuta | 32:dc684a0b8448 | 145 | {.time_s = 0, .x_m = 0.12, .y_m = 0.2}}; |
shimizuta | 32:dc684a0b8448 | 146 | LineParam over_come_front_l[] = { |
shimizuta | 32:dc684a0b8448 | 147 | {.time_s = 0.6, .x_m = -0, .y_m = 0.32}, |
shimizuta | 32:dc684a0b8448 | 148 | {.time_s = 0.6, .x_m = -0, .y_m = 0.32}, |
shimizuta | 32:dc684a0b8448 | 149 | {.time_s = 0.2, .x_m = -0, .y_m = 0.32}, |
shimizuta | 32:dc684a0b8448 | 150 | {.time_s = 0.2, .x_m = -0.13, .y_m = 0.15}, |
shimizuta | 32:dc684a0b8448 | 151 | {.time_s = 0.2, .x_m = 0.2, .y_m = 0.15}, |
shimizuta | 32:dc684a0b8448 | 152 | {.time_s = 0, .x_m = 0.2, .y_m = 0.2}}; |
shimizuta | 32:dc684a0b8448 | 153 | LineParam over_come_back[] = { |
shimizuta | 32:dc684a0b8448 | 154 | {.time_s = 0.6, .x_m = 0, .y_m = 0.3}, |
shimizuta | 32:dc684a0b8448 | 155 | {.time_s = 0.2, .x_m = 0, .y_m = 0.3}, |
shimizuta | 32:dc684a0b8448 | 156 | {.time_s = 1, .x_m = -0.1,.y_m = 0.3}, |
shimizuta | 32:dc684a0b8448 | 157 | {.time_s = 0, .x_m = -0.1,.y_m = 0.3}, |
shimizuta | 32:dc684a0b8448 | 158 | }; |
shimizuta | 32:dc684a0b8448 | 159 | walks[OVERCOME].SetOneLegFreeLinesParam(RIGHT_F, over_come_front_r, sizeof(over_come_front_r)/ sizeof(over_come_front_r[0])); |
shimizuta | 32:dc684a0b8448 | 160 | walks[OVERCOME].SetOneLegFreeLinesParam(LEFT_F, over_come_front_l, sizeof(over_come_front_l)/sizeof(over_come_front_l[0])); |
shimizuta | 32:dc684a0b8448 | 161 | walks[OVERCOME].SetOneLegFreeLinesParam(LEFT_B, over_come_back, sizeof(over_come_back)/sizeof(over_come_back[0])); |
shimizuta | 32:dc684a0b8448 | 162 | walks[OVERCOME].SetOneLegFreeLinesParam(RIGHT_B, over_come_back, sizeof(over_come_back)/sizeof(over_come_back[0])); |
shimizuta | 31:86eb746eaed4 | 163 | |
shimizuta | 31:86eb746eaed4 | 164 | // SANDDUNE, //前足だけがsandduneに乗った状態で進む |
shimizuta | 32:dc684a0b8448 | 165 | offset_x_m = -0.03, offset_y_m = 0.3, stride_m = 0.1, height_m = 0.03, buffer_height_m = 0.01, |
shimizuta | 31:86eb746eaed4 | 166 | stridetime_s = 0.2, toptime_s = 0.07, buffer_time_s = 0.03; |
shimizuta | 31:86eb746eaed4 | 167 | walks[SANDDUNE].SetAllLegTriangleParam // 4足一括で設定 |
shimizuta | 32:dc684a0b8448 | 168 | (offset_x_m, offset_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s); |
shimizuta | 32:dc684a0b8448 | 169 | walks[SANDDUNE].ChangeOneParam(LEFT_F, OFFSET_X_M, 0); |
shimizuta | 32:dc684a0b8448 | 170 | walks[SANDDUNE].ChangeOneParam(RIGHT_F, OFFSET_X_M, 0); |
shimizuta | 32:dc684a0b8448 | 171 | walks[SANDDUNE].ChangeOneParam(LEFT_F, OFFSET_Y_M, offset_y_m - 0.1); |
shimizuta | 32:dc684a0b8448 | 172 | walks[SANDDUNE].ChangeOneParam(RIGHT_F, OFFSET_Y_M, offset_y_m - 0.1); |
shimizuta | 31:86eb746eaed4 | 173 | walks[SANDDUNE].SetOffsetTime(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1]) |
shimizuta | 31:86eb746eaed4 | 174 | |
shimizuta | 31:86eb746eaed4 | 175 | // OVERCOME_BACK, //後ろ足を乗せる |
shimizuta | 31:86eb746eaed4 | 176 | float offset_x_back = -0.05; |
shimizuta | 32:dc684a0b8448 | 177 | LineParam overcomebackParams[] = { |
shimizuta | 32:dc684a0b8448 | 178 | {.time_s = 0.8, .x_m = -0.05f + offset_x_back, .y_m = 0.3}, |
shimizuta | 32:dc684a0b8448 | 179 | {.time_s = 0.2, .x_m = -0.05f + offset_x_back, .y_m = 0.3}, |
shimizuta | 32:dc684a0b8448 | 180 | {.time_s = 0.2, .x_m = -0.1f + offset_x_back, .y_m = 0.16}, |
shimizuta | 32:dc684a0b8448 | 181 | {.time_s = 0.2, .x_m = 0.1f + offset_x_back, .y_m = 0.16}, |
shimizuta | 32:dc684a0b8448 | 182 | {.time_s = 0.2, .x_m = 0.1f + offset_x_back, .y_m = 0.2}, |
shimizuta | 32:dc684a0b8448 | 183 | {.time_s = 0.8, .x_m = 0.05f + offset_x_back, .y_m = 0.2}, |
shimizuta | 32:dc684a0b8448 | 184 | {.time_s = 0, .x_m = 0.05f + offset_x_back, .y_m = 0.2}, |
shimizuta | 31:86eb746eaed4 | 185 | }; |
shimizuta | 32:dc684a0b8448 | 186 | LineParam standbackParams[] = { |
shimizuta | 32:dc684a0b8448 | 187 | {.time_s = 0.6, .x_m = 0.0f + offset_x_back, .y_m = 0.2}, |
shimizuta | 32:dc684a0b8448 | 188 | {.time_s = 0.2, .x_m = 0.0f + offset_x_back, .y_m = 0.2}, |
shimizuta | 32:dc684a0b8448 | 189 | {.time_s = 0.6, .x_m = -0.05f + offset_x_back, .y_m = 0.2}, |
shimizuta | 32:dc684a0b8448 | 190 | {.time_s = 0, .x_m = -0.05f + offset_x_back, .y_m = 0.2}, |
shimizuta | 31:86eb746eaed4 | 191 | }; |
shimizuta | 31:86eb746eaed4 | 192 | walks[OVERCOME_BACK].SetOneLegFreeLinesParam(LEFT_F, standbackParams, sizeof(standbackParams) / sizeof(standbackParams[0])); |
shimizuta | 31:86eb746eaed4 | 193 | walks[OVERCOME_BACK].SetOneLegFreeLinesParam(RIGHT_F, standbackParams, sizeof(standbackParams) / sizeof(standbackParams[0])); |
shimizuta | 31:86eb746eaed4 | 194 | walks[OVERCOME_BACK].SetOneLegFreeLinesParam(LEFT_B, overcomebackParams, sizeof(overcomebackParams) / sizeof(overcomebackParams[0])); |
shimizuta | 31:86eb746eaed4 | 195 | walks[OVERCOME_BACK].SetOneLegFreeLinesParam(RIGHT_B, overcomebackParams, sizeof(overcomebackParams) / sizeof(overcomebackParams[0])); |
shimizuta | 31:86eb746eaed4 | 196 | walks[OVERCOME_BACK].SetOffsetTime(0, 0, 0.5, 0); |
shimizuta | 31:86eb746eaed4 | 197 | |
shimizuta | 31:86eb746eaed4 | 198 | // STRAIGHT_W, //両足がsandduneに乗った状態で進む |
shimizuta | 32:dc684a0b8448 | 199 | offset_x_m = -0.09, offset_y_m = 0.2, stride_m = 0.1, height_m = 0.03, buffer_height_m = 0.01, |
shimizuta | 31:86eb746eaed4 | 200 | stridetime_s = 0.2, toptime_s = 0.07, buffer_time_s = 0.03; |
shimizuta | 31:86eb746eaed4 | 201 | walks[STRAIGHT_W].SetAllLegTriangleParam // 4足一括で設定 |
shimizuta | 32:dc684a0b8448 | 202 | (offset_x_m, offset_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s); |
shimizuta | 32:dc684a0b8448 | 203 | walks[STRAIGHT_W].ChangeOneParam(LEFT_F, OFFSET_X_M, 0); |
shimizuta | 32:dc684a0b8448 | 204 | walks[STRAIGHT_W].ChangeOneParam(RIGHT_F, OFFSET_X_M, 0); |
shimizuta | 31:86eb746eaed4 | 205 | walks[STRAIGHT_W].SetOffsetTime(0, 0.5, 0.5, 0); |
shimizuta | 31:86eb746eaed4 | 206 | |
shimizuta | 32:dc684a0b8448 | 207 | // ROPE_F, //ropeをまたぐ(前足) |
shimizuta | 32:dc684a0b8448 | 208 | offset_x_m = 0, offset_y_m = 0.3, stride_m = .15, height_m = 0.03, buffer_height_m = 0.01, |
shimizuta | 31:86eb746eaed4 | 209 | stridetime_s = 1, toptime_s = 0.35, buffer_time_s = 0.05; |
shimizuta | 31:86eb746eaed4 | 210 | walks[ROPE_F].SetAllLegTriangleParam // 4足一括で設定 |
shimizuta | 32:dc684a0b8448 | 211 | (offset_x_m, offset_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s); |
shimizuta | 31:86eb746eaed4 | 212 | walks[ROPE_F].ChangeOneParam(LEFT_F, HEIGHT_M, 0.15); //前足だけ足を延ばす |
shimizuta | 31:86eb746eaed4 | 213 | walks[ROPE_F].ChangeOneParam(RIGHT_F, HEIGHT_M, 0.15); |
shimizuta | 31:86eb746eaed4 | 214 | walks[ROPE_F].SetOffsetTime(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1]) |
shimizuta | 31:86eb746eaed4 | 215 | |
shimizuta | 31:86eb746eaed4 | 216 | // ROPE_B, //ropeをまたぐ(後ろ足) |
shimizuta | 32:dc684a0b8448 | 217 | offset_x_m = -0.05, offset_y_m = 0.3, stride_m = .1, height_m = 0.03, buffer_height_m = 0.01, |
shimizuta | 31:86eb746eaed4 | 218 | stridetime_s = 1, toptime_s = 0.35, buffer_time_s = 0.05; |
shimizuta | 31:86eb746eaed4 | 219 | walks[ROPE_B].SetAllLegTriangleParam // 4足一括で設定 |
shimizuta | 32:dc684a0b8448 | 220 | (offset_x_m, offset_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s); |
shimizuta | 31:86eb746eaed4 | 221 | walks[ROPE_B].ChangeOneParam(LEFT_B, HEIGHT_M, 0.15); //後ろ足だけ足を延ばす |
shimizuta | 31:86eb746eaed4 | 222 | walks[ROPE_B].ChangeOneParam(RIGHT_B, HEIGHT_M, 0.15); |
shimizuta | 32:dc684a0b8448 | 223 | walks[ROPE_B].ChangeOneParam(LEFT_B, OFFSET_X_M, -0.07); |
shimizuta | 32:dc684a0b8448 | 224 | walks[ROPE_B].ChangeOneParam(RIGHT_B, OFFSET_X_M, -0.07); |
shimizuta | 31:86eb746eaed4 | 225 | walks[ROPE_B].SetOffsetTime(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1]) |
yuto17320508 | 18:0033ef1814ba | 226 | } |
shimizuta | 27:79b4b932a6dd | 227 | Walk walks[END]; //歩行法 |
shimizuta | 9:905f93247688 | 228 | int main() |
yuto17320508 | 5:556d5a5e9d24 | 229 | { |
shimizuta | 29:7d8b8011a88d | 230 | #ifdef VSCODE |
shimizuta | 27:79b4b932a6dd | 231 | if (FileOpen()) //csv fileに書き込み |
shimizuta | 27:79b4b932a6dd | 232 | return 1; //異常終了したら強制終了 |
shimizuta | 29:7d8b8011a88d | 233 | #endif |
shimizuta | 27:79b4b932a6dd | 234 | DEBUG("param set start"); |
shimizuta | 27:79b4b932a6dd | 235 | ParamsSetup(walks, leg); //各動きの際の足の軌道を設定。パラメータはこの関数内に打ち込む |
shimizuta | 27:79b4b932a6dd | 236 | for (int i = 0; i < END; i++) //軌道のチェック |
shimizuta | 27:79b4b932a6dd | 237 | { |
shimizuta | 27:79b4b932a6dd | 238 | if (walks[i].CheckOrbit(leg[0]) == 1) //軌道が定義外なら |
shimizuta | 29:7d8b8011a88d | 239 | { |
shimizuta | 32:dc684a0b8448 | 240 | printf("error: move pattern %d\r\n", i); |
shimizuta | 29:7d8b8011a88d | 241 | return 1; //強制終了.errorは内部の関数からprintfで知らせる |
shimizuta | 29:7d8b8011a88d | 242 | } |
shimizuta | 27:79b4b932a6dd | 243 | } |
shimizuta | 29:7d8b8011a88d | 244 | printf("Stand up?\r\n"); |
shimizuta | 27:79b4b932a6dd | 245 | WaitStdin('y'); // ボタンを押したら立つ |
shimizuta | 27:79b4b932a6dd | 246 | MoveOneCycle(walks[STANDUP], leg); |
shimizuta | 29:7d8b8011a88d | 247 | printf("Move?\r\n"); |
shimizuta | 27:79b4b932a6dd | 248 | WaitStdin('y'); // ボタンを押したらスタート |
shimizuta | 27:79b4b932a6dd | 249 | #ifdef USE_ROS |
shimizuta | 27:79b4b932a6dd | 250 | nh_mbed.getHardware()->setBaud(115200); |
shimizuta | 27:79b4b932a6dd | 251 | nh_mbed.initNode(); |
shimizuta | 27:79b4b932a6dd | 252 | nh_mbed.subscribe(sub_vel); |
shimizuta | 27:79b4b932a6dd | 253 | while (1) |
shimizuta | 27:79b4b932a6dd | 254 | nh_mbed.spinOnce(); |
shimizuta | 27:79b4b932a6dd | 255 | #else |
shimizuta | 32:dc684a0b8448 | 256 | |
shimizuta | 32:dc684a0b8448 | 257 | for(int k=0;k<5;k++)MoveOneCycle(walks[STRAIGHT], leg); |
shimizuta | 32:dc684a0b8448 | 258 | for(int k=0;k<1;k++)MoveOneCycle(walks[UP], leg); |
shimizuta | 32:dc684a0b8448 | 259 | for(int k=0;k<1;k++)MoveOneCycle(walks[OVERCOME],leg); |
shimizuta | 32:dc684a0b8448 | 260 | for(int k=0;k<5;k++) MoveOneCycle(walks[SANDDUNE],leg); |
shimizuta | 32:dc684a0b8448 | 261 | for(int k=0;k<1;k++)MoveOneCycle(walks[OVERCOME_BACK],leg); |
shimizuta | 32:dc684a0b8448 | 262 | for(int k=0;k<3;k++)MoveOneCycle(walks[STRAIGHT_W], leg); |
shimizuta | 32:dc684a0b8448 | 263 | // for(int k=0;k<5;k++)Move(*straight_w2, leg,(*straight_w2).GetTheta(0.1)); |
shimizuta | 32:dc684a0b8448 | 264 | // for(int k=0;k<3;k++)Move(*straight, leg); |
shimizuta | 32:dc684a0b8448 | 265 | /* |
shimizuta | 27:79b4b932a6dd | 266 | for (int i = 1; i < END; i++) //ENDになるまでWalkWayの順に動作 |
shimizuta | 27:79b4b932a6dd | 267 | { |
shimizuta | 32:dc684a0b8448 | 268 | printf("Move %d\r\n", i); |
shimizuta | 32:dc684a0b8448 | 269 | for (int j = 0; j < 20; j++) //debug用に2歩進む |
shimizuta | 32:dc684a0b8448 | 270 | { |
shimizuta | 32:dc684a0b8448 | 271 | if(MoveOneCycle(walks[i], leg) == 1) |
shimizuta | 32:dc684a0b8448 | 272 | printf("error:In MoveOneCycle. WalkWay %d\r\n",i); |
shimizuta | 32:dc684a0b8448 | 273 | } |
shimizuta | 27:79b4b932a6dd | 274 | } |
shimizuta | 32:dc684a0b8448 | 275 | |
shimizuta | 27:79b4b932a6dd | 276 | MoveOneCycle(walks[STANDUP], leg); //最後はLRFを保護するためSTANDUPの状態で終わる |
shimizuta | 32:dc684a0b8448 | 277 | |
shimizuta | 32:dc684a0b8448 | 278 | */ printf("program end\r\n"); |
shimizuta | 29:7d8b8011a88d | 279 | #ifdef VSCODE |
shimizuta | 27:79b4b932a6dd | 280 | fclose(fp); |
shimizuta | 27:79b4b932a6dd | 281 | #endif |
shimizuta | 29:7d8b8011a88d | 282 | #endif |
shimizuta | 2:a92568bdeb5c | 283 | } |
shimizuta | 32:dc684a0b8448 | 284 | //一サイクル分進む.return 1:異常終了 |
shimizuta | 32:dc684a0b8448 | 285 | int MoveOneCycle(Walk walkway, OneLeg leg[4]) |
yuto17320508 | 5:556d5a5e9d24 | 286 | { |
shimizuta | 27:79b4b932a6dd | 287 | #ifndef VSCODE |
shimizuta | 9:905f93247688 | 288 | timer.reset(); |
shimizuta | 9:905f93247688 | 289 | timer.start(); |
shimizuta | 27:79b4b932a6dd | 290 | #endif |
shimizuta | 27:79b4b932a6dd | 291 | int count = walkway.GetOneWalkTime() / walkway.calctime_s_; |
shimizuta | 27:79b4b932a6dd | 292 | for (int i = 0; i < count; i++) |
yuto17320508 | 8:21b932c4e6c5 | 293 | { |
shimizuta | 27:79b4b932a6dd | 294 | #ifndef VSCODE |
shimizuta | 9:905f93247688 | 295 | float time_s = timer.read(); |
shimizuta | 27:79b4b932a6dd | 296 | #endif |
shimizuta | 29:7d8b8011a88d | 297 | //4本の足それぞれの足先サーボ角度更新 |
shimizuta | 29:7d8b8011a88d | 298 | if (walkway.Cal4LegsPosi(leg) == 1) |
shimizuta | 32:dc684a0b8448 | 299 | { |
shimizuta | 29:7d8b8011a88d | 300 | printf("error: time = %f\r\n", i * walkway.calctime_s_); |
shimizuta | 32:dc684a0b8448 | 301 | return 1; |
shimizuta | 32:dc684a0b8448 | 302 | } |
shimizuta | 19:1adc7302cfd9 | 303 | #ifdef USE_CAN |
shimizuta | 27:79b4b932a6dd | 304 | SendRad(leg[2], leg[3]); //slave_mbed分の足の目標位置を送信 |
shimizuta | 19:1adc7302cfd9 | 305 | #endif |
shimizuta | 9:905f93247688 | 306 | //自身が動かす足のサーボを動かす |
shimizuta | 16:0069a56f11a3 | 307 | MoveServo(leg[0], 0, 0); |
shimizuta | 11:e81425872740 | 308 | MoveServo(leg[1], 1, 0); |
shimizuta | 27:79b4b932a6dd | 309 | #ifndef VSCODE |
shimizuta | 9:905f93247688 | 310 | wait_ms(kServoSpan_ms); |
shimizuta | 27:79b4b932a6dd | 311 | #endif |
shimizuta | 16:0069a56f11a3 | 312 | MoveServo(leg[0], 0, 1); |
shimizuta | 11:e81425872740 | 313 | MoveServo(leg[1], 1, 1); |
shimizuta | 29:7d8b8011a88d | 314 | #ifdef VSCODE |
shimizuta | 27:79b4b932a6dd | 315 | //ファイルに書き込み。time[s],x[0],y[0],x[1],y[1],x[2],y[2],x[3],y[3]の順 |
shimizuta | 27:79b4b932a6dd | 316 | fprintf(fp, "%f", i * walkway.calctime_s_); |
shimizuta | 27:79b4b932a6dd | 317 | for (int i = 0; i < 4; i++) |
shimizuta | 27:79b4b932a6dd | 318 | fprintf(fp, ",%f,%f", leg[i].GetX_m(), leg[i].GetY_m()); |
shimizuta | 27:79b4b932a6dd | 319 | fprintf(fp, "\r\n"); |
shimizuta | 29:7d8b8011a88d | 320 | #else |
shimizuta | 27:79b4b932a6dd | 321 | //計算周期がwalkway.calctime_s_になるようwait |
shimizuta | 27:79b4b932a6dd | 322 | float rest_time_s = walkway.calctime_s_ - (timer.read() - time_s); |
shimizuta | 9:905f93247688 | 323 | if (rest_time_s > 0) |
shimizuta | 9:905f93247688 | 324 | wait(rest_time_s); |
shimizuta | 19:1adc7302cfd9 | 325 | else |
shimizuta | 19:1adc7302cfd9 | 326 | { //計算周期が達成できないときはDEBUGで知らせるだけ。動きはする。 |
shimizuta | 19:1adc7302cfd9 | 327 | DEBUG("error: rest_time_s = %f in Move()\r\n", rest_time_s); |
shimizuta | 14:d7cb429946f4 | 328 | led[0] = 1; |
shimizuta | 14:d7cb429946f4 | 329 | } |
shimizuta | 27:79b4b932a6dd | 330 | #endif |
shimizuta | 9:905f93247688 | 331 | } |
shimizuta | 32:dc684a0b8448 | 332 | return 0; |
yuto17320508 | 5:556d5a5e9d24 | 333 | } |
shimizuta | 14:d7cb429946f4 | 334 | void MoveServo(OneLeg leg, int serial_num, int servo_id) |
yuto17320508 | 6:43708adf2e5d | 335 | { |
shimizuta | 27:79b4b932a6dd | 336 | #ifndef VSCODE |
shimizuta | 11:e81425872740 | 337 | float degree = leg.GetRad(servo_id) * kRadToDegree; |
shimizuta | 14:d7cb429946f4 | 338 | //サーボの座標系に変更 |
shimizuta | 14:d7cb429946f4 | 339 | float servo_degree = kServoSign[serial_num][servo_id] * degree + kOriginDegree[serial_num][servo_id]; |
shimizuta | 27:79b4b932a6dd | 340 | // DEBUG("servo_degree[%d][%d],%f\r\n", serial_num, servo_id, servo_degree); |
shimizuta | 14:d7cb429946f4 | 341 | servo[serial_num].set_degree(servo_id, servo_degree); |
shimizuta | 27:79b4b932a6dd | 342 | #endif |
shimizuta | 12:2ac37fe6c3bb | 343 | } |
shimizuta | 27:79b4b932a6dd | 344 | void WaitStdin(char startchar) |
shimizuta | 27:79b4b932a6dd | 345 | { |
shimizuta | 27:79b4b932a6dd | 346 | #ifndef USE_ROS |
shimizuta | 27:79b4b932a6dd | 347 | char str[255] = {}; |
shimizuta | 27:79b4b932a6dd | 348 | do |
shimizuta | 27:79b4b932a6dd | 349 | { |
shimizuta | 27:79b4b932a6dd | 350 | printf("put '%c', then start\r\n", startchar); |
shimizuta | 27:79b4b932a6dd | 351 | scanf("%s", str); |
shimizuta | 27:79b4b932a6dd | 352 | } while (str[0] != startchar); |
shimizuta | 27:79b4b932a6dd | 353 | #endif |
shimizuta | 27:79b4b932a6dd | 354 | } |
shimizuta | 27:79b4b932a6dd | 355 | int FileOpen() //1:異常終了 |
shimizuta | 27:79b4b932a6dd | 356 | { |
shimizuta | 27:79b4b932a6dd | 357 | if ((fp = fopen("data.csv", "w")) == NULL) |
shimizuta | 27:79b4b932a6dd | 358 | { |
shimizuta | 27:79b4b932a6dd | 359 | printf("error : FileSave()\r\n"); |
shimizuta | 27:79b4b932a6dd | 360 | return 1; |
shimizuta | 27:79b4b932a6dd | 361 | } |
shimizuta | 27:79b4b932a6dd | 362 | fprintf(fp, "time[s],x[0],y[0],x[1],y[1],x[2],y[2],x[3],y[3]\r\n"); |
shimizuta | 27:79b4b932a6dd | 363 | return 0; |
shimizuta | 27:79b4b932a6dd | 364 | } |
shimizuta | 27:79b4b932a6dd | 365 | #ifdef USE_ROS |
shimizuta | 27:79b4b932a6dd | 366 | void callback(const geometry_msgs::Vector3 &cmd_vel) |
shimizuta | 27:79b4b932a6dd | 367 | { |
shimizuta | 27:79b4b932a6dd | 368 | float left_vel = cmd_vel.x; |
shimizuta | 27:79b4b932a6dd | 369 | float right_vel = cmd_vel.y; |
shimizuta | 27:79b4b932a6dd | 370 | //閾値は要検討 |
shimizuta | 27:79b4b932a6dd | 371 | if (right_vel < left_vel) |
shimizuta | 27:79b4b932a6dd | 372 | MoveOneCycle(walks[TURNRIGHT], leg); |
shimizuta | 27:79b4b932a6dd | 373 | else if (left_vel < right_vel) |
shimizuta | 27:79b4b932a6dd | 374 | MoveOneCycle(walks[TURNLEFT], leg); |
shimizuta | 27:79b4b932a6dd | 375 | else |
shimizuta | 27:79b4b932a6dd | 376 | MoveOneCycle(walks[STRAIGHT], leg); |
shimizuta | 27:79b4b932a6dd | 377 | } |
shimizuta | 27:79b4b932a6dd | 378 | #endif |
shimizuta | 29:7d8b8011a88d | 379 | //param back_height_on_step:段差の高さ。後ろにあるとする。前にあるときはマイナスを入れる |
shimizuta | 29:7d8b8011a88d | 380 | float GetSteepBodyRad(float back_height_on_step) |
shimizuta | 29:7d8b8011a88d | 381 | { |
shimizuta | 29:7d8b8011a88d | 382 | float offset_hight = back_height_on_step + leg[LEFT_B].GetY_m() - leg[LEFT_B].GetY_m(); |
shimizuta | 29:7d8b8011a88d | 383 | float theta = atan2(offset_hight, (float)(sqrt(0.09 - offset_hight * offset_hight))); |
shimizuta | 29:7d8b8011a88d | 384 | return theta; |
shimizuta | 29:7d8b8011a88d | 385 | } |