test

Dependencies:   mbed ros_lib_kinetic nhk19mr2_can_info splitData SerialHalfDuplex_HM

Committer:
shimizuta
Date:
Fri Mar 01 12:07:23 2019 +0000
Revision:
34:89d701e15cdf
Parent:
33:945d634d4c9b
Child:
35:b4e1b8f25cd7
over come and rope

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 34:89d701e15cdf 15 #include <ros.h>
shimizuta 34:89d701e15cdf 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" //歩き方に関するファイル
shimizuta 34:89d701e15cdf 22 #define USE_OVERCOME
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 34:89d701e15cdf 60
shimizuta 27:79b4b932a6dd 61 FILE *fp;
shimizuta 11:e81425872740 62 const float kRadToDegree = 180.0 / M_PI;
shimizuta 32:dc684a0b8448 63 int MoveOneCycle(Walk walkway, OneLeg leg[4]);
shimizuta 11:e81425872740 64 void MoveServo(OneLeg leg, int legnum, int servo_id);
shimizuta 27:79b4b932a6dd 65 void WaitStdin(char startchar);
shimizuta 27:79b4b932a6dd 66 int FileOpen();
shimizuta 27:79b4b932a6dd 67 int IsArrived(int count, int finish);
shimizuta 29:7d8b8011a88d 68 //段差があるときの機体角度を計算
shimizuta 29:7d8b8011a88d 69 //param back_height_on_step:段差の高さ。後ろにあるとする。前にあるときはマイナスを入れる
shimizuta 29:7d8b8011a88d 70 float GetSteepBodyRad(float back_height_on_step);
shimizuta 27:79b4b932a6dd 71
shimizuta 27:79b4b932a6dd 72 ////////調整するべきパラメータ
shimizuta 27:79b4b932a6dd 73 enum WalkWay
shimizuta 27:79b4b932a6dd 74 {
shimizuta 27:79b4b932a6dd 75 STANDUP,
shimizuta 34:89d701e15cdf 76 // STRAIGHT,
shimizuta 34:89d701e15cdf 77 // TURNLEFT,
shimizuta 34:89d701e15cdf 78 // TURNRIGHT,
shimizuta 34:89d701e15cdf 79 UP, //足を伸ばして立つ
shimizuta 31:86eb746eaed4 80 END,
shimizuta 27:79b4b932a6dd 81 };
shimizuta 27:79b4b932a6dd 82 void ParamsSetup(Walk walks[END], OneLeg leg[4]) //各パラメータの設定。減らしていく必要あり
shimizuta 19:1adc7302cfd9 83 {
shimizuta 27:79b4b932a6dd 84 Walk::calctime_s_ = 0.03; //計算周期
shimizuta 27:79b4b932a6dd 85 //足の作成、サイズデータのみの足の骨組.4足同じにしている
shimizuta 27:79b4b932a6dd 86 for (int i = 0; i < 4; i++)
shimizuta 27:79b4b932a6dd 87 leg[i] = OneLeg(kBetweenServoHalf_m, kLegLength1, kLegLength2);
shimizuta 29:7d8b8011a88d 88 walks[STANDUP].SetAllLegStandParam(0, 0.2, 0.5); //x,y,time_s.一括で設定できる
shimizuta 34:89d701e15cdf 89 /*
shimizuta 32:dc684a0b8448 90 //STRAIGT 論文通りのとき、offset_y_mは <=0.32
shimizuta 32:dc684a0b8448 91 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 34:89d701e15cdf 92 stridetime_s = 1, toptime_s = 0.1, buffer_time_s = 0.03;
shimizuta 31:86eb746eaed4 93 walks[STRAIGHT].SetAllLegTriangleParam // 4足を取り敢えず一括で設定してから
shimizuta 32:dc684a0b8448 94 (offset_x_m, offset_y_m, stride_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s);
shimizuta 32:dc684a0b8448 95 walks[STRAIGHT].ChangeOneParam(LEFT_F, OFFSET_X_M, 0);
shimizuta 32:dc684a0b8448 96 walks[STRAIGHT].ChangeOneParam(RIGHT_F, OFFSET_X_M, 0);
shimizuta 32:dc684a0b8448 97 walks[STRAIGHT].ChangeOneParam(LEFT_F, OFFSET_Y_M, 0.2);
shimizuta 32:dc684a0b8448 98 walks[STRAIGHT].ChangeOneParam(RIGHT_F, OFFSET_Y_M, 0.2);
shimizuta 29:7d8b8011a88d 99 walks[STRAIGHT].SetOffsetTime(0, 0.5, 0.5, 0);
shimizuta 32:dc684a0b8448 100
shimizuta 31:86eb746eaed4 101 //TURNLEFTのparam
shimizuta 32:dc684a0b8448 102 float stride_short_m = 0.05, stride_long_m = 0.25;
shimizuta 32:dc684a0b8448 103 stridetime_s = 0.3, toptime_s = 0.07, buffer_time_s = 0.03,
shimizuta 34:89d701e15cdf 104 offset_x_m = 0, offset_y_m = 0.2, height_m = 0.03, buffer_height_m = 0.01;
shimizuta 31:86eb746eaed4 105 walks[TURNLEFT].SetAllLegTriangleParam // 4足を取り敢えず一括で設定してから
shimizuta 32:dc684a0b8448 106 (offset_x_m, offset_y_m, stride_long_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s);
shimizuta 32:dc684a0b8448 107 walks[TURNLEFT].ChangeOneParam(LEFT_F, STRIDE_M, stride_short_m); //一部のパラメータを変更
shimizuta 32:dc684a0b8448 108 walks[TURNLEFT].ChangeOneParam(LEFT_B, STRIDE_M, stride_short_m);
shimizuta 31:86eb746eaed4 109 walks[TURNLEFT].SetOffsetTime(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1])
shimizuta 31:86eb746eaed4 110
shimizuta 31:86eb746eaed4 111 //TURNRIGHT1のparam
shimizuta 31:86eb746eaed4 112 walks[TURNRIGHT].SetAllLegTriangleParam // 4足を取り敢えず一括で設定してから
shimizuta 34:89d701e15cdf 113 (offset_x_m, offset_y_m, stride_long_m, height_m, buffer_height_m, stridetime_s, toptime_s, buffer_time_s);
shimizuta 32:dc684a0b8448 114 walks[TURNRIGHT].ChangeOneParam(RIGHT_F, STRIDE_M, stride_short_m); //一部のパラメータを変更
shimizuta 32:dc684a0b8448 115 walks[TURNRIGHT].ChangeOneParam(RIGHT_B, STRIDE_M, stride_short_m);
shimizuta 31:86eb746eaed4 116 walks[TURNRIGHT].SetOffsetTime(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1])
shimizuta 34:89d701e15cdf 117 */
shimizuta 31:86eb746eaed4 118 // UP, //足を伸ばして立つ
shimizuta 34:89d701e15cdf 119 walks[UP].SetAllLegStandParam(0, 0.30, 2); //x,y,time_s.一括で設定できる
shimizuta 34:89d701e15cdf 120 // walks[UP].SetOneLegStandParam(RIGHT_B, 0, 0.30, 2); //x,y,time_s
shimizuta 34:89d701e15cdf 121 // walks[UP].SetOneLegStandParam(RIGHT_F, 0, 0.30, 2); //x,y,time_s
shimizuta 34:89d701e15cdf 122 // walks[UP].SetOneLegStandParam(LEFT_B, 0, 0.30, 2); //x,y,time_s
shimizuta 34:89d701e15cdf 123 // walks[UP].SetOneLegStandParam(RIGHT_B, 0, 0.30, 2); //x,y,time_s
yuto17320508 18:0033ef1814ba 124 }
shimizuta 27:79b4b932a6dd 125 Walk walks[END]; //歩行法
shimizuta 9:905f93247688 126 int main()
yuto17320508 5:556d5a5e9d24 127 {
shimizuta 34:89d701e15cdf 128
shimizuta 34:89d701e15cdf 129 //足とシリアルサーボの番号
shimizuta 34:89d701e15cdf 130 // RIGHT_B, RIGHT_F, LEFT_B, LEFT_F,};
shimizuta 34:89d701e15cdf 131 //前足かける
shimizuta 34:89d701e15cdf 132 float start_x_m[4] = {-0, 0, -0, 0}; //足のoffset
shimizuta 34:89d701e15cdf 133 float start_y_m[4] = {.3, .3, .31, .3};
shimizuta 34:89d701e15cdf 134 float d_x_m = 0.15;
shimizuta 34:89d701e15cdf 135 float goal_y_m[4] = {.3, 0.2, .31, 0.2};
shimizuta 34:89d701e15cdf 136 float height_m[] = {0.03, 0.13, 0.03, 0.13};
shimizuta 34:89d701e15cdf 137 float gravity_dist[] = {0.075, 0, 0.075, 0};
shimizuta 34:89d701e15cdf 138 OverCome overcome(start_x_m, start_y_m, d_x_m, goal_y_m, height_m, gravity_dist);
shimizuta 34:89d701e15cdf 139 //そのまま進む
shimizuta 34:89d701e15cdf 140 float d_x_m2 = 0.075;
shimizuta 34:89d701e15cdf 141 float height1_m[] = {0.05, 0.05, 0.05, 0.05};
shimizuta 34:89d701e15cdf 142 OverCome overcome1(start_x_m, goal_y_m, d_x_m2, goal_y_m, height1_m, gravity_dist);
shimizuta 34:89d701e15cdf 143 //後ろ脚載せる
shimizuta 34:89d701e15cdf 144 float height2_m[] = {0.08, 0.08, 0.08, 0.08};
shimizuta 34:89d701e15cdf 145 float start2_y_m[] = {.25, .3, .25, .3};
shimizuta 34:89d701e15cdf 146 float goal2_y_m[] = {.2, .3, .2, .3};
shimizuta 34:89d701e15cdf 147 OverCome overcome2(start_x_m, start2_y_m, d_x_m2, goal2_y_m, height2_m, gravity_dist);
shimizuta 34:89d701e15cdf 148 //
shimizuta 34:89d701e15cdf 149 float height3_m[] = {0.05, 0.05, 0.05, 0.05};
shimizuta 34:89d701e15cdf 150 float start3_x_m[] = {0, 0, 0, 0.05};
shimizuta 34:89d701e15cdf 151 OverCome overcome3(start3_x_m, goal2_y_m, d_x_m2, goal2_y_m, height3_m, gravity_dist);
shimizuta 34:89d701e15cdf 152 //後ろ脚を落とす
shimizuta 34:89d701e15cdf 153 float d_x_m4 = 0.1;
shimizuta 34:89d701e15cdf 154 float goal4_y_m[] = {.3, .3, .3, .3};
shimizuta 34:89d701e15cdf 155 OverCome overcome4(start_x_m, goal2_y_m, d_x_m4, goal4_y_m, height3_m, gravity_dist);
shimizuta 34:89d701e15cdf 156 OverCome overcome5(start_x_m, goal4_y_m, d_x_m4, goal4_y_m, height3_m, gravity_dist);
shimizuta 34:89d701e15cdf 157
shimizuta 34:89d701e15cdf 158 /*ROPEを超えた
shimizuta 34:89d701e15cdf 159 //足とシリアルサーボの番号
shimizuta 34:89d701e15cdf 160 // RIGHT_B, RIGHT_F, LEFT_B, LEFT_F,};
shimizuta 34:89d701e15cdf 161 //上手く行った
shimizuta 34:89d701e15cdf 162 float start_x_m[4] = {-0, 0, -0, 0};
shimizuta 34:89d701e15cdf 163 float start_y_m[4] = {.3, .28, .3, .28};
shimizuta 34:89d701e15cdf 164 float d_x_m = 0.1;
shimizuta 34:89d701e15cdf 165 float goal_y_m[4] = {.3, .28, .3, .28};
shimizuta 34:89d701e15cdf 166 float height_m = 0.13;
shimizuta 34:89d701e15cdf 167 float gravity_dist[] = {0.075, -0.03, 0.105, 0};
shimizuta 34:89d701e15cdf 168 OverCome rope[] = {
shimizuta 34:89d701e15cdf 169 OverCome(start_x_m, start_y_m, d_x_m, goal_y_m, height_m, gravity_dist),
shimizuta 34:89d701e15cdf 170 };
shimizuta 34:89d701e15cdf 171 */
shimizuta 29:7d8b8011a88d 172 #ifdef VSCODE
shimizuta 27:79b4b932a6dd 173 if (FileOpen()) //csv fileに書き込み
shimizuta 27:79b4b932a6dd 174 return 1; //異常終了したら強制終了
shimizuta 29:7d8b8011a88d 175 #endif
shimizuta 34:89d701e15cdf 176 printf("param set start\r\n");
shimizuta 27:79b4b932a6dd 177 ParamsSetup(walks, leg); //各動きの際の足の軌道を設定。パラメータはこの関数内に打ち込む
shimizuta 27:79b4b932a6dd 178 for (int i = 0; i < END; i++) //軌道のチェック
shimizuta 27:79b4b932a6dd 179 {
shimizuta 27:79b4b932a6dd 180 if (walks[i].CheckOrbit(leg[0]) == 1) //軌道が定義外なら
shimizuta 29:7d8b8011a88d 181 {
shimizuta 32:dc684a0b8448 182 printf("error: move pattern %d\r\n", i);
shimizuta 29:7d8b8011a88d 183 return 1; //強制終了.errorは内部の関数からprintfで知らせる
shimizuta 29:7d8b8011a88d 184 }
shimizuta 27:79b4b932a6dd 185 }
shimizuta 34:89d701e15cdf 186 /*ROPEのチェック
shimizuta 34:89d701e15cdf 187 for (int i = 0; i < sizeof(rope) / sizeof(rope[0]); i++)
shimizuta 34:89d701e15cdf 188 {
shimizuta 34:89d701e15cdf 189 if (rope[i].walk.CheckOrbit(leg[0]) == 1) //軌道が定義外なら
shimizuta 34:89d701e15cdf 190 {
shimizuta 34:89d701e15cdf 191 printf("error: rope pattern %d\r\n", i);
shimizuta 34:89d701e15cdf 192 return 1; //強制終了.errorは内部の関数からprintfで知らせる
shimizuta 34:89d701e15cdf 193 }
shimizuta 34:89d701e15cdf 194 }
shimizuta 34:89d701e15cdf 195 */
shimizuta 34:89d701e15cdf 196 if (overcome.walk.CheckOrbit(leg[0]) == 1) //軌道が定義外なら
shimizuta 34:89d701e15cdf 197 {
shimizuta 34:89d701e15cdf 198 printf("error: move pattern overcome0\r\n");
shimizuta 34:89d701e15cdf 199 return 1; //強制終了.errorは内部の関数からprintfで知らせる
shimizuta 34:89d701e15cdf 200 }
shimizuta 34:89d701e15cdf 201 if (overcome1.walk.CheckOrbit(leg[0]) == 1) //軌道が定義外なら
shimizuta 34:89d701e15cdf 202 {
shimizuta 34:89d701e15cdf 203 printf("error: move pattern overcome1\r\n");
shimizuta 34:89d701e15cdf 204 return 1; //強制終了.errorは内部の関数からprintfで知らせる
shimizuta 34:89d701e15cdf 205 }
shimizuta 34:89d701e15cdf 206
shimizuta 34:89d701e15cdf 207 if (overcome2.walk.CheckOrbit(leg[0]) == 1) //軌道が定義外なら
shimizuta 34:89d701e15cdf 208 {
shimizuta 34:89d701e15cdf 209 printf("error: move pattern overcome 2\r\n");
shimizuta 34:89d701e15cdf 210 return 1; //強制終了.errorは内部の関数からprintfで知らせる
shimizuta 34:89d701e15cdf 211 }
shimizuta 34:89d701e15cdf 212 if (overcome3.walk.CheckOrbit(leg[0]) == 1) //軌道が定義外なら
shimizuta 34:89d701e15cdf 213 {
shimizuta 34:89d701e15cdf 214 printf("error: move pattern overcome 3\r\n");
shimizuta 34:89d701e15cdf 215 return 1; //強制終了.errorは内部の関数からprintfで知らせる
shimizuta 34:89d701e15cdf 216 }
shimizuta 34:89d701e15cdf 217
shimizuta 34:89d701e15cdf 218 if (overcome4.walk.CheckOrbit(leg[0]) == 1) //軌道が定義外なら
shimizuta 34:89d701e15cdf 219 {
shimizuta 34:89d701e15cdf 220 printf("error: move pattern overcome 4\r\n");
shimizuta 34:89d701e15cdf 221 return 1; //強制終了.errorは内部の関数からprintfで知らせる
shimizuta 34:89d701e15cdf 222 }
shimizuta 34:89d701e15cdf 223
shimizuta 34:89d701e15cdf 224 if (overcome5.walk.CheckOrbit(leg[0]) == 1) //軌道が定義外なら
shimizuta 34:89d701e15cdf 225 {
shimizuta 34:89d701e15cdf 226 printf("error: move pattern overcome 5\r\n");
shimizuta 34:89d701e15cdf 227 return 1; //強制終了.errorは内部の関数からprintfで知らせる
shimizuta 34:89d701e15cdf 228 }
shimizuta 29:7d8b8011a88d 229 printf("Stand up?\r\n");
shimizuta 27:79b4b932a6dd 230 WaitStdin('y'); // ボタンを押したら立つ
shimizuta 27:79b4b932a6dd 231 MoveOneCycle(walks[STANDUP], leg);
shimizuta 29:7d8b8011a88d 232 printf("Move?\r\n");
shimizuta 27:79b4b932a6dd 233 WaitStdin('y'); // ボタンを押したらスタート
shimizuta 27:79b4b932a6dd 234 #ifdef USE_ROS
shimizuta 27:79b4b932a6dd 235 nh_mbed.getHardware()->setBaud(115200);
shimizuta 27:79b4b932a6dd 236 nh_mbed.initNode();
shimizuta 27:79b4b932a6dd 237 nh_mbed.subscribe(sub_vel);
shimizuta 27:79b4b932a6dd 238 while (1)
shimizuta 27:79b4b932a6dd 239 nh_mbed.spinOnce();
shimizuta 27:79b4b932a6dd 240 #else
shimizuta 34:89d701e15cdf 241
shimizuta 34:89d701e15cdf 242 // for (int k = 0; k < 5; k++)//壁あて.機体保護のため抜いておく
shimizuta 34:89d701e15cdf 243 // MoveOneCycle(walks[STRAIGHT], leg);
shimizuta 34:89d701e15cdf 244 MoveOneCycle(walks[UP], leg); //立つ
shimizuta 34:89d701e15cdf 245 for (int k = 0; k < 1; k++) //前足かける
shimizuta 34:89d701e15cdf 246 MoveOneCycle(overcome.walk, leg);
shimizuta 34:89d701e15cdf 247 for (int k = 0; k < 5; k++) //そのまま進む
shimizuta 34:89d701e15cdf 248 MoveOneCycle(overcome1.walk, leg);
shimizuta 34:89d701e15cdf 249 for (int k = 0; k < 1; k++) //後ろ足載せる
shimizuta 34:89d701e15cdf 250 MoveOneCycle(overcome2.walk, leg);
shimizuta 34:89d701e15cdf 251 for (int k = 0; k < 3; k++) //そのまま進む
shimizuta 34:89d701e15cdf 252 MoveOneCycle(overcome3.walk, leg);
shimizuta 34:89d701e15cdf 253 for (int k = 0; k < 1; k++) //後ろ足を落とす
shimizuta 34:89d701e15cdf 254 MoveOneCycle(overcome4.walk, leg);
shimizuta 34:89d701e15cdf 255 for (int k = 0; k < 5; k++) //足上げたまま動く
shimizuta 34:89d701e15cdf 256 MoveOneCycle(overcome5.walk, leg);
shimizuta 34:89d701e15cdf 257 /*rope用
shimizuta 34:89d701e15cdf 258 for (int k = 0; k < 10; k++) //前足かける
shimizuta 34:89d701e15cdf 259 MoveOneCycle(rope[0].walk, leg);
shimizuta 34:89d701e15cdf 260 */
shimizuta 34:89d701e15cdf 261 printf("program end\r\n");
shimizuta 29:7d8b8011a88d 262 #ifdef VSCODE
shimizuta 27:79b4b932a6dd 263 fclose(fp);
shimizuta 27:79b4b932a6dd 264 #endif
shimizuta 29:7d8b8011a88d 265 #endif
shimizuta 2:a92568bdeb5c 266 }
shimizuta 32:dc684a0b8448 267 //一サイクル分進む.return 1:異常終了
shimizuta 32:dc684a0b8448 268 int MoveOneCycle(Walk walkway, OneLeg leg[4])
yuto17320508 5:556d5a5e9d24 269 {
shimizuta 27:79b4b932a6dd 270 #ifndef VSCODE
shimizuta 9:905f93247688 271 timer.reset();
shimizuta 9:905f93247688 272 timer.start();
shimizuta 27:79b4b932a6dd 273 #endif
shimizuta 27:79b4b932a6dd 274 int count = walkway.GetOneWalkTime() / walkway.calctime_s_;
shimizuta 27:79b4b932a6dd 275 for (int i = 0; i < count; i++)
yuto17320508 8:21b932c4e6c5 276 {
shimizuta 27:79b4b932a6dd 277 #ifndef VSCODE
shimizuta 9:905f93247688 278 float time_s = timer.read();
shimizuta 27:79b4b932a6dd 279 #endif
shimizuta 29:7d8b8011a88d 280 //4本の足それぞれの足先サーボ角度更新
shimizuta 29:7d8b8011a88d 281 if (walkway.Cal4LegsPosi(leg) == 1)
shimizuta 32:dc684a0b8448 282 {
shimizuta 29:7d8b8011a88d 283 printf("error: time = %f\r\n", i * walkway.calctime_s_);
shimizuta 32:dc684a0b8448 284 return 1;
shimizuta 32:dc684a0b8448 285 }
shimizuta 19:1adc7302cfd9 286 #ifdef USE_CAN
shimizuta 27:79b4b932a6dd 287 SendRad(leg[2], leg[3]); //slave_mbed分の足の目標位置を送信
shimizuta 19:1adc7302cfd9 288 #endif
shimizuta 9:905f93247688 289 //自身が動かす足のサーボを動かす
shimizuta 16:0069a56f11a3 290 MoveServo(leg[0], 0, 0);
shimizuta 11:e81425872740 291 MoveServo(leg[1], 1, 0);
shimizuta 27:79b4b932a6dd 292 #ifndef VSCODE
shimizuta 9:905f93247688 293 wait_ms(kServoSpan_ms);
shimizuta 27:79b4b932a6dd 294 #endif
shimizuta 16:0069a56f11a3 295 MoveServo(leg[0], 0, 1);
shimizuta 11:e81425872740 296 MoveServo(leg[1], 1, 1);
shimizuta 29:7d8b8011a88d 297 #ifdef VSCODE
shimizuta 27:79b4b932a6dd 298 //ファイルに書き込み。time[s],x[0],y[0],x[1],y[1],x[2],y[2],x[3],y[3]の順
shimizuta 27:79b4b932a6dd 299 fprintf(fp, "%f", i * walkway.calctime_s_);
shimizuta 27:79b4b932a6dd 300 for (int i = 0; i < 4; i++)
shimizuta 27:79b4b932a6dd 301 fprintf(fp, ",%f,%f", leg[i].GetX_m(), leg[i].GetY_m());
shimizuta 27:79b4b932a6dd 302 fprintf(fp, "\r\n");
shimizuta 29:7d8b8011a88d 303 #else
shimizuta 27:79b4b932a6dd 304 //計算周期がwalkway.calctime_s_になるようwait
shimizuta 27:79b4b932a6dd 305 float rest_time_s = walkway.calctime_s_ - (timer.read() - time_s);
shimizuta 9:905f93247688 306 if (rest_time_s > 0)
shimizuta 9:905f93247688 307 wait(rest_time_s);
shimizuta 19:1adc7302cfd9 308 else
shimizuta 19:1adc7302cfd9 309 { //計算周期が達成できないときはDEBUGで知らせるだけ。動きはする。
shimizuta 19:1adc7302cfd9 310 DEBUG("error: rest_time_s = %f in Move()\r\n", rest_time_s);
shimizuta 14:d7cb429946f4 311 led[0] = 1;
shimizuta 14:d7cb429946f4 312 }
shimizuta 27:79b4b932a6dd 313 #endif
shimizuta 9:905f93247688 314 }
shimizuta 32:dc684a0b8448 315 return 0;
yuto17320508 5:556d5a5e9d24 316 }
shimizuta 14:d7cb429946f4 317 void MoveServo(OneLeg leg, int serial_num, int servo_id)
yuto17320508 6:43708adf2e5d 318 {
shimizuta 27:79b4b932a6dd 319 #ifndef VSCODE
shimizuta 11:e81425872740 320 float degree = leg.GetRad(servo_id) * kRadToDegree;
shimizuta 14:d7cb429946f4 321 //サーボの座標系に変更
shimizuta 14:d7cb429946f4 322 float servo_degree = kServoSign[serial_num][servo_id] * degree + kOriginDegree[serial_num][servo_id];
shimizuta 27:79b4b932a6dd 323 // DEBUG("servo_degree[%d][%d],%f\r\n", serial_num, servo_id, servo_degree);
shimizuta 14:d7cb429946f4 324 servo[serial_num].set_degree(servo_id, servo_degree);
shimizuta 27:79b4b932a6dd 325 #endif
shimizuta 12:2ac37fe6c3bb 326 }
shimizuta 27:79b4b932a6dd 327 void WaitStdin(char startchar)
shimizuta 27:79b4b932a6dd 328 {
shimizuta 27:79b4b932a6dd 329 #ifndef USE_ROS
shimizuta 27:79b4b932a6dd 330 char str[255] = {};
shimizuta 27:79b4b932a6dd 331 do
shimizuta 27:79b4b932a6dd 332 {
shimizuta 27:79b4b932a6dd 333 printf("put '%c', then start\r\n", startchar);
shimizuta 27:79b4b932a6dd 334 scanf("%s", str);
shimizuta 27:79b4b932a6dd 335 } while (str[0] != startchar);
shimizuta 27:79b4b932a6dd 336 #endif
shimizuta 27:79b4b932a6dd 337 }
shimizuta 27:79b4b932a6dd 338 int FileOpen() //1:異常終了
shimizuta 27:79b4b932a6dd 339 {
shimizuta 27:79b4b932a6dd 340 if ((fp = fopen("data.csv", "w")) == NULL)
shimizuta 27:79b4b932a6dd 341 {
shimizuta 27:79b4b932a6dd 342 printf("error : FileSave()\r\n");
shimizuta 27:79b4b932a6dd 343 return 1;
shimizuta 27:79b4b932a6dd 344 }
shimizuta 27:79b4b932a6dd 345 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 346 return 0;
shimizuta 27:79b4b932a6dd 347 }
shimizuta 27:79b4b932a6dd 348 #ifdef USE_ROS
shimizuta 27:79b4b932a6dd 349 void callback(const geometry_msgs::Vector3 &cmd_vel)
shimizuta 27:79b4b932a6dd 350 {
shimizuta 27:79b4b932a6dd 351 float left_vel = cmd_vel.x;
shimizuta 27:79b4b932a6dd 352 float right_vel = cmd_vel.y;
shimizuta 34:89d701e15cdf 353 int state = cmd_vel.z;
shimizuta 27:79b4b932a6dd 354 //閾値は要検討
shimizuta 27:79b4b932a6dd 355 if (right_vel < left_vel)
shimizuta 27:79b4b932a6dd 356 MoveOneCycle(walks[TURNRIGHT], leg);
shimizuta 27:79b4b932a6dd 357 else if (left_vel < right_vel)
shimizuta 27:79b4b932a6dd 358 MoveOneCycle(walks[TURNLEFT], leg);
shimizuta 27:79b4b932a6dd 359 else
shimizuta 27:79b4b932a6dd 360 MoveOneCycle(walks[STRAIGHT], leg);
shimizuta 27:79b4b932a6dd 361 }
shimizuta 27:79b4b932a6dd 362 #endif
shimizuta 34:89d701e15cdf 363 /*
shimizuta 29:7d8b8011a88d 364 //param back_height_on_step:段差の高さ。後ろにあるとする。前にあるときはマイナスを入れる
shimizuta 29:7d8b8011a88d 365 float GetSteepBodyRad(float back_height_on_step)
shimizuta 29:7d8b8011a88d 366 {
shimizuta 29:7d8b8011a88d 367 float offset_hight = back_height_on_step + leg[LEFT_B].GetY_m() - leg[LEFT_B].GetY_m();
shimizuta 29:7d8b8011a88d 368 float theta = atan2(offset_hight, (float)(sqrt(0.09 - offset_hight * offset_hight)));
shimizuta 29:7d8b8011a88d 369 return theta;
shimizuta 34:89d701e15cdf 370 }
shimizuta 34:89d701e15cdf 371 */