test

Dependencies:   mbed ros_lib_kinetic nhk19mr2_can_info splitData SerialHalfDuplex_HM

Committer:
shimizuta
Date:
Mon Mar 04 10:02:45 2019 +0000
Revision:
37:e4b37af4d8c7
Parent:
36:b0edccff7457
Child:
38:e664b1c12da9
for ROS

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 #include <math.h>
shimizuta 27:79b4b932a6dd 5 #include <stdio.h>
shimizuta 27:79b4b932a6dd 6 #else
yuto17320508 0:f000d896d188 7 #include "mbed.h"
shimizuta 9:905f93247688 8 #include "pinnames.h"
shimizuta 11:e81425872740 9 #include "KondoServo.h"
shimizuta 14:d7cb429946f4 10 #include "pi.h"
shimizuta 16:0069a56f11a3 11 #include "can.h"
shimizuta 27:79b4b932a6dd 12 #define USE_CAN //can通信するならdefine.しないなら切らないとエラー出る
shimizuta 36:b0edccff7457 13 #define USE_ROS
shimizuta 34:89d701e15cdf 14 #include <ros.h>
shimizuta 34:89d701e15cdf 15 #include <geometry_msgs/Vector3.h>
shimizuta 27:79b4b932a6dd 16 #endif
shimizuta 27:79b4b932a6dd 17 //#define DEBUG_ON //デバッグ用。使わないときはコメントアウト
shimizuta 27:79b4b932a6dd 18 #include "debug.h"
shimizuta 11:e81425872740 19 #include "OneLeg.h" ///足先の座標を保存するクラス。x,yやサーボの角度の保存、サーボの駆動も行う。他の足を考慮した処理は別のクラスに任せる。
shimizuta 11:e81425872740 20 #include "Walk.h" //歩き方に関するファイル
shimizuta 35:b4e1b8f25cd7 21 #include "OverCome.h"
shimizuta 35:b4e1b8f25cd7 22 #include "change_walk.h"
shimizuta 27:79b4b932a6dd 23 ////////////あまり変化させないパラメータ。この他は全てmainの上(ParamSetup())にある。
shimizuta 35:b4e1b8f25cd7 24 const int kServoSpan_ms = 6; //サーボの送信間隔
shimizuta 35:b4e1b8f25cd7 25 const float kBetweenServoHalf_m = 0.034 * 0.5; //サーボ間の距離の半分
shimizuta 35:b4e1b8f25cd7 26 float kLegLength1[2] = {0.15, 0.15};
shimizuta 35:b4e1b8f25cd7 27 float kLegLength2[2] = {0.33, 0.34};
shimizuta 14:d7cb429946f4 28 //サーボの正負と座標系の正負の補正.足で一セット。
shimizuta 35:b4e1b8f25cd7 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 35:b4e1b8f25cd7 34 (7300 - 3500) * kServoValToDegree,
shimizuta 35:b4e1b8f25cd7 35 (6995 - 3500) * kServoValToDegree + 180,
shimizuta 14:d7cb429946f4 36 },
shimizuta 14:d7cb429946f4 37 {
shimizuta 35:b4e1b8f25cd7 38 (7619 - 3500) * kServoValToDegree,
shimizuta 35:b4e1b8f25cd7 39 (7085 - 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 34:89d701e15cdf 59
shimizuta 27:79b4b932a6dd 60 FILE *fp;
shimizuta 11:e81425872740 61 const float kRadToDegree = 180.0 / M_PI;
shimizuta 32:dc684a0b8448 62 int MoveOneCycle(Walk walkway, OneLeg leg[4]);
shimizuta 11:e81425872740 63 void MoveServo(OneLeg leg, int legnum, int servo_id);
shimizuta 27:79b4b932a6dd 64 void WaitStdin(char startchar);
shimizuta 27:79b4b932a6dd 65 int FileOpen();
shimizuta 27:79b4b932a6dd 66 ////////調整するべきパラメータ
shimizuta 27:79b4b932a6dd 67 enum WalkWay
shimizuta 27:79b4b932a6dd 68 {
shimizuta 27:79b4b932a6dd 69 STANDUP,
shimizuta 35:b4e1b8f25cd7 70 LRFPOSTURE,
shimizuta 35:b4e1b8f25cd7 71 FRONTLEG_ON_SANDDUNE, //前足かける
shimizuta 27:79b4b932a6dd 72 };
shimizuta 32:dc684a0b8448 73
shimizuta 35:b4e1b8f25cd7 74 float offset_x_m[4] = {-0.1, 0.1, -0.1, 0.1},
shimizuta 35:b4e1b8f25cd7 75 offset_y_m[4] = {0.35, 0.35, 0.35, 0.35};
shimizuta 35:b4e1b8f25cd7 76 //strideはLRFから変更するようにする
shimizuta 35:b4e1b8f25cd7 77 float stride_m[4] = {0.2, 0.2, 0.2, 0.2},
shimizuta 35:b4e1b8f25cd7 78 height_m[4] = {0.1, 0.1, 0.1, 0.1}, buffer_height_m = 0.05,
shimizuta 35:b4e1b8f25cd7 79 stridetime_s = 1, toptime_s = 0.4, buffer_time_s = 0.2;
shimizuta 35:b4e1b8f25cd7 80 /*
shimizuta 35:b4e1b8f25cd7 81 LineParam over_come_front[]{
shimizuta 35:b4e1b8f25cd7 82 {.time_s = 0, .x_m = -0.075, .y_m = 0.41},
shimizuta 35:b4e1b8f25cd7 83 {.time_s = 0.2, .x_m = -0.175, .y_m = 0.26},
shimizuta 35:b4e1b8f25cd7 84 {.time_s = 0.4, .x_m = 0.075, .y_m = 0.26},
shimizuta 35:b4e1b8f25cd7 85 {.time_s = 0.6, .x_m = 0.075, .y_m = 0.41},
shimizuta 35:b4e1b8f25cd7 86 {.time_s = 1.6, .x_m = -0.075, .y_m = 0.41},
shimizuta 35:b4e1b8f25cd7 87 };
shimizuta 35:b4e1b8f25cd7 88 */
shimizuta 35:b4e1b8f25cd7 89 float d_x_m = 0.1;
shimizuta 35:b4e1b8f25cd7 90 float start_y_m[4] = {0.41, 0.41, 0.41, 0.41};
shimizuta 35:b4e1b8f25cd7 91 float goal_y_m[4] = {0.41, 0.29, 0.41, 0.29};
shimizuta 35:b4e1b8f25cd7 92 float overcome_height_m[] = {0.1, 0.2, 0.1, 0.2};
shimizuta 35:b4e1b8f25cd7 93 float gravity_dist[] = {0.01, -0.01, 0.01, -0.01};
shimizuta 35:b4e1b8f25cd7 94 int SetWalk(Walk &walk, WalkWay way)
shimizuta 35:b4e1b8f25cd7 95 {
shimizuta 35:b4e1b8f25cd7 96 switch (way)
shimizuta 35:b4e1b8f25cd7 97 {
shimizuta 35:b4e1b8f25cd7 98 case STANDUP:
shimizuta 35:b4e1b8f25cd7 99 for (int i = 0; i < 4; i++)
shimizuta 35:b4e1b8f25cd7 100 SetOneLegStandParam(walk, i, offset_x_m[i], offset_y_m[i], 0.5);
shimizuta 35:b4e1b8f25cd7 101 break;
shimizuta 35:b4e1b8f25cd7 102 case LRFPOSTURE:
shimizuta 35:b4e1b8f25cd7 103 for (int i = 0; i < 4; i++)
shimizuta 35:b4e1b8f25cd7 104 SetOneLegTriangleParam(walk, i, offset_x_m[i], offset_y_m[i],
shimizuta 35:b4e1b8f25cd7 105 stride_m[i], height_m[i], buffer_height_m,
shimizuta 35:b4e1b8f25cd7 106 stridetime_s, toptime_s, buffer_time_s);
shimizuta 35:b4e1b8f25cd7 107 walk.SetOffsetTime(0, 0.5, 0.5, 0);
shimizuta 35:b4e1b8f25cd7 108 break;
shimizuta 31:86eb746eaed4 109
shimizuta 35:b4e1b8f25cd7 110 case FRONTLEG_ON_SANDDUNE: //前足かける
shimizuta 35:b4e1b8f25cd7 111 // for(int q = 0; q < 4; q++)
shimizuta 35:b4e1b8f25cd7 112 // SetOneLegFreeLinesParam(walk, q, over_come_front, sizeof(over_come_front) / sizeof(over_come_front[0]));
shimizuta 35:b4e1b8f25cd7 113 // walk.SetOffsetTime(0, 0.5, 0.5, 0);
shimizuta 35:b4e1b8f25cd7 114
shimizuta 35:b4e1b8f25cd7 115 OverCome overcome(offset_x_m, start_y_m, d_x_m, goal_y_m, overcome_height_m, gravity_dist, walk.leg);
shimizuta 35:b4e1b8f25cd7 116 walk.Copy(overcome.walk);
shimizuta 35:b4e1b8f25cd7 117 break;
shimizuta 35:b4e1b8f25cd7 118 }
shimizuta 35:b4e1b8f25cd7 119 return walk.CheckOrbit();
yuto17320508 18:0033ef1814ba 120 }
shimizuta 35:b4e1b8f25cd7 121
shimizuta 9:905f93247688 122 int main()
yuto17320508 5:556d5a5e9d24 123 {
shimizuta 29:7d8b8011a88d 124 #ifdef VSCODE
shimizuta 27:79b4b932a6dd 125 if (FileOpen()) //csv fileに書き込み
shimizuta 27:79b4b932a6dd 126 return 1; //異常終了したら強制終了
shimizuta 29:7d8b8011a88d 127 #endif
shimizuta 35:b4e1b8f25cd7 128 OneLeg leg[4]; //各足の位置
shimizuta 35:b4e1b8f25cd7 129 for (int i = 0; i < 4; i++)
shimizuta 35:b4e1b8f25cd7 130 leg[i] = OneLeg(kBetweenServoHalf_m, kLegLength1, kLegLength2);
shimizuta 35:b4e1b8f25cd7 131 Walk walk(leg); //歩行法はここに入れていく
shimizuta 35:b4e1b8f25cd7 132 Walk::calctime_s_ = 0.03;
shimizuta 35:b4e1b8f25cd7 133 printf("Stand up?\r\n");
shimizuta 35:b4e1b8f25cd7 134 WaitStdin('y'); // ボタンを押したら立つ
shimizuta 35:b4e1b8f25cd7 135 if (SetWalk(walk, STANDUP) == 1)
shimizuta 27:79b4b932a6dd 136 {
shimizuta 35:b4e1b8f25cd7 137 printf("error: stand move\r\n");
shimizuta 34:89d701e15cdf 138 return 1; //強制終了.errorは内部の関数からprintfで知らせる
shimizuta 34:89d701e15cdf 139 }
shimizuta 35:b4e1b8f25cd7 140 if (MoveOneCycle(walk, leg) == 1)
shimizuta 34:89d701e15cdf 141 {
shimizuta 35:b4e1b8f25cd7 142 printf("error: stand move\r\n");
shimizuta 34:89d701e15cdf 143 return 1; //強制終了.errorは内部の関数からprintfで知らせる
shimizuta 34:89d701e15cdf 144 }
shimizuta 29:7d8b8011a88d 145 printf("Move?\r\n");
shimizuta 27:79b4b932a6dd 146 WaitStdin('y'); // ボタンを押したらスタート
shimizuta 27:79b4b932a6dd 147 #ifdef USE_ROS
shimizuta 27:79b4b932a6dd 148 nh_mbed.getHardware()->setBaud(115200);
shimizuta 27:79b4b932a6dd 149 nh_mbed.initNode();
shimizuta 27:79b4b932a6dd 150 nh_mbed.subscribe(sub_vel);
shimizuta 36:b0edccff7457 151 while (1){
shimizuta 27:79b4b932a6dd 152 nh_mbed.spinOnce();
shimizuta 36:b0edccff7457 153 SetWalk(walk, LRFPOSTURE);
shimizuta 36:b0edccff7457 154 MoveOneCycle(walk, leg);
shimizuta 36:b0edccff7457 155 }
shimizuta 27:79b4b932a6dd 156 #else
shimizuta 34:89d701e15cdf 157
shimizuta 35:b4e1b8f25cd7 158 if (SetWalk(walk, FRONTLEG_ON_SANDDUNE) == 1)
shimizuta 35:b4e1b8f25cd7 159 {
shimizuta 35:b4e1b8f25cd7 160 printf("error: triangle\r\n");
shimizuta 35:b4e1b8f25cd7 161 return 1; //強制終了.errorは内部の関数からprintfで知らせる
shimizuta 35:b4e1b8f25cd7 162 }
shimizuta 35:b4e1b8f25cd7 163
shimizuta 35:b4e1b8f25cd7 164 for (int i = 0; i < 2; i++)
shimizuta 35:b4e1b8f25cd7 165 {
shimizuta 35:b4e1b8f25cd7 166 if (MoveOneCycle(walk, leg) == 1)
shimizuta 35:b4e1b8f25cd7 167 {
shimizuta 35:b4e1b8f25cd7 168 printf("error: triangle move\r\n");
shimizuta 35:b4e1b8f25cd7 169 return 1; //強制終了.errorは内部の関数からprintfで知らせる
shimizuta 35:b4e1b8f25cd7 170 }
shimizuta 35:b4e1b8f25cd7 171 }
shimizuta 35:b4e1b8f25cd7 172 offset_y_m[LEFT_F] = 0.29;
shimizuta 35:b4e1b8f25cd7 173 offset_y_m[RIGHT_F] = 0.29;
shimizuta 35:b4e1b8f25cd7 174 if (SetWalk(walk, LRFPOSTURE) == 1)
shimizuta 35:b4e1b8f25cd7 175 {
shimizuta 35:b4e1b8f25cd7 176 printf("error: triangle\r\n");
shimizuta 35:b4e1b8f25cd7 177 return 1; //強制終了.errorは内部の関数からprintfで知らせる
shimizuta 35:b4e1b8f25cd7 178 }
shimizuta 35:b4e1b8f25cd7 179
shimizuta 35:b4e1b8f25cd7 180 for (int i = 0; i < 20; i++)
shimizuta 35:b4e1b8f25cd7 181 {
shimizuta 35:b4e1b8f25cd7 182 if (MoveOneCycle(walk, leg) == 1)
shimizuta 35:b4e1b8f25cd7 183 {
shimizuta 35:b4e1b8f25cd7 184 printf("error: triangle move\r\n");
shimizuta 35:b4e1b8f25cd7 185 return 1; //強制終了.errorは内部の関数からprintfで知らせる
shimizuta 35:b4e1b8f25cd7 186 }
shimizuta 35:b4e1b8f25cd7 187 }
shimizuta 35:b4e1b8f25cd7 188
shimizuta 34:89d701e15cdf 189 printf("program end\r\n");
shimizuta 29:7d8b8011a88d 190 #ifdef VSCODE
shimizuta 27:79b4b932a6dd 191 fclose(fp);
shimizuta 27:79b4b932a6dd 192 #endif
shimizuta 29:7d8b8011a88d 193 #endif
shimizuta 2:a92568bdeb5c 194 }
shimizuta 32:dc684a0b8448 195 //一サイクル分進む.return 1:異常終了
shimizuta 32:dc684a0b8448 196 int MoveOneCycle(Walk walkway, OneLeg leg[4])
yuto17320508 5:556d5a5e9d24 197 {
shimizuta 27:79b4b932a6dd 198 #ifndef VSCODE
shimizuta 9:905f93247688 199 timer.reset();
shimizuta 9:905f93247688 200 timer.start();
shimizuta 27:79b4b932a6dd 201 #endif
shimizuta 35:b4e1b8f25cd7 202 int count = walkway.orbit[0].GetOneWalkTime() / walkway.calctime_s_;
shimizuta 27:79b4b932a6dd 203 for (int i = 0; i < count; i++)
yuto17320508 8:21b932c4e6c5 204 {
shimizuta 27:79b4b932a6dd 205 #ifndef VSCODE
shimizuta 9:905f93247688 206 float time_s = timer.read();
shimizuta 27:79b4b932a6dd 207 #endif
shimizuta 29:7d8b8011a88d 208 //4本の足それぞれの足先サーボ角度更新
shimizuta 29:7d8b8011a88d 209 if (walkway.Cal4LegsPosi(leg) == 1)
shimizuta 32:dc684a0b8448 210 {
shimizuta 29:7d8b8011a88d 211 printf("error: time = %f\r\n", i * walkway.calctime_s_);
shimizuta 32:dc684a0b8448 212 return 1;
shimizuta 32:dc684a0b8448 213 }
shimizuta 19:1adc7302cfd9 214 #ifdef USE_CAN
shimizuta 27:79b4b932a6dd 215 SendRad(leg[2], leg[3]); //slave_mbed分の足の目標位置を送信
shimizuta 19:1adc7302cfd9 216 #endif
shimizuta 9:905f93247688 217 //自身が動かす足のサーボを動かす
shimizuta 16:0069a56f11a3 218 MoveServo(leg[0], 0, 0);
shimizuta 11:e81425872740 219 MoveServo(leg[1], 1, 0);
shimizuta 27:79b4b932a6dd 220 #ifndef VSCODE
shimizuta 9:905f93247688 221 wait_ms(kServoSpan_ms);
shimizuta 27:79b4b932a6dd 222 #endif
shimizuta 16:0069a56f11a3 223 MoveServo(leg[0], 0, 1);
shimizuta 11:e81425872740 224 MoveServo(leg[1], 1, 1);
shimizuta 29:7d8b8011a88d 225 #ifdef VSCODE
shimizuta 27:79b4b932a6dd 226 //ファイルに書き込み。time[s],x[0],y[0],x[1],y[1],x[2],y[2],x[3],y[3]の順
shimizuta 27:79b4b932a6dd 227 fprintf(fp, "%f", i * walkway.calctime_s_);
shimizuta 27:79b4b932a6dd 228 for (int i = 0; i < 4; i++)
shimizuta 27:79b4b932a6dd 229 fprintf(fp, ",%f,%f", leg[i].GetX_m(), leg[i].GetY_m());
shimizuta 27:79b4b932a6dd 230 fprintf(fp, "\r\n");
shimizuta 29:7d8b8011a88d 231 #else
shimizuta 27:79b4b932a6dd 232 //計算周期がwalkway.calctime_s_になるようwait
shimizuta 27:79b4b932a6dd 233 float rest_time_s = walkway.calctime_s_ - (timer.read() - time_s);
shimizuta 9:905f93247688 234 if (rest_time_s > 0)
shimizuta 9:905f93247688 235 wait(rest_time_s);
shimizuta 19:1adc7302cfd9 236 else
shimizuta 19:1adc7302cfd9 237 { //計算周期が達成できないときはDEBUGで知らせるだけ。動きはする。
shimizuta 19:1adc7302cfd9 238 DEBUG("error: rest_time_s = %f in Move()\r\n", rest_time_s);
shimizuta 14:d7cb429946f4 239 led[0] = 1;
shimizuta 14:d7cb429946f4 240 }
shimizuta 27:79b4b932a6dd 241 #endif
shimizuta 9:905f93247688 242 }
shimizuta 32:dc684a0b8448 243 return 0;
yuto17320508 5:556d5a5e9d24 244 }
shimizuta 14:d7cb429946f4 245 void MoveServo(OneLeg leg, int serial_num, int servo_id)
yuto17320508 6:43708adf2e5d 246 {
shimizuta 27:79b4b932a6dd 247 #ifndef VSCODE
shimizuta 11:e81425872740 248 float degree = leg.GetRad(servo_id) * kRadToDegree;
shimizuta 14:d7cb429946f4 249 //サーボの座標系に変更
shimizuta 14:d7cb429946f4 250 float servo_degree = kServoSign[serial_num][servo_id] * degree + kOriginDegree[serial_num][servo_id];
shimizuta 27:79b4b932a6dd 251 // DEBUG("servo_degree[%d][%d],%f\r\n", serial_num, servo_id, servo_degree);
shimizuta 14:d7cb429946f4 252 servo[serial_num].set_degree(servo_id, servo_degree);
shimizuta 27:79b4b932a6dd 253 #endif
shimizuta 12:2ac37fe6c3bb 254 }
shimizuta 27:79b4b932a6dd 255 void WaitStdin(char startchar)
shimizuta 27:79b4b932a6dd 256 {
shimizuta 27:79b4b932a6dd 257 #ifndef USE_ROS
shimizuta 27:79b4b932a6dd 258 char str[255] = {};
shimizuta 27:79b4b932a6dd 259 do
shimizuta 27:79b4b932a6dd 260 {
shimizuta 27:79b4b932a6dd 261 printf("put '%c', then start\r\n", startchar);
shimizuta 27:79b4b932a6dd 262 scanf("%s", str);
shimizuta 27:79b4b932a6dd 263 } while (str[0] != startchar);
shimizuta 27:79b4b932a6dd 264 #endif
shimizuta 27:79b4b932a6dd 265 }
shimizuta 27:79b4b932a6dd 266 int FileOpen() //1:異常終了
shimizuta 27:79b4b932a6dd 267 {
shimizuta 27:79b4b932a6dd 268 if ((fp = fopen("data.csv", "w")) == NULL)
shimizuta 27:79b4b932a6dd 269 {
shimizuta 27:79b4b932a6dd 270 printf("error : FileSave()\r\n");
shimizuta 27:79b4b932a6dd 271 return 1;
shimizuta 27:79b4b932a6dd 272 }
shimizuta 27:79b4b932a6dd 273 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 274 return 0;
shimizuta 27:79b4b932a6dd 275 }
shimizuta 27:79b4b932a6dd 276 #ifdef USE_ROS
shimizuta 27:79b4b932a6dd 277 void callback(const geometry_msgs::Vector3 &cmd_vel)
shimizuta 27:79b4b932a6dd 278 {
shimizuta 27:79b4b932a6dd 279 float left_vel = cmd_vel.x;
shimizuta 27:79b4b932a6dd 280 float right_vel = cmd_vel.y;
shimizuta 34:89d701e15cdf 281 int state = cmd_vel.z;
shimizuta 27:79b4b932a6dd 282 //閾値は要検討
shimizuta 27:79b4b932a6dd 283 if (right_vel < left_vel)
shimizuta 35:b4e1b8f25cd7 284 {
shimizuta 35:b4e1b8f25cd7 285 stride_m[LEFT_F] = 0.2;
shimizuta 35:b4e1b8f25cd7 286 stride_m[RIGHT_F] = 0.2;
shimizuta 35:b4e1b8f25cd7 287 stride_m[LEFT_B] = 0.1;
shimizuta 35:b4e1b8f25cd7 288 stride_m[RIGHT_B] = 0.1;
shimizuta 35:b4e1b8f25cd7 289 }
shimizuta 27:79b4b932a6dd 290 else
shimizuta 35:b4e1b8f25cd7 291 {
shimizuta 35:b4e1b8f25cd7 292 stride_m[LEFT_F] = 0.1;
shimizuta 35:b4e1b8f25cd7 293 stride_m[RIGHT_F] = 0.1;
shimizuta 35:b4e1b8f25cd7 294 stride_m[LEFT_B] = 0.2;
shimizuta 35:b4e1b8f25cd7 295 stride_m[RIGHT_B] = 0.2;
shimizuta 35:b4e1b8f25cd7 296 }
shimizuta 36:b0edccff7457 297
shimizuta 27:79b4b932a6dd 298 }
shimizuta 35:b4e1b8f25cd7 299 #endif