test

Dependencies:   mbed ros_lib_kinetic nhk19mr2_can_info splitData SerialHalfDuplex_HM

Committer:
shimizuta
Date:
Thu Feb 28 09:39:02 2019 +0000
Revision:
33:945d634d4c9b
Parent:
32:dc684a0b8448
Child:
34:89d701e15cdf
cannot over come

Who changed what in which revision?

UserRevisionLine numberNew 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 #endif
shimizuta 27:79b4b932a6dd 16 //#define DEBUG_ON //デバッグ用。使わないときはコメントアウト
shimizuta 27:79b4b932a6dd 17 #include "debug.h"
shimizuta 11:e81425872740 18 #include "OneLeg.h" ///足先の座標を保存するクラス。x,yやサーボの角度の保存、サーボの駆動も行う。他の足を考慮した処理は別のクラスに任せる。
shimizuta 11:e81425872740 19 #include "Walk.h" //歩き方に関するファイル
yuto17320508 4:fffdb273836e 20
shimizuta 27:79b4b932a6dd 21 ////////////あまり変化させないパラメータ。この他は全てmainの上(ParamSetup())にある。
shimizuta 27:79b4b932a6dd 22 const int kServoSpan_ms = 6; //サーボの送信間隔
shimizuta 19:1adc7302cfd9 23 const float kBetweenServoHalf_m = 0.03 * 0.5; //サーボ間の距離の半分
shimizuta 19:1adc7302cfd9 24 float kLegLength1[2] = {0.1, 0.1};
shimizuta 29:7d8b8011a88d 25 float kLegLength2[2] = {0.2452 + 0.0025, 0.23};
shimizuta 14:d7cb429946f4 26 //サーボの正負と座標系の正負の補正.足で一セット。
shimizuta 27:79b4b932a6dd 27 const int kServoSign[2][2] = {{1, -1}, {-1, 1}};
shimizuta 14:d7cb429946f4 28 //欲しい座標系0度でのサーボのICSマネージャーの値
shimizuta 27:79b4b932a6dd 29 const double kServoValToDegree = 270.0 / (11500 - 3500); //ICSの値を度に変換
shimizuta 14:d7cb429946f4 30 const double kOriginDegree[2][2] = {
shimizuta 14:d7cb429946f4 31 {
shimizuta 31:86eb746eaed4 32 (7639 - 3500) * kServoValToDegree,
shimizuta 31:86eb746eaed4 33 (7662 - 3500) * kServoValToDegree + 180,
shimizuta 14:d7cb429946f4 34 },
shimizuta 14:d7cb429946f4 35 {
shimizuta 31:86eb746eaed4 36 (6431 - 3500) * kServoValToDegree,
shimizuta 31:86eb746eaed4 37 (8135 - 3500) * kServoValToDegree - 180,
shimizuta 14:d7cb429946f4 38 },
shimizuta 14:d7cb429946f4 39 };
shimizuta 9:905f93247688 40 ///////////////
shimizuta 27:79b4b932a6dd 41 #ifndef VSCODE
shimizuta 9:905f93247688 42 Timer timer;
shimizuta 11:e81425872740 43 KondoServo servo[2] = {
shimizuta 11:e81425872740 44 KondoServo(pin_serial_servo_tx[0], pin_serial_servo_rx[0]),
shimizuta 11:e81425872740 45 KondoServo(pin_serial_servo_tx[1], pin_serial_servo_rx[1]),
shimizuta 11:e81425872740 46 };
shimizuta 27:79b4b932a6dd 47 DigitalOut led[4] = {DigitalOut(LED1), DigitalOut(LED2), DigitalOut(LED3), DigitalOut(LED4)};
shimizuta 27:79b4b932a6dd 48 #endif
shimizuta 27:79b4b932a6dd 49 #ifdef USE_ROS
shimizuta 33:945d634d4c9b 50 #include <ros.h>
shimizuta 33:945d634d4c9b 51 #include <geometry_msgs/Vector3.h>
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 33:945d634d4c9b 140 {.time_s = 0.2, .x_m = 0, .y_m = 0.32},
shimizuta 33:945d634d4c9b 141 {.time_s = 0.2, .x_m = -0.13, .y_m = 0.15},
shimizuta 33:945d634d4c9b 142 {.time_s = 0.2, .x_m = 0.12, .y_m = 0.15},
shimizuta 33:945d634d4c9b 143 {.time_s = 0.6, .x_m = 0.12, .y_m = 0.2},
shimizuta 33:945d634d4c9b 144 {.time_s = 0,
shimizuta 33:945d634d4c9b 145 .x_m = 0.05, .y_m = 0.2}};
shimizuta 33:945d634d4c9b 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.2, .x_m = -0, .y_m = 0.32},
shimizuta 32:dc684a0b8448 149 {.time_s = 0.2, .x_m = -0.13, .y_m = 0.15},
shimizuta 32:dc684a0b8448 150 {.time_s = 0.2, .x_m = 0.12, .y_m = 0.15},
shimizuta 32:dc684a0b8448 151 {.time_s = 0, .x_m = 0.12, .y_m = 0.2}};
shimizuta 33:945d634d4c9b 152 LineParam over_come_backleg[] = {
shimizuta 32:dc684a0b8448 153 {.time_s = 0.6, .x_m = 0, .y_m = 0.3},
shimizuta 32:dc684a0b8448 154 {.time_s = 0.2, .x_m = 0, .y_m = 0.3},
shimizuta 33:945d634d4c9b 155 {.time_s = 0.4, .x_m = -0.1,.y_m = 0.3},
shimizuta 32:dc684a0b8448 156 {.time_s = 0, .x_m = -0.1,.y_m = 0.3},
shimizuta 32:dc684a0b8448 157 };
shimizuta 32:dc684a0b8448 158 walks[OVERCOME].SetOneLegFreeLinesParam(RIGHT_F, over_come_front_r, sizeof(over_come_front_r)/ sizeof(over_come_front_r[0]));
shimizuta 32:dc684a0b8448 159 walks[OVERCOME].SetOneLegFreeLinesParam(LEFT_F, over_come_front_l, sizeof(over_come_front_l)/sizeof(over_come_front_l[0]));
shimizuta 33:945d634d4c9b 160 walks[OVERCOME].SetOneLegFreeLinesParam(LEFT_B, over_come_backleg, sizeof(over_come_backleg)/sizeof(over_come_backleg[0]));
shimizuta 33:945d634d4c9b 161 walks[OVERCOME].SetOneLegFreeLinesParam(RIGHT_B, over_come_backleg, sizeof(over_come_backleg)/sizeof(over_come_backleg[0]));
shimizuta 33:945d634d4c9b 162
shimizuta 33:945d634d4c9b 163
shimizuta 33:945d634d4c9b 164 LineParam over_come_front_r[] = {
shimizuta 33:945d634d4c9b 165 {.time_s = 0.2, .x_m = 0, .y_m = 0.32},
shimizuta 33:945d634d4c9b 166 {.time_s = 0.2, .x_m = -0.13, .y_m = 0.15},
shimizuta 33:945d634d4c9b 167 {.time_s = 0.2, .x_m = 0.12, .y_m = 0.15},
shimizuta 33:945d634d4c9b 168 {.time_s = 0.6, .x_m = 0.12, .y_m = 0.2},
shimizuta 33:945d634d4c9b 169 {.time_s = 0,
shimizuta 33:945d634d4c9b 170 .x_m = 0.05, .y_m = 0.2}};
shimizuta 33:945d634d4c9b 171 LineParam over_come_front_l[] = {
shimizuta 33:945d634d4c9b 172 {.time_s = 0.6, .x_m = -0, .y_m = 0.32},
shimizuta 33:945d634d4c9b 173 {.time_s = 0.2, .x_m = -0, .y_m = 0.32},
shimizuta 33:945d634d4c9b 174 {.time_s = 0.2, .x_m = -0.13, .y_m = 0.15},
shimizuta 33:945d634d4c9b 175 {.time_s = 0.2, .x_m = 0.12, .y_m = 0.15},
shimizuta 33:945d634d4c9b 176 {.time_s = 0, .x_m = 0.12, .y_m = 0.2}};
shimizuta 33:945d634d4c9b 177 LineParam over_come_backleg[] = {
shimizuta 33:945d634d4c9b 178 {.time_s = 0.6, .x_m = 0, .y_m = 0.3},
shimizuta 33:945d634d4c9b 179 {.time_s = 0.2, .x_m = 0, .y_m = 0.3},
shimizuta 33:945d634d4c9b 180 {.time_s = 0.4, .x_m = -0.1,.y_m = 0.3},
shimizuta 33:945d634d4c9b 181 {.time_s = 0, .x_m = -0.1,.y_m = 0.3},
shimizuta 33:945d634d4c9b 182 };
shimizuta 33:945d634d4c9b 183 walks[OVERCOME].SetOneLegFreeLinesParam(RIGHT_F, over_come_front_r, sizeof(over_come_front_r)/ sizeof(over_come_front_r[0]));
shimizuta 33:945d634d4c9b 184 walks[OVERCOME].SetOneLegFreeLinesParam(LEFT_F, over_come_front_l, sizeof(over_come_front_l)/sizeof(over_come_front_l[0]));
shimizuta 33:945d634d4c9b 185 walks[OVERCOME].SetOneLegFreeLinesParam(LEFT_B, over_come_backleg, sizeof(over_come_backleg)/sizeof(over_come_backleg[0]));
shimizuta 33:945d634d4c9b 186 walks[OVERCOME].SetOneLegFreeLinesParam(RIGHT_B, over_come_backleg, sizeof(over_come_backleg)/sizeof(over_come_backleg[0]));
shimizuta 33:945d634d4c9b 187
shimizuta 31:86eb746eaed4 188
shimizuta 31:86eb746eaed4 189 // SANDDUNE, //前足だけがsandduneに乗った状態で進む
shimizuta 32:dc684a0b8448 190 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 191 stridetime_s = 0.2, toptime_s = 0.07, buffer_time_s = 0.03;
shimizuta 31:86eb746eaed4 192 walks[SANDDUNE].SetAllLegTriangleParam // 4足一括で設定
shimizuta 32:dc684a0b8448 193 (offset_x_m, offset_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s);
shimizuta 32:dc684a0b8448 194 walks[SANDDUNE].ChangeOneParam(LEFT_F, OFFSET_X_M, 0);
shimizuta 32:dc684a0b8448 195 walks[SANDDUNE].ChangeOneParam(RIGHT_F, OFFSET_X_M, 0);
shimizuta 32:dc684a0b8448 196 walks[SANDDUNE].ChangeOneParam(LEFT_F, OFFSET_Y_M, offset_y_m - 0.1);
shimizuta 32:dc684a0b8448 197 walks[SANDDUNE].ChangeOneParam(RIGHT_F, OFFSET_Y_M, offset_y_m - 0.1);
shimizuta 31:86eb746eaed4 198 walks[SANDDUNE].SetOffsetTime(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1])
shimizuta 31:86eb746eaed4 199
shimizuta 31:86eb746eaed4 200 // OVERCOME_BACK, //後ろ足を乗せる
shimizuta 31:86eb746eaed4 201 float offset_x_back = -0.05;
shimizuta 32:dc684a0b8448 202 LineParam overcomebackParams[] = {
shimizuta 32:dc684a0b8448 203 {.time_s = 0.8, .x_m = -0.05f + offset_x_back, .y_m = 0.3},
shimizuta 32:dc684a0b8448 204 {.time_s = 0.2, .x_m = -0.05f + offset_x_back, .y_m = 0.3},
shimizuta 32:dc684a0b8448 205 {.time_s = 0.2, .x_m = -0.1f + offset_x_back, .y_m = 0.16},
shimizuta 32:dc684a0b8448 206 {.time_s = 0.2, .x_m = 0.1f + offset_x_back, .y_m = 0.16},
shimizuta 32:dc684a0b8448 207 {.time_s = 0.2, .x_m = 0.1f + offset_x_back, .y_m = 0.2},
shimizuta 32:dc684a0b8448 208 {.time_s = 0.8, .x_m = 0.05f + offset_x_back, .y_m = 0.2},
shimizuta 32:dc684a0b8448 209 {.time_s = 0, .x_m = 0.05f + offset_x_back, .y_m = 0.2},
shimizuta 31:86eb746eaed4 210 };
shimizuta 32:dc684a0b8448 211 LineParam standbackParams[] = {
shimizuta 32:dc684a0b8448 212 {.time_s = 0.6, .x_m = 0.0f + offset_x_back, .y_m = 0.2},
shimizuta 32:dc684a0b8448 213 {.time_s = 0.2, .x_m = 0.0f + offset_x_back, .y_m = 0.2},
shimizuta 32:dc684a0b8448 214 {.time_s = 0.6, .x_m = -0.05f + offset_x_back, .y_m = 0.2},
shimizuta 32:dc684a0b8448 215 {.time_s = 0, .x_m = -0.05f + offset_x_back, .y_m = 0.2},
shimizuta 31:86eb746eaed4 216 };
shimizuta 31:86eb746eaed4 217 walks[OVERCOME_BACK].SetOneLegFreeLinesParam(LEFT_F, standbackParams, sizeof(standbackParams) / sizeof(standbackParams[0]));
shimizuta 31:86eb746eaed4 218 walks[OVERCOME_BACK].SetOneLegFreeLinesParam(RIGHT_F, standbackParams, sizeof(standbackParams) / sizeof(standbackParams[0]));
shimizuta 31:86eb746eaed4 219 walks[OVERCOME_BACK].SetOneLegFreeLinesParam(LEFT_B, overcomebackParams, sizeof(overcomebackParams) / sizeof(overcomebackParams[0]));
shimizuta 31:86eb746eaed4 220 walks[OVERCOME_BACK].SetOneLegFreeLinesParam(RIGHT_B, overcomebackParams, sizeof(overcomebackParams) / sizeof(overcomebackParams[0]));
shimizuta 31:86eb746eaed4 221 walks[OVERCOME_BACK].SetOffsetTime(0, 0, 0.5, 0);
shimizuta 31:86eb746eaed4 222
shimizuta 31:86eb746eaed4 223 // STRAIGHT_W, //両足がsandduneに乗った状態で進む
shimizuta 32:dc684a0b8448 224 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 225 stridetime_s = 0.2, toptime_s = 0.07, buffer_time_s = 0.03;
shimizuta 31:86eb746eaed4 226 walks[STRAIGHT_W].SetAllLegTriangleParam // 4足一括で設定
shimizuta 32:dc684a0b8448 227 (offset_x_m, offset_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s);
shimizuta 32:dc684a0b8448 228 walks[STRAIGHT_W].ChangeOneParam(LEFT_F, OFFSET_X_M, 0);
shimizuta 32:dc684a0b8448 229 walks[STRAIGHT_W].ChangeOneParam(RIGHT_F, OFFSET_X_M, 0);
shimizuta 31:86eb746eaed4 230 walks[STRAIGHT_W].SetOffsetTime(0, 0.5, 0.5, 0);
shimizuta 31:86eb746eaed4 231
shimizuta 32:dc684a0b8448 232 // ROPE_F, //ropeをまたぐ(前足)
shimizuta 32:dc684a0b8448 233 offset_x_m = 0, offset_y_m = 0.3, stride_m = .15, height_m = 0.03, buffer_height_m = 0.01,
shimizuta 31:86eb746eaed4 234 stridetime_s = 1, toptime_s = 0.35, buffer_time_s = 0.05;
shimizuta 31:86eb746eaed4 235 walks[ROPE_F].SetAllLegTriangleParam // 4足一括で設定
shimizuta 32:dc684a0b8448 236 (offset_x_m, offset_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s);
shimizuta 31:86eb746eaed4 237 walks[ROPE_F].ChangeOneParam(LEFT_F, HEIGHT_M, 0.15); //前足だけ足を延ばす
shimizuta 31:86eb746eaed4 238 walks[ROPE_F].ChangeOneParam(RIGHT_F, HEIGHT_M, 0.15);
shimizuta 31:86eb746eaed4 239 walks[ROPE_F].SetOffsetTime(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1])
shimizuta 31:86eb746eaed4 240
shimizuta 31:86eb746eaed4 241 // ROPE_B, //ropeをまたぐ(後ろ足)
shimizuta 32:dc684a0b8448 242 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 243 stridetime_s = 1, toptime_s = 0.35, buffer_time_s = 0.05;
shimizuta 31:86eb746eaed4 244 walks[ROPE_B].SetAllLegTriangleParam // 4足一括で設定
shimizuta 32:dc684a0b8448 245 (offset_x_m, offset_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s);
shimizuta 31:86eb746eaed4 246 walks[ROPE_B].ChangeOneParam(LEFT_B, HEIGHT_M, 0.15); //後ろ足だけ足を延ばす
shimizuta 31:86eb746eaed4 247 walks[ROPE_B].ChangeOneParam(RIGHT_B, HEIGHT_M, 0.15);
shimizuta 32:dc684a0b8448 248 walks[ROPE_B].ChangeOneParam(LEFT_B, OFFSET_X_M, -0.07);
shimizuta 32:dc684a0b8448 249 walks[ROPE_B].ChangeOneParam(RIGHT_B, OFFSET_X_M, -0.07);
shimizuta 31:86eb746eaed4 250 walks[ROPE_B].SetOffsetTime(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1])
yuto17320508 18:0033ef1814ba 251 }
shimizuta 27:79b4b932a6dd 252 Walk walks[END]; //歩行法
shimizuta 9:905f93247688 253 int main()
yuto17320508 5:556d5a5e9d24 254 {
shimizuta 29:7d8b8011a88d 255 #ifdef VSCODE
shimizuta 27:79b4b932a6dd 256 if (FileOpen()) //csv fileに書き込み
shimizuta 27:79b4b932a6dd 257 return 1; //異常終了したら強制終了
shimizuta 29:7d8b8011a88d 258 #endif
shimizuta 27:79b4b932a6dd 259 DEBUG("param set start");
shimizuta 27:79b4b932a6dd 260 ParamsSetup(walks, leg); //各動きの際の足の軌道を設定。パラメータはこの関数内に打ち込む
shimizuta 27:79b4b932a6dd 261 for (int i = 0; i < END; i++) //軌道のチェック
shimizuta 27:79b4b932a6dd 262 {
shimizuta 27:79b4b932a6dd 263 if (walks[i].CheckOrbit(leg[0]) == 1) //軌道が定義外なら
shimizuta 29:7d8b8011a88d 264 {
shimizuta 32:dc684a0b8448 265 printf("error: move pattern %d\r\n", i);
shimizuta 29:7d8b8011a88d 266 return 1; //強制終了.errorは内部の関数からprintfで知らせる
shimizuta 29:7d8b8011a88d 267 }
shimizuta 27:79b4b932a6dd 268 }
shimizuta 29:7d8b8011a88d 269 printf("Stand up?\r\n");
shimizuta 27:79b4b932a6dd 270 WaitStdin('y'); // ボタンを押したら立つ
shimizuta 27:79b4b932a6dd 271 MoveOneCycle(walks[STANDUP], leg);
shimizuta 29:7d8b8011a88d 272 printf("Move?\r\n");
shimizuta 27:79b4b932a6dd 273 WaitStdin('y'); // ボタンを押したらスタート
shimizuta 27:79b4b932a6dd 274 #ifdef USE_ROS
shimizuta 27:79b4b932a6dd 275 nh_mbed.getHardware()->setBaud(115200);
shimizuta 27:79b4b932a6dd 276 nh_mbed.initNode();
shimizuta 27:79b4b932a6dd 277 nh_mbed.subscribe(sub_vel);
shimizuta 27:79b4b932a6dd 278 while (1)
shimizuta 27:79b4b932a6dd 279 nh_mbed.spinOnce();
shimizuta 27:79b4b932a6dd 280 #else
shimizuta 32:dc684a0b8448 281
shimizuta 32:dc684a0b8448 282 for(int k=0;k<5;k++)MoveOneCycle(walks[STRAIGHT], leg);
shimizuta 32:dc684a0b8448 283 for(int k=0;k<1;k++)MoveOneCycle(walks[UP], leg);
shimizuta 32:dc684a0b8448 284 for(int k=0;k<1;k++)MoveOneCycle(walks[OVERCOME],leg);
shimizuta 32:dc684a0b8448 285 for(int k=0;k<5;k++) MoveOneCycle(walks[SANDDUNE],leg);
shimizuta 33:945d634d4c9b 286 // for(int k=0;k<1;k++)MoveOneCycle(walks[OVERCOME_BACK],leg);
shimizuta 33:945d634d4c9b 287 // for(int k=0;k<3;k++)MoveOneCycle(walks[STRAIGHT_W], leg);
shimizuta 32:dc684a0b8448 288 // for(int k=0;k<5;k++)Move(*straight_w2, leg,(*straight_w2).GetTheta(0.1));
shimizuta 32:dc684a0b8448 289 // for(int k=0;k<3;k++)Move(*straight, leg);
shimizuta 32:dc684a0b8448 290 /*
shimizuta 27:79b4b932a6dd 291 for (int i = 1; i < END; i++) //ENDになるまでWalkWayの順に動作
shimizuta 27:79b4b932a6dd 292 {
shimizuta 32:dc684a0b8448 293 printf("Move %d\r\n", i);
shimizuta 32:dc684a0b8448 294 for (int j = 0; j < 20; j++) //debug用に2歩進む
shimizuta 32:dc684a0b8448 295 {
shimizuta 32:dc684a0b8448 296 if(MoveOneCycle(walks[i], leg) == 1)
shimizuta 32:dc684a0b8448 297 printf("error:In MoveOneCycle. WalkWay %d\r\n",i);
shimizuta 32:dc684a0b8448 298 }
shimizuta 27:79b4b932a6dd 299 }
shimizuta 32:dc684a0b8448 300
shimizuta 27:79b4b932a6dd 301 MoveOneCycle(walks[STANDUP], leg); //最後はLRFを保護するためSTANDUPの状態で終わる
shimizuta 32:dc684a0b8448 302
shimizuta 32:dc684a0b8448 303 */ printf("program end\r\n");
shimizuta 29:7d8b8011a88d 304 #ifdef VSCODE
shimizuta 27:79b4b932a6dd 305 fclose(fp);
shimizuta 27:79b4b932a6dd 306 #endif
shimizuta 29:7d8b8011a88d 307 #endif
shimizuta 2:a92568bdeb5c 308 }
shimizuta 32:dc684a0b8448 309 //一サイクル分進む.return 1:異常終了
shimizuta 32:dc684a0b8448 310 int MoveOneCycle(Walk walkway, OneLeg leg[4])
yuto17320508 5:556d5a5e9d24 311 {
shimizuta 27:79b4b932a6dd 312 #ifndef VSCODE
shimizuta 9:905f93247688 313 timer.reset();
shimizuta 9:905f93247688 314 timer.start();
shimizuta 27:79b4b932a6dd 315 #endif
shimizuta 27:79b4b932a6dd 316 int count = walkway.GetOneWalkTime() / walkway.calctime_s_;
shimizuta 27:79b4b932a6dd 317 for (int i = 0; i < count; i++)
yuto17320508 8:21b932c4e6c5 318 {
shimizuta 27:79b4b932a6dd 319 #ifndef VSCODE
shimizuta 9:905f93247688 320 float time_s = timer.read();
shimizuta 27:79b4b932a6dd 321 #endif
shimizuta 29:7d8b8011a88d 322 //4本の足それぞれの足先サーボ角度更新
shimizuta 29:7d8b8011a88d 323 if (walkway.Cal4LegsPosi(leg) == 1)
shimizuta 32:dc684a0b8448 324 {
shimizuta 29:7d8b8011a88d 325 printf("error: time = %f\r\n", i * walkway.calctime_s_);
shimizuta 32:dc684a0b8448 326 return 1;
shimizuta 32:dc684a0b8448 327 }
shimizuta 19:1adc7302cfd9 328 #ifdef USE_CAN
shimizuta 27:79b4b932a6dd 329 SendRad(leg[2], leg[3]); //slave_mbed分の足の目標位置を送信
shimizuta 19:1adc7302cfd9 330 #endif
shimizuta 9:905f93247688 331 //自身が動かす足のサーボを動かす
shimizuta 16:0069a56f11a3 332 MoveServo(leg[0], 0, 0);
shimizuta 11:e81425872740 333 MoveServo(leg[1], 1, 0);
shimizuta 27:79b4b932a6dd 334 #ifndef VSCODE
shimizuta 9:905f93247688 335 wait_ms(kServoSpan_ms);
shimizuta 27:79b4b932a6dd 336 #endif
shimizuta 16:0069a56f11a3 337 MoveServo(leg[0], 0, 1);
shimizuta 11:e81425872740 338 MoveServo(leg[1], 1, 1);
shimizuta 29:7d8b8011a88d 339 #ifdef VSCODE
shimizuta 27:79b4b932a6dd 340 //ファイルに書き込み。time[s],x[0],y[0],x[1],y[1],x[2],y[2],x[3],y[3]の順
shimizuta 27:79b4b932a6dd 341 fprintf(fp, "%f", i * walkway.calctime_s_);
shimizuta 27:79b4b932a6dd 342 for (int i = 0; i < 4; i++)
shimizuta 27:79b4b932a6dd 343 fprintf(fp, ",%f,%f", leg[i].GetX_m(), leg[i].GetY_m());
shimizuta 27:79b4b932a6dd 344 fprintf(fp, "\r\n");
shimizuta 29:7d8b8011a88d 345 #else
shimizuta 27:79b4b932a6dd 346 //計算周期がwalkway.calctime_s_になるようwait
shimizuta 27:79b4b932a6dd 347 float rest_time_s = walkway.calctime_s_ - (timer.read() - time_s);
shimizuta 9:905f93247688 348 if (rest_time_s > 0)
shimizuta 9:905f93247688 349 wait(rest_time_s);
shimizuta 19:1adc7302cfd9 350 else
shimizuta 19:1adc7302cfd9 351 { //計算周期が達成できないときはDEBUGで知らせるだけ。動きはする。
shimizuta 19:1adc7302cfd9 352 DEBUG("error: rest_time_s = %f in Move()\r\n", rest_time_s);
shimizuta 14:d7cb429946f4 353 led[0] = 1;
shimizuta 14:d7cb429946f4 354 }
shimizuta 27:79b4b932a6dd 355 #endif
shimizuta 9:905f93247688 356 }
shimizuta 32:dc684a0b8448 357 return 0;
yuto17320508 5:556d5a5e9d24 358 }
shimizuta 14:d7cb429946f4 359 void MoveServo(OneLeg leg, int serial_num, int servo_id)
yuto17320508 6:43708adf2e5d 360 {
shimizuta 27:79b4b932a6dd 361 #ifndef VSCODE
shimizuta 11:e81425872740 362 float degree = leg.GetRad(servo_id) * kRadToDegree;
shimizuta 14:d7cb429946f4 363 //サーボの座標系に変更
shimizuta 14:d7cb429946f4 364 float servo_degree = kServoSign[serial_num][servo_id] * degree + kOriginDegree[serial_num][servo_id];
shimizuta 27:79b4b932a6dd 365 // DEBUG("servo_degree[%d][%d],%f\r\n", serial_num, servo_id, servo_degree);
shimizuta 14:d7cb429946f4 366 servo[serial_num].set_degree(servo_id, servo_degree);
shimizuta 27:79b4b932a6dd 367 #endif
shimizuta 12:2ac37fe6c3bb 368 }
shimizuta 27:79b4b932a6dd 369 void WaitStdin(char startchar)
shimizuta 27:79b4b932a6dd 370 {
shimizuta 27:79b4b932a6dd 371 #ifndef USE_ROS
shimizuta 27:79b4b932a6dd 372 char str[255] = {};
shimizuta 27:79b4b932a6dd 373 do
shimizuta 27:79b4b932a6dd 374 {
shimizuta 27:79b4b932a6dd 375 printf("put '%c', then start\r\n", startchar);
shimizuta 27:79b4b932a6dd 376 scanf("%s", str);
shimizuta 27:79b4b932a6dd 377 } while (str[0] != startchar);
shimizuta 27:79b4b932a6dd 378 #endif
shimizuta 27:79b4b932a6dd 379 }
shimizuta 27:79b4b932a6dd 380 int FileOpen() //1:異常終了
shimizuta 27:79b4b932a6dd 381 {
shimizuta 27:79b4b932a6dd 382 if ((fp = fopen("data.csv", "w")) == NULL)
shimizuta 27:79b4b932a6dd 383 {
shimizuta 27:79b4b932a6dd 384 printf("error : FileSave()\r\n");
shimizuta 27:79b4b932a6dd 385 return 1;
shimizuta 27:79b4b932a6dd 386 }
shimizuta 27:79b4b932a6dd 387 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 388 return 0;
shimizuta 27:79b4b932a6dd 389 }
shimizuta 27:79b4b932a6dd 390 #ifdef USE_ROS
shimizuta 27:79b4b932a6dd 391 void callback(const geometry_msgs::Vector3 &cmd_vel)
shimizuta 27:79b4b932a6dd 392 {
shimizuta 27:79b4b932a6dd 393 float left_vel = cmd_vel.x;
shimizuta 27:79b4b932a6dd 394 float right_vel = cmd_vel.y;
shimizuta 27:79b4b932a6dd 395 //閾値は要検討
shimizuta 27:79b4b932a6dd 396 if (right_vel < left_vel)
shimizuta 27:79b4b932a6dd 397 MoveOneCycle(walks[TURNRIGHT], leg);
shimizuta 27:79b4b932a6dd 398 else if (left_vel < right_vel)
shimizuta 27:79b4b932a6dd 399 MoveOneCycle(walks[TURNLEFT], leg);
shimizuta 27:79b4b932a6dd 400 else
shimizuta 27:79b4b932a6dd 401 MoveOneCycle(walks[STRAIGHT], leg);
shimizuta 27:79b4b932a6dd 402 }
shimizuta 27:79b4b932a6dd 403 #endif
shimizuta 29:7d8b8011a88d 404 //param back_height_on_step:段差の高さ。後ろにあるとする。前にあるときはマイナスを入れる
shimizuta 29:7d8b8011a88d 405 float GetSteepBodyRad(float back_height_on_step)
shimizuta 29:7d8b8011a88d 406 {
shimizuta 29:7d8b8011a88d 407 float offset_hight = back_height_on_step + leg[LEFT_B].GetY_m() - leg[LEFT_B].GetY_m();
shimizuta 29:7d8b8011a88d 408 float theta = atan2(offset_hight, (float)(sqrt(0.09 - offset_hight * offset_hight)));
shimizuta 29:7d8b8011a88d 409 return theta;
shimizuta 29:7d8b8011a88d 410 }