test
Dependencies: mbed ros_lib_kinetic nhk19mr2_can_info splitData SerialHalfDuplex_HM
main.cpp@31:86eb746eaed4, 2019-02-28 (annotated)
- Committer:
- shimizuta
- Date:
- Thu Feb 28 03:52:09 2019 +0000
- Revision:
- 31:86eb746eaed4
- Parent:
- 29:7d8b8011a88d
- Child:
- 32:dc684a0b8448
move straight;
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 | 27:79b4b932a6dd | 69 | void 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 | 29:7d8b8011a88d | 103 | //STRAIGT 論文通りのとき、start_y_mは <=0.32 |
shimizuta | 31:86eb746eaed4 | 104 | float start_x_m = 0.075, start_y_m = 0.2, stride_m = 0.15, height_m = 0.03, 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 | 31:86eb746eaed4 | 107 | (start_x_m, start_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s); |
shimizuta | 29:7d8b8011a88d | 108 | walks[STRAIGHT].SetOffsetTime(0, 0.5, 0.5, 0); |
shimizuta | 31:86eb746eaed4 | 109 | /* |
shimizuta | 31:86eb746eaed4 | 110 | //TURNLEFTのparam |
shimizuta | 31:86eb746eaed4 | 111 | float stride_short_m = 0.2, stride_long_m = 0.1, start_x_short_m = 0.1, start_x_long_m = 0.051; |
shimizuta | 31:86eb746eaed4 | 112 | stridetime_s = 0.2, toptime_s = 0.07, buffer_time_s = 0.03, |
shimizuta | 31:86eb746eaed4 | 113 | start_y_m = 0.2, height_m = 0.03, buffer_height_m = 0.01; |
shimizuta | 31:86eb746eaed4 | 114 | walks[TURNLEFT].SetAllLegTriangleParam // 4足を取り敢えず一括で設定してから |
shimizuta | 31:86eb746eaed4 | 115 | (start_x_short_m, start_y_m, stride_short_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s); |
shimizuta | 31:86eb746eaed4 | 116 | walks[TURNLEFT].ChangeOneParam(LEFT_F, STRIDE_M, stride_long_m); //一部のパラメータを変更 |
shimizuta | 31:86eb746eaed4 | 117 | walks[TURNLEFT].ChangeOneParam(LEFT_B, STRIDE_M, stride_long_m); |
shimizuta | 31:86eb746eaed4 | 118 | walks[TURNLEFT].ChangeOneParam(LEFT_F, STRAT_X_M, start_x_long_m); //一部のパラメータを変更 |
shimizuta | 31:86eb746eaed4 | 119 | walks[TURNLEFT].ChangeOneParam(LEFT_B, STRAT_X_M, start_x_long_m); |
shimizuta | 31:86eb746eaed4 | 120 | walks[TURNLEFT].SetOffsetTime(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1]) |
shimizuta | 31:86eb746eaed4 | 121 | |
shimizuta | 31:86eb746eaed4 | 122 | //TURNRIGHT1のparam |
shimizuta | 31:86eb746eaed4 | 123 | walks[TURNRIGHT].SetAllLegTriangleParam // 4足を取り敢えず一括で設定してから |
shimizuta | 31:86eb746eaed4 | 124 | (start_x_short_m, start_y_m, stride_short_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s); |
shimizuta | 31:86eb746eaed4 | 125 | walks[TURNRIGHT].ChangeOneParam(RIGHT_F, STRIDE_M, stride_long_m); //一部のパラメータを変更 |
shimizuta | 31:86eb746eaed4 | 126 | walks[TURNRIGHT].ChangeOneParam(RIGHT_B, STRIDE_M, stride_long_m); |
shimizuta | 31:86eb746eaed4 | 127 | walks[TURNLEFT].ChangeOneParam(RIGHT_F, STRAT_X_M, start_x_long_m); //一部のパラメータを変更 |
shimizuta | 31:86eb746eaed4 | 128 | walks[TURNLEFT].ChangeOneParam(RIGHT_B, STRAT_X_M, start_x_long_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 | 31:86eb746eaed4 | 132 | walks[UP].SetAllLegStandParam(0, 0.3, 1.2); //x,y,time_s.一括で設定できる |
shimizuta | 31:86eb746eaed4 | 133 | |
shimizuta | 31:86eb746eaed4 | 134 | // OVERCOME 前足を乗せる |
shimizuta | 31:86eb746eaed4 | 135 | LineParam over_come_front[] = { |
shimizuta | 31:86eb746eaed4 | 136 | {.time_s = 0.6, .x_m = -0.1, .y_m = 0.3}, |
shimizuta | 31:86eb746eaed4 | 137 | {.time_s = 0.2, .x_m = -0.1, .y_m = 0.3}, |
shimizuta | 31:86eb746eaed4 | 138 | {.time_s = 0.2, .x_m = -0.13, .y_m = 0.16}, |
shimizuta | 31:86eb746eaed4 | 139 | {.time_s = 0.2, .x_m = 0.08, .y_m = 0.16}, |
shimizuta | 31:86eb746eaed4 | 140 | {.time_s = 0.6, .x_m = 0.08, .y_m = 0.2}, |
shimizuta | 31:86eb746eaed4 | 141 | {.time_s = 0, .x_m = 0.08, .y_m = 0.2}}; |
shimizuta | 31:86eb746eaed4 | 142 | walks[OVERCOME].SetAllLegFreeLinesParam(over_come_front, sizeof(over_come_front)/sizeof(over_come_front[0])); //前足設定 |
shimizuta | 31:86eb746eaed4 | 143 | walks[OVERCOME].SetOneLegStandParam(LEFT_B, 0, 0.3, frontleg.GetOneWalkTime()); |
shimizuta | 31:86eb746eaed4 | 144 | walks[OVERCOME].SetOneLegStandParam(RIGHT_B, 0, 0.3, frontleg.GetOneWalkTime()); |
shimizuta | 31:86eb746eaed4 | 145 | walks[OVERCOME].SetOffsetTime(0, 0.5, 0, 0); |
shimizuta | 31:86eb746eaed4 | 146 | |
shimizuta | 31:86eb746eaed4 | 147 | // SANDDUNE, //前足だけがsandduneに乗った状態で進む |
shimizuta | 31:86eb746eaed4 | 148 | start_x_m = 0.02, start_y_m = 0.3, stride_m = 0.1, height_m = 0.03, buffer_height_m = 0.01, |
shimizuta | 31:86eb746eaed4 | 149 | stridetime_s = 0.2, toptime_s = 0.07, buffer_time_s = 0.03; |
shimizuta | 31:86eb746eaed4 | 150 | walks[SANDDUNE].SetAllLegTriangleParam // 4足一括で設定 |
shimizuta | 31:86eb746eaed4 | 151 | (start_x_m, start_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s); |
shimizuta | 31:86eb746eaed4 | 152 | walks[SANDDUNE].SetOffsetTime(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1]) |
shimizuta | 31:86eb746eaed4 | 153 | |
shimizuta | 31:86eb746eaed4 | 154 | // OVERCOME_BACK, //後ろ足を乗せる |
shimizuta | 31:86eb746eaed4 | 155 | float offset_x_back = -0.05; |
shimizuta | 31:86eb746eaed4 | 156 | Lineparam overcomebackParams[6] = { |
shimizuta | 31:86eb746eaed4 | 157 | {.time_s = 0.8, .x_m = -0.05 + offset_x_back, .y_m = 0.3}, |
shimizuta | 31:86eb746eaed4 | 158 | {.time_s = 0.2, .x_m = -0.05 + offset_x_back, .y_m = 0.3}, |
shimizuta | 31:86eb746eaed4 | 159 | {.time_s = 0.2, .x_m = -0.1 + offset_x_back, .y_m = 0.16}, |
shimizuta | 31:86eb746eaed4 | 160 | {.time_s = 0.2, .x_m = 0.1 + offset_x_back, .y_m = 0.16}, |
shimizuta | 31:86eb746eaed4 | 161 | {.time_s = 0.2, .x_m = 0.1 + offset_x_back, .y_m = 0.2}, |
shimizuta | 31:86eb746eaed4 | 162 | {.time_s = 0.6, .x_m = 0.05 + offset_x_back, .y_m = 0.2}, |
shimizuta | 31:86eb746eaed4 | 163 | }; |
shimizuta | 31:86eb746eaed4 | 164 | Lineparam standbackParams[3] = { |
shimizuta | 31:86eb746eaed4 | 165 | {.time_s = 0.6, .x_m = 0.0 + offset_x_back, .y_m = 0.2}, |
shimizuta | 31:86eb746eaed4 | 166 | {.time_s = 0.2, .x_m = 0.0 + offset_x_back, .y_m = 0.2}, |
shimizuta | 31:86eb746eaed4 | 167 | {.time_s = 0.6, .x_m = -0.05 + offset_x_back, .y_m = 0.2}, |
shimizuta | 31:86eb746eaed4 | 168 | }; |
shimizuta | 31:86eb746eaed4 | 169 | walks[OVERCOME_BACK].SetOneLegFreeLinesParam(LEFT_F, standbackParams, sizeof(standbackParams) / sizeof(standbackParams[0])); |
shimizuta | 31:86eb746eaed4 | 170 | walks[OVERCOME_BACK].SetOneLegFreeLinesParam(RIGHT_F, standbackParams, sizeof(standbackParams) / sizeof(standbackParams[0])); |
shimizuta | 31:86eb746eaed4 | 171 | walks[OVERCOME_BACK].SetOneLegFreeLinesParam(LEFT_B, overcomebackParams, sizeof(overcomebackParams) / sizeof(overcomebackParams[0])); |
shimizuta | 31:86eb746eaed4 | 172 | walks[OVERCOME_BACK].SetOneLegFreeLinesParam(RIGHT_B, overcomebackParams, sizeof(overcomebackParams) / sizeof(overcomebackParams[0])); |
shimizuta | 31:86eb746eaed4 | 173 | walks[OVERCOME_BACK].SetOffsetTime(0, 0, 0.5, 0); |
shimizuta | 31:86eb746eaed4 | 174 | |
shimizuta | 31:86eb746eaed4 | 175 | // STRAIGHT_W, //両足がsandduneに乗った状態で進む |
shimizuta | 31:86eb746eaed4 | 176 | start_x_m = -0.04, start_y_m = 0.2, stride_m = 0.1, height_m = 0.03, buffer_height_m = 0.01, |
shimizuta | 31:86eb746eaed4 | 177 | stridetime_s = 0.2, toptime_s = 0.07, buffer_time_s = 0.03; |
shimizuta | 31:86eb746eaed4 | 178 | walks[STRAIGHT_W].SetAllLegTriangleParam // 4足一括で設定 |
shimizuta | 31:86eb746eaed4 | 179 | (start_x_m, start_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s); |
shimizuta | 31:86eb746eaed4 | 180 | walks[STRAIGHT_W].ChangeOneParam(LEFT_F, STRAT_X_M, 0.05); |
shimizuta | 31:86eb746eaed4 | 181 | walks[STRAIGHT_W].ChangeOneParam(RIGHT_F, STRAT_X_M, 0.05); |
shimizuta | 31:86eb746eaed4 | 182 | walks[STRAIGHT_W].SetOffsetTime(0, 0.5, 0.5, 0); |
shimizuta | 31:86eb746eaed4 | 183 | |
shimizuta | 31:86eb746eaed4 | 184 | // ROPE_F, //ropeをまたぐ(前足) |
shimizuta | 31:86eb746eaed4 | 185 | float start_x_front_m = 0.05; //前足のstart_x |
shimizuta | 31:86eb746eaed4 | 186 | start_x_m = .72, start_y_m = 0.3, stride_m = .15, height_m = 0.03, buffer_height_m = 0.01, |
shimizuta | 31:86eb746eaed4 | 187 | stridetime_s = 1, toptime_s = 0.35, buffer_time_s = 0.05; |
shimizuta | 31:86eb746eaed4 | 188 | walks[ROPE_F].SetAllLegTriangleParam // 4足一括で設定 |
shimizuta | 31:86eb746eaed4 | 189 | (start_x_m, start_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s); |
shimizuta | 31:86eb746eaed4 | 190 | walks[ROPE_F].ChangeOneParam(LEFT_F, HEIGHT_M, 0.15); //前足だけ足を延ばす |
shimizuta | 31:86eb746eaed4 | 191 | walks[ROPE_F].ChangeOneParam(RIGHT_F, HEIGHT_M, 0.15); |
shimizuta | 31:86eb746eaed4 | 192 | walks[ROPE_F].SetOffsetTime(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1]) |
shimizuta | 31:86eb746eaed4 | 193 | |
shimizuta | 31:86eb746eaed4 | 194 | // ROPE_B, //ropeをまたぐ(後ろ足) |
shimizuta | 31:86eb746eaed4 | 195 | start_x_m = 0, start_y_m = 0.3, stride_m = .15, height_m = 0.03, buffer_height_m = 0.01, |
shimizuta | 31:86eb746eaed4 | 196 | stridetime_s = 1, toptime_s = 0.35, buffer_time_s = 0.05; |
shimizuta | 31:86eb746eaed4 | 197 | walks[ROPE_B].SetAllLegTriangleParam // 4足一括で設定 |
shimizuta | 31:86eb746eaed4 | 198 | (start_x_m, start_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s); |
shimizuta | 31:86eb746eaed4 | 199 | walks[ROPE_B].ChangeOneParam(LEFT_B, HEIGHT_M, 0.15); //後ろ足だけ足を延ばす |
shimizuta | 31:86eb746eaed4 | 200 | walks[ROPE_B].ChangeOneParam(RIGHT_B, HEIGHT_M, 0.15); |
shimizuta | 31:86eb746eaed4 | 201 | walks[ROPE_B].ChangeOneParam(LEFT_B, STRAT_X_M, -0.02); |
shimizuta | 31:86eb746eaed4 | 202 | walks[ROPE_B].ChangeOneParam(RIGHT_B, STRAT_X_M, -0.02); |
shimizuta | 31:86eb746eaed4 | 203 | walks[ROPE_B].SetOffsetTime(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1]) |
shimizuta | 31:86eb746eaed4 | 204 | */ |
yuto17320508 | 18:0033ef1814ba | 205 | } |
shimizuta | 27:79b4b932a6dd | 206 | Walk walks[END]; //歩行法 |
shimizuta | 9:905f93247688 | 207 | int main() |
yuto17320508 | 5:556d5a5e9d24 | 208 | { |
shimizuta | 29:7d8b8011a88d | 209 | #ifdef VSCODE |
shimizuta | 27:79b4b932a6dd | 210 | if (FileOpen()) //csv fileに書き込み |
shimizuta | 27:79b4b932a6dd | 211 | return 1; //異常終了したら強制終了 |
shimizuta | 29:7d8b8011a88d | 212 | #endif |
shimizuta | 27:79b4b932a6dd | 213 | DEBUG("param set start"); |
shimizuta | 27:79b4b932a6dd | 214 | ParamsSetup(walks, leg); //各動きの際の足の軌道を設定。パラメータはこの関数内に打ち込む |
shimizuta | 27:79b4b932a6dd | 215 | for (int i = 0; i < END; i++) //軌道のチェック |
shimizuta | 27:79b4b932a6dd | 216 | { |
shimizuta | 27:79b4b932a6dd | 217 | if (walks[i].CheckOrbit(leg[0]) == 1) //軌道が定義外なら |
shimizuta | 29:7d8b8011a88d | 218 | { |
shimizuta | 29:7d8b8011a88d | 219 | printf("error: move pattern %d", i); |
shimizuta | 29:7d8b8011a88d | 220 | return 1; //強制終了.errorは内部の関数からprintfで知らせる |
shimizuta | 29:7d8b8011a88d | 221 | } |
shimizuta | 27:79b4b932a6dd | 222 | } |
shimizuta | 29:7d8b8011a88d | 223 | printf("Stand up?\r\n"); |
shimizuta | 27:79b4b932a6dd | 224 | WaitStdin('y'); // ボタンを押したら立つ |
shimizuta | 27:79b4b932a6dd | 225 | MoveOneCycle(walks[STANDUP], leg); |
shimizuta | 29:7d8b8011a88d | 226 | printf("Move?\r\n"); |
shimizuta | 27:79b4b932a6dd | 227 | WaitStdin('y'); // ボタンを押したらスタート |
shimizuta | 27:79b4b932a6dd | 228 | #ifdef USE_ROS |
shimizuta | 27:79b4b932a6dd | 229 | nh_mbed.getHardware()->setBaud(115200); |
shimizuta | 27:79b4b932a6dd | 230 | nh_mbed.initNode(); |
shimizuta | 27:79b4b932a6dd | 231 | nh_mbed.subscribe(sub_vel); |
shimizuta | 27:79b4b932a6dd | 232 | while (1) |
shimizuta | 27:79b4b932a6dd | 233 | nh_mbed.spinOnce(); |
shimizuta | 27:79b4b932a6dd | 234 | #else |
shimizuta | 27:79b4b932a6dd | 235 | for (int i = 1; i < END; i++) //ENDになるまでWalkWayの順に動作 |
shimizuta | 27:79b4b932a6dd | 236 | { |
shimizuta | 27:79b4b932a6dd | 237 | DEBUG("Move %d\r\n", i); |
shimizuta | 31:86eb746eaed4 | 238 | for (int j = 0; j < 50; j++) //debug用に2歩進む |
shimizuta | 27:79b4b932a6dd | 239 | MoveOneCycle(walks[i], leg); |
shimizuta | 27:79b4b932a6dd | 240 | } |
shimizuta | 27:79b4b932a6dd | 241 | MoveOneCycle(walks[STANDUP], leg); //最後はLRFを保護するためSTANDUPの状態で終わる |
shimizuta | 27:79b4b932a6dd | 242 | printf("program end\r\n"); |
shimizuta | 29:7d8b8011a88d | 243 | #ifdef VSCODE |
shimizuta | 27:79b4b932a6dd | 244 | fclose(fp); |
shimizuta | 27:79b4b932a6dd | 245 | #endif |
shimizuta | 29:7d8b8011a88d | 246 | #endif |
shimizuta | 2:a92568bdeb5c | 247 | } |
shimizuta | 27:79b4b932a6dd | 248 | //一サイクル分進む |
shimizuta | 27:79b4b932a6dd | 249 | void MoveOneCycle(Walk walkway, OneLeg leg[4]) |
yuto17320508 | 5:556d5a5e9d24 | 250 | { |
shimizuta | 27:79b4b932a6dd | 251 | #ifndef VSCODE |
shimizuta | 9:905f93247688 | 252 | timer.reset(); |
shimizuta | 9:905f93247688 | 253 | timer.start(); |
shimizuta | 27:79b4b932a6dd | 254 | #endif |
shimizuta | 27:79b4b932a6dd | 255 | int count = walkway.GetOneWalkTime() / walkway.calctime_s_; |
shimizuta | 27:79b4b932a6dd | 256 | for (int i = 0; i < count; i++) |
yuto17320508 | 8:21b932c4e6c5 | 257 | { |
shimizuta | 27:79b4b932a6dd | 258 | #ifndef VSCODE |
shimizuta | 9:905f93247688 | 259 | float time_s = timer.read(); |
shimizuta | 27:79b4b932a6dd | 260 | #endif |
shimizuta | 29:7d8b8011a88d | 261 | //4本の足それぞれの足先サーボ角度更新 |
shimizuta | 29:7d8b8011a88d | 262 | if (walkway.Cal4LegsPosi(leg) == 1) |
shimizuta | 29:7d8b8011a88d | 263 | printf("error: time = %f\r\n", i * walkway.calctime_s_); |
shimizuta | 19:1adc7302cfd9 | 264 | #ifdef USE_CAN |
shimizuta | 27:79b4b932a6dd | 265 | SendRad(leg[2], leg[3]); //slave_mbed分の足の目標位置を送信 |
shimizuta | 19:1adc7302cfd9 | 266 | #endif |
shimizuta | 9:905f93247688 | 267 | //自身が動かす足のサーボを動かす |
shimizuta | 16:0069a56f11a3 | 268 | MoveServo(leg[0], 0, 0); |
shimizuta | 11:e81425872740 | 269 | MoveServo(leg[1], 1, 0); |
shimizuta | 27:79b4b932a6dd | 270 | #ifndef VSCODE |
shimizuta | 9:905f93247688 | 271 | wait_ms(kServoSpan_ms); |
shimizuta | 27:79b4b932a6dd | 272 | #endif |
shimizuta | 16:0069a56f11a3 | 273 | MoveServo(leg[0], 0, 1); |
shimizuta | 11:e81425872740 | 274 | MoveServo(leg[1], 1, 1); |
shimizuta | 29:7d8b8011a88d | 275 | #ifdef VSCODE |
shimizuta | 27:79b4b932a6dd | 276 | //ファイルに書き込み。time[s],x[0],y[0],x[1],y[1],x[2],y[2],x[3],y[3]の順 |
shimizuta | 27:79b4b932a6dd | 277 | fprintf(fp, "%f", i * walkway.calctime_s_); |
shimizuta | 27:79b4b932a6dd | 278 | for (int i = 0; i < 4; i++) |
shimizuta | 27:79b4b932a6dd | 279 | fprintf(fp, ",%f,%f", leg[i].GetX_m(), leg[i].GetY_m()); |
shimizuta | 27:79b4b932a6dd | 280 | fprintf(fp, "\r\n"); |
shimizuta | 29:7d8b8011a88d | 281 | #else |
shimizuta | 27:79b4b932a6dd | 282 | //計算周期がwalkway.calctime_s_になるようwait |
shimizuta | 27:79b4b932a6dd | 283 | float rest_time_s = walkway.calctime_s_ - (timer.read() - time_s); |
shimizuta | 9:905f93247688 | 284 | if (rest_time_s > 0) |
shimizuta | 9:905f93247688 | 285 | wait(rest_time_s); |
shimizuta | 19:1adc7302cfd9 | 286 | else |
shimizuta | 19:1adc7302cfd9 | 287 | { //計算周期が達成できないときはDEBUGで知らせるだけ。動きはする。 |
shimizuta | 19:1adc7302cfd9 | 288 | DEBUG("error: rest_time_s = %f in Move()\r\n", rest_time_s); |
shimizuta | 14:d7cb429946f4 | 289 | led[0] = 1; |
shimizuta | 14:d7cb429946f4 | 290 | } |
shimizuta | 27:79b4b932a6dd | 291 | #endif |
shimizuta | 9:905f93247688 | 292 | } |
yuto17320508 | 5:556d5a5e9d24 | 293 | } |
shimizuta | 14:d7cb429946f4 | 294 | void MoveServo(OneLeg leg, int serial_num, int servo_id) |
yuto17320508 | 6:43708adf2e5d | 295 | { |
shimizuta | 27:79b4b932a6dd | 296 | #ifndef VSCODE |
shimizuta | 11:e81425872740 | 297 | float degree = leg.GetRad(servo_id) * kRadToDegree; |
shimizuta | 14:d7cb429946f4 | 298 | //サーボの座標系に変更 |
shimizuta | 14:d7cb429946f4 | 299 | float servo_degree = kServoSign[serial_num][servo_id] * degree + kOriginDegree[serial_num][servo_id]; |
shimizuta | 27:79b4b932a6dd | 300 | // DEBUG("servo_degree[%d][%d],%f\r\n", serial_num, servo_id, servo_degree); |
shimizuta | 14:d7cb429946f4 | 301 | servo[serial_num].set_degree(servo_id, servo_degree); |
shimizuta | 27:79b4b932a6dd | 302 | #endif |
shimizuta | 12:2ac37fe6c3bb | 303 | } |
shimizuta | 27:79b4b932a6dd | 304 | void WaitStdin(char startchar) |
shimizuta | 27:79b4b932a6dd | 305 | { |
shimizuta | 27:79b4b932a6dd | 306 | #ifndef USE_ROS |
shimizuta | 27:79b4b932a6dd | 307 | char str[255] = {}; |
shimizuta | 27:79b4b932a6dd | 308 | do |
shimizuta | 27:79b4b932a6dd | 309 | { |
shimizuta | 27:79b4b932a6dd | 310 | printf("put '%c', then start\r\n", startchar); |
shimizuta | 27:79b4b932a6dd | 311 | scanf("%s", str); |
shimizuta | 27:79b4b932a6dd | 312 | } while (str[0] != startchar); |
shimizuta | 27:79b4b932a6dd | 313 | #endif |
shimizuta | 27:79b4b932a6dd | 314 | } |
shimizuta | 27:79b4b932a6dd | 315 | int FileOpen() //1:異常終了 |
shimizuta | 27:79b4b932a6dd | 316 | { |
shimizuta | 27:79b4b932a6dd | 317 | if ((fp = fopen("data.csv", "w")) == NULL) |
shimizuta | 27:79b4b932a6dd | 318 | { |
shimizuta | 27:79b4b932a6dd | 319 | printf("error : FileSave()\r\n"); |
shimizuta | 27:79b4b932a6dd | 320 | return 1; |
shimizuta | 27:79b4b932a6dd | 321 | } |
shimizuta | 27:79b4b932a6dd | 322 | 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 | 323 | return 0; |
shimizuta | 27:79b4b932a6dd | 324 | } |
shimizuta | 27:79b4b932a6dd | 325 | #ifdef USE_ROS |
shimizuta | 27:79b4b932a6dd | 326 | void callback(const geometry_msgs::Vector3 &cmd_vel) |
shimizuta | 27:79b4b932a6dd | 327 | { |
shimizuta | 27:79b4b932a6dd | 328 | float left_vel = cmd_vel.x; |
shimizuta | 27:79b4b932a6dd | 329 | float right_vel = cmd_vel.y; |
shimizuta | 27:79b4b932a6dd | 330 | //閾値は要検討 |
shimizuta | 27:79b4b932a6dd | 331 | if (right_vel < left_vel) |
shimizuta | 27:79b4b932a6dd | 332 | MoveOneCycle(walks[TURNRIGHT], leg); |
shimizuta | 27:79b4b932a6dd | 333 | else if (left_vel < right_vel) |
shimizuta | 27:79b4b932a6dd | 334 | MoveOneCycle(walks[TURNLEFT], leg); |
shimizuta | 27:79b4b932a6dd | 335 | else |
shimizuta | 27:79b4b932a6dd | 336 | MoveOneCycle(walks[STRAIGHT], leg); |
shimizuta | 27:79b4b932a6dd | 337 | } |
shimizuta | 27:79b4b932a6dd | 338 | #endif |
shimizuta | 29:7d8b8011a88d | 339 | //param back_height_on_step:段差の高さ。後ろにあるとする。前にあるときはマイナスを入れる |
shimizuta | 29:7d8b8011a88d | 340 | float GetSteepBodyRad(float back_height_on_step) |
shimizuta | 29:7d8b8011a88d | 341 | { |
shimizuta | 29:7d8b8011a88d | 342 | float offset_hight = back_height_on_step + leg[LEFT_B].GetY_m() - leg[LEFT_B].GetY_m(); |
shimizuta | 29:7d8b8011a88d | 343 | float theta = atan2(offset_hight, (float)(sqrt(0.09 - offset_hight * offset_hight))); |
shimizuta | 29:7d8b8011a88d | 344 | return theta; |
shimizuta | 29:7d8b8011a88d | 345 | } |