test
Dependencies: mbed ros_lib_kinetic nhk19mr2_can_info splitData SerialHalfDuplex_HM
main.cpp@28:8e1cbeffe6c2, 2019-02-27 (annotated)
- Committer:
- shimizuta
- Date:
- Wed Feb 27 01:25:01 2019 +0000
- Revision:
- 28:8e1cbeffe6c2
- Parent:
- 27:79b4b932a6dd
- Child:
- 29:7d8b8011a88d
- Child:
- 30:32785b3c19f8
straight, turnl,r was ok. ROS program was written but not debug
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 | 27:79b4b932a6dd | 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 | 19:1adc7302cfd9 | 27 | float kLegLength2[2] = {0.2452 + 0.0025, 0.22529 + 0.0025}; |
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 | 27:79b4b932a6dd | 34 | (8338 - 3500) * kServoValToDegree, |
shimizuta | 27:79b4b932a6dd | 35 | (5887 - 3500) * kServoValToDegree + 180, |
shimizuta | 14:d7cb429946f4 | 36 | }, |
shimizuta | 14:d7cb429946f4 | 37 | { |
yuto17320508 | 20:70cc6083e9c7 | 38 | (6470 - 3500) * kServoValToDegree, |
yuto17320508 | 20:70cc6083e9c7 | 39 | (7419 - 3500) * kServoValToDegree - 180, //180度の時6657シータ負の方向に動かすと値は減るので、0度の位置は-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 | 27:79b4b932a6dd | 74 | |
shimizuta | 27:79b4b932a6dd | 75 | ////////調整するべきパラメータ |
shimizuta | 27:79b4b932a6dd | 76 | enum WalkWay |
shimizuta | 27:79b4b932a6dd | 77 | { |
shimizuta | 27:79b4b932a6dd | 78 | STANDUP, |
shimizuta | 27:79b4b932a6dd | 79 | STRAIGHT, |
shimizuta | 27:79b4b932a6dd | 80 | TURNLEFT, |
shimizuta | 27:79b4b932a6dd | 81 | TURNRIGHT, |
shimizuta | 27:79b4b932a6dd | 82 | END, |
shimizuta | 27:79b4b932a6dd | 83 | }; |
shimizuta | 27:79b4b932a6dd | 84 | void ParamsSetup(Walk walks[END], OneLeg leg[4]) //各パラメータの設定。減らしていく必要あり |
shimizuta | 19:1adc7302cfd9 | 85 | { |
shimizuta | 27:79b4b932a6dd | 86 | Walk::calctime_s_ = 0.03; //計算周期 |
shimizuta | 27:79b4b932a6dd | 87 | //足の作成、サイズデータのみの足の骨組.4足同じにしている |
shimizuta | 27:79b4b932a6dd | 88 | for (int i = 0; i < 4; i++) |
shimizuta | 27:79b4b932a6dd | 89 | leg[i] = OneLeg(kBetweenServoHalf_m, kLegLength1, kLegLength2); |
shimizuta | 27:79b4b932a6dd | 90 | //軌道のデフォルト値 |
shimizuta | 27:79b4b932a6dd | 91 | const float kStrideTime_s = 0.3, kRiseTime_s = 0.1, |
shimizuta | 27:79b4b932a6dd | 92 | kStride_m = 0.15, kHeight_m = 0.03, kGround_m = 0.2, |
shimizuta | 27:79b4b932a6dd | 93 | kEllipseCenterX_m = 0, kEllipseCenterY_m = kGround_m; |
shimizuta | 27:79b4b932a6dd | 94 | //STANDUP時のパラメータ。 |
shimizuta | 27:79b4b932a6dd | 95 | walks[STANDUP].SetAllLegStandParam(0, 0.2, 0.5); //一括で設定できる |
shimizuta | 27:79b4b932a6dd | 96 | |
shimizuta | 27:79b4b932a6dd | 97 | //STRAIGHT1のparamater |
shimizuta | 27:79b4b932a6dd | 98 | walks[STRAIGHT].SetOffset(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1]) |
shimizuta | 27:79b4b932a6dd | 99 | walks[STRAIGHT].SetAllLegEllipseParam // 4足一括で設定 |
shimizuta | 27:79b4b932a6dd | 100 | (kStrideTime_s, kRiseTime_s, kStride_m, kHeight_m, kGround_m, kEllipseCenterX_m, kEllipseCenterY_m); |
shimizuta | 27:79b4b932a6dd | 101 | |
shimizuta | 27:79b4b932a6dd | 102 | //TURNLEFT1のparam |
shimizuta | 27:79b4b932a6dd | 103 | float stridetime_s = 0.2, risetime_s = 0.1, stride_short_m = 0.2, stride_long_m = 0.1; |
shimizuta | 27:79b4b932a6dd | 104 | walks[TURNLEFT].SetAllLegEllipseParam // 4足を取り敢えず一括で設定してから |
shimizuta | 27:79b4b932a6dd | 105 | (stridetime_s, risetime_s, stride_short_m, kHeight_m, kGround_m, 0, kEllipseCenterY_m); |
shimizuta | 27:79b4b932a6dd | 106 | walks[TURNLEFT].ChangeOneParam(LEFT_F, STRIDE_M, stride_long_m); //一部のパラメータを変更 |
shimizuta | 27:79b4b932a6dd | 107 | walks[TURNLEFT].ChangeOneParam(LEFT_B, STRIDE_M, stride_long_m); |
shimizuta | 27:79b4b932a6dd | 108 | walks[TURNLEFT].SetOffset(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1]) |
shimizuta | 27:79b4b932a6dd | 109 | |
shimizuta | 27:79b4b932a6dd | 110 | //TURNRIGHT1のparam |
shimizuta | 27:79b4b932a6dd | 111 | walks[TURNRIGHT].SetAllLegEllipseParam // 4足を取り敢えず一括で設定してから |
shimizuta | 27:79b4b932a6dd | 112 | (stridetime_s, risetime_s, stride_short_m, kHeight_m, kGround_m, 0, kEllipseCenterY_m); |
shimizuta | 27:79b4b932a6dd | 113 | walks[TURNRIGHT].ChangeOneParam(RIGHT_F, STRIDE_M, stride_long_m); //一部のパラメータを変更 |
shimizuta | 27:79b4b932a6dd | 114 | walks[TURNRIGHT].ChangeOneParam(RIGHT_B, STRIDE_M, stride_long_m); |
shimizuta | 27:79b4b932a6dd | 115 | walks[TURNRIGHT].SetOffset(0, 0.5, 0.5, 0); //位相ずれの程度(値域[0..1]) |
yuto17320508 | 18:0033ef1814ba | 116 | } |
shimizuta | 27:79b4b932a6dd | 117 | Walk walks[END]; //歩行法 |
shimizuta | 9:905f93247688 | 118 | int main() |
yuto17320508 | 5:556d5a5e9d24 | 119 | { |
shimizuta | 27:79b4b932a6dd | 120 | if (FileOpen()) //csv fileに書き込み |
shimizuta | 27:79b4b932a6dd | 121 | return 1; //異常終了したら強制終了 |
shimizuta | 27:79b4b932a6dd | 122 | DEBUG("param set start"); |
shimizuta | 27:79b4b932a6dd | 123 | ParamsSetup(walks, leg); //各動きの際の足の軌道を設定。パラメータはこの関数内に打ち込む |
shimizuta | 27:79b4b932a6dd | 124 | for (int i = 0; i < END; i++) //軌道のチェック |
shimizuta | 27:79b4b932a6dd | 125 | { |
shimizuta | 27:79b4b932a6dd | 126 | if (walks[i].CheckOrbit(leg[0]) == 1) //軌道が定義外なら |
shimizuta | 27:79b4b932a6dd | 127 | return 1; //強制終了.errorは内部の関数からprintfで知らせる |
shimizuta | 27:79b4b932a6dd | 128 | } |
shimizuta | 27:79b4b932a6dd | 129 | DEBUG("Stand up?\r\n"); |
shimizuta | 27:79b4b932a6dd | 130 | WaitStdin('y'); // ボタンを押したら立つ |
shimizuta | 27:79b4b932a6dd | 131 | MoveOneCycle(walks[STANDUP], leg); |
shimizuta | 27:79b4b932a6dd | 132 | DEBUG("Move?\r\n"); |
shimizuta | 27:79b4b932a6dd | 133 | WaitStdin('y'); // ボタンを押したらスタート |
shimizuta | 27:79b4b932a6dd | 134 | #ifdef USE_ROS |
shimizuta | 27:79b4b932a6dd | 135 | nh_mbed.getHardware()->setBaud(115200); |
shimizuta | 27:79b4b932a6dd | 136 | nh_mbed.initNode(); |
shimizuta | 27:79b4b932a6dd | 137 | nh_mbed.subscribe(sub_vel); |
shimizuta | 27:79b4b932a6dd | 138 | while (1) |
shimizuta | 27:79b4b932a6dd | 139 | nh_mbed.spinOnce(); |
shimizuta | 27:79b4b932a6dd | 140 | #else |
shimizuta | 27:79b4b932a6dd | 141 | for (int i = 1; i < END; i++) //ENDになるまでWalkWayの順に動作 |
shimizuta | 27:79b4b932a6dd | 142 | { |
shimizuta | 27:79b4b932a6dd | 143 | DEBUG("Move %d\r\n", i); |
shimizuta | 27:79b4b932a6dd | 144 | for (int j = 0; j < 2; j++) //debug用に2歩進む |
shimizuta | 27:79b4b932a6dd | 145 | MoveOneCycle(walks[i], leg); |
shimizuta | 27:79b4b932a6dd | 146 | } |
shimizuta | 27:79b4b932a6dd | 147 | MoveOneCycle(walks[STANDUP], leg); //最後はLRFを保護するためSTANDUPの状態で終わる |
shimizuta | 27:79b4b932a6dd | 148 | printf("program end\r\n"); |
shimizuta | 27:79b4b932a6dd | 149 | fclose(fp); |
shimizuta | 27:79b4b932a6dd | 150 | #endif |
shimizuta | 2:a92568bdeb5c | 151 | } |
shimizuta | 27:79b4b932a6dd | 152 | //一サイクル分進む |
shimizuta | 27:79b4b932a6dd | 153 | void MoveOneCycle(Walk walkway, OneLeg leg[4]) |
yuto17320508 | 5:556d5a5e9d24 | 154 | { |
shimizuta | 27:79b4b932a6dd | 155 | #ifndef VSCODE |
shimizuta | 9:905f93247688 | 156 | timer.reset(); |
shimizuta | 9:905f93247688 | 157 | timer.start(); |
shimizuta | 27:79b4b932a6dd | 158 | #endif |
shimizuta | 27:79b4b932a6dd | 159 | int count = walkway.GetOneWalkTime() / walkway.calctime_s_; |
shimizuta | 27:79b4b932a6dd | 160 | for (int i = 0; i < count; i++) |
yuto17320508 | 8:21b932c4e6c5 | 161 | { |
shimizuta | 27:79b4b932a6dd | 162 | #ifndef VSCODE |
shimizuta | 9:905f93247688 | 163 | float time_s = timer.read(); |
shimizuta | 27:79b4b932a6dd | 164 | #endif |
shimizuta | 27:79b4b932a6dd | 165 | walkway.Cal4LegsPosi(leg); //4本の足それぞれの足先サーボ角度更新 |
shimizuta | 19:1adc7302cfd9 | 166 | #ifdef USE_CAN |
shimizuta | 27:79b4b932a6dd | 167 | SendRad(leg[2], leg[3]); //slave_mbed分の足の目標位置を送信 |
shimizuta | 19:1adc7302cfd9 | 168 | #endif |
shimizuta | 9:905f93247688 | 169 | //自身が動かす足のサーボを動かす |
shimizuta | 16:0069a56f11a3 | 170 | MoveServo(leg[0], 0, 0); |
shimizuta | 11:e81425872740 | 171 | MoveServo(leg[1], 1, 0); |
shimizuta | 27:79b4b932a6dd | 172 | #ifndef VSCODE |
shimizuta | 9:905f93247688 | 173 | wait_ms(kServoSpan_ms); |
shimizuta | 27:79b4b932a6dd | 174 | #endif |
shimizuta | 16:0069a56f11a3 | 175 | MoveServo(leg[0], 0, 1); |
shimizuta | 11:e81425872740 | 176 | MoveServo(leg[1], 1, 1); |
shimizuta | 27:79b4b932a6dd | 177 | //ファイルに書き込み。time[s],x[0],y[0],x[1],y[1],x[2],y[2],x[3],y[3]の順 |
shimizuta | 27:79b4b932a6dd | 178 | fprintf(fp, "%f", i * walkway.calctime_s_); |
shimizuta | 27:79b4b932a6dd | 179 | for (int i = 0; i < 4; i++) |
shimizuta | 27:79b4b932a6dd | 180 | fprintf(fp, ",%f,%f", leg[i].GetX_m(), leg[i].GetY_m()); |
shimizuta | 27:79b4b932a6dd | 181 | fprintf(fp, "\r\n"); |
shimizuta | 27:79b4b932a6dd | 182 | #ifndef VSCODE |
shimizuta | 27:79b4b932a6dd | 183 | //計算周期がwalkway.calctime_s_になるようwait |
shimizuta | 27:79b4b932a6dd | 184 | float rest_time_s = walkway.calctime_s_ - (timer.read() - time_s); |
shimizuta | 9:905f93247688 | 185 | if (rest_time_s > 0) |
shimizuta | 9:905f93247688 | 186 | wait(rest_time_s); |
shimizuta | 19:1adc7302cfd9 | 187 | else |
shimizuta | 19:1adc7302cfd9 | 188 | { //計算周期が達成できないときはDEBUGで知らせるだけ。動きはする。 |
shimizuta | 19:1adc7302cfd9 | 189 | DEBUG("error: rest_time_s = %f in Move()\r\n", rest_time_s); |
shimizuta | 14:d7cb429946f4 | 190 | led[0] = 1; |
shimizuta | 14:d7cb429946f4 | 191 | } |
shimizuta | 27:79b4b932a6dd | 192 | #endif |
shimizuta | 9:905f93247688 | 193 | } |
yuto17320508 | 5:556d5a5e9d24 | 194 | } |
shimizuta | 14:d7cb429946f4 | 195 | void MoveServo(OneLeg leg, int serial_num, int servo_id) |
yuto17320508 | 6:43708adf2e5d | 196 | { |
shimizuta | 27:79b4b932a6dd | 197 | #ifndef VSCODE |
shimizuta | 11:e81425872740 | 198 | float degree = leg.GetRad(servo_id) * kRadToDegree; |
shimizuta | 14:d7cb429946f4 | 199 | //サーボの座標系に変更 |
shimizuta | 14:d7cb429946f4 | 200 | float servo_degree = kServoSign[serial_num][servo_id] * degree + kOriginDegree[serial_num][servo_id]; |
shimizuta | 27:79b4b932a6dd | 201 | // DEBUG("servo_degree[%d][%d],%f\r\n", serial_num, servo_id, servo_degree); |
shimizuta | 14:d7cb429946f4 | 202 | servo[serial_num].set_degree(servo_id, servo_degree); |
shimizuta | 27:79b4b932a6dd | 203 | #endif |
shimizuta | 12:2ac37fe6c3bb | 204 | } |
shimizuta | 27:79b4b932a6dd | 205 | void WaitStdin(char startchar) |
shimizuta | 27:79b4b932a6dd | 206 | { |
shimizuta | 27:79b4b932a6dd | 207 | #ifndef USE_ROS |
shimizuta | 27:79b4b932a6dd | 208 | char str[255] = {}; |
shimizuta | 27:79b4b932a6dd | 209 | do |
shimizuta | 27:79b4b932a6dd | 210 | { |
shimizuta | 27:79b4b932a6dd | 211 | printf("put '%c', then start\r\n", startchar); |
shimizuta | 27:79b4b932a6dd | 212 | scanf("%s", str); |
shimizuta | 27:79b4b932a6dd | 213 | } while (str[0] != startchar); |
shimizuta | 27:79b4b932a6dd | 214 | #endif |
shimizuta | 27:79b4b932a6dd | 215 | } |
shimizuta | 27:79b4b932a6dd | 216 | int FileOpen() //1:異常終了 |
shimizuta | 27:79b4b932a6dd | 217 | { |
shimizuta | 27:79b4b932a6dd | 218 | if ((fp = fopen("data.csv", "w")) == NULL) |
shimizuta | 27:79b4b932a6dd | 219 | { |
shimizuta | 27:79b4b932a6dd | 220 | printf("error : FileSave()\r\n"); |
shimizuta | 27:79b4b932a6dd | 221 | return 1; |
shimizuta | 27:79b4b932a6dd | 222 | } |
shimizuta | 27:79b4b932a6dd | 223 | 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 | 224 | return 0; |
shimizuta | 27:79b4b932a6dd | 225 | } |
shimizuta | 27:79b4b932a6dd | 226 | #ifdef USE_ROS |
shimizuta | 27:79b4b932a6dd | 227 | void callback(const geometry_msgs::Vector3 &cmd_vel) |
shimizuta | 27:79b4b932a6dd | 228 | { |
shimizuta | 27:79b4b932a6dd | 229 | float left_vel = cmd_vel.x; |
shimizuta | 27:79b4b932a6dd | 230 | float right_vel = cmd_vel.y; |
shimizuta | 27:79b4b932a6dd | 231 | //閾値は要検討 |
shimizuta | 27:79b4b932a6dd | 232 | if (right_vel < left_vel) |
shimizuta | 27:79b4b932a6dd | 233 | MoveOneCycle(walks[TURNRIGHT], leg); |
shimizuta | 27:79b4b932a6dd | 234 | else if (left_vel < right_vel) |
shimizuta | 27:79b4b932a6dd | 235 | MoveOneCycle(walks[TURNLEFT], leg); |
shimizuta | 27:79b4b932a6dd | 236 | else |
shimizuta | 27:79b4b932a6dd | 237 | MoveOneCycle(walks[STRAIGHT], leg); |
shimizuta | 27:79b4b932a6dd | 238 | } |
shimizuta | 27:79b4b932a6dd | 239 | #endif |