Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: DriveConroller IMU MDD Mycan Odometer PID RotaryEncoder UART USS mbed
Fork of AR_MastarNode by
main.cpp@0:6db16ad02a1b, 2018-08-04 (annotated)
- Committer:
- TanakaTarou
- Date:
- Sat Aug 04 13:07:23 2018 +0000
- Revision:
- 0:6db16ad02a1b
- Child:
- 1:d7ceb38da3d8
AR?MasterNode
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
TanakaTarou | 0:6db16ad02a1b | 1 | #include "mbed.h" |
TanakaTarou | 0:6db16ad02a1b | 2 | #include "DriveController.h" |
TanakaTarou | 0:6db16ad02a1b | 3 | #include "IMU.h" |
TanakaTarou | 0:6db16ad02a1b | 4 | #include "MDD.h" |
TanakaTarou | 0:6db16ad02a1b | 5 | #include "MDD2.h" |
TanakaTarou | 0:6db16ad02a1b | 6 | #include "Mycan.h" |
TanakaTarou | 0:6db16ad02a1b | 7 | #include "Odometer.h" |
TanakaTarou | 0:6db16ad02a1b | 8 | #include "PID.h" |
TanakaTarou | 0:6db16ad02a1b | 9 | #include "RotaryEncoder.h" |
TanakaTarou | 0:6db16ad02a1b | 10 | #include "CSV.h" |
TanakaTarou | 0:6db16ad02a1b | 11 | #include "SBUS.h" |
TanakaTarou | 0:6db16ad02a1b | 12 | #include "USS.h" |
TanakaTarou | 0:6db16ad02a1b | 13 | #include "hardwareConfig.h" |
TanakaTarou | 0:6db16ad02a1b | 14 | |
TanakaTarou | 0:6db16ad02a1b | 15 | //(X, Y, θ, speed, angle, injection, 補給昇降) |
TanakaTarou | 0:6db16ad02a1b | 16 | float position[10][7] = {{0.0, 0.0, 0.0, 0, 90, 0, 0.0},//x移動, 角度変化 |
TanakaTarou | 0:6db16ad02a1b | 17 | {-0.3, 0.0, 0.0, 0, 90, 0, 0.0},//y移動 |
TanakaTarou | 0:6db16ad02a1b | 18 | {-0.3, 5.0, 0.0, 0, 90, 0, 0.0},//発射 |
TanakaTarou | 0:6db16ad02a1b | 19 | {-0.3, 0.0, 0.0, 0, 90, 0, 0.0},//y移動,角度戻す, P上昇 |
TanakaTarou | 0:6db16ad02a1b | 20 | |
TanakaTarou | 0:6db16ad02a1b | 21 | {-0.6, 0.0, 0.0, 0, 90, 0, 0.0},//x移動, 角度変化, 下降&バットマン駆動 |
TanakaTarou | 0:6db16ad02a1b | 22 | {-0.6, 5.0, 0.0, 0, 90, 0, 0.0},//y移動 |
TanakaTarou | 0:6db16ad02a1b | 23 | {-0.6, 0.0, 0.0, 0, 90, 0, 0.0},//発射 |
TanakaTarou | 0:6db16ad02a1b | 24 | //{6.0, 0.0, 0.0, 20, 90, 0, 6.8},//y移動,角度戻す, P上昇 |
TanakaTarou | 0:6db16ad02a1b | 25 | |
TanakaTarou | 0:6db16ad02a1b | 26 | {-0.9, 0.0, 0.0, 20, 90, 0, 0.0},//x移動, 角度変化, 下降&バットマン駆動 |
TanakaTarou | 0:6db16ad02a1b | 27 | {-0.9, 5.0, 0.0, 20, 90, 0, 0.0},//y移動 |
TanakaTarou | 0:6db16ad02a1b | 28 | {-0.9, 0.0, 0.0, 20, 90, 0, 0.0},//発射 |
TanakaTarou | 0:6db16ad02a1b | 29 | //{7.0, 0.0, 0.0, 20, 90, 0, 6.8},//y移動,角度戻す, P上昇 |
TanakaTarou | 0:6db16ad02a1b | 30 | /* |
TanakaTarou | 0:6db16ad02a1b | 31 | {3.0, 0.0, 0.0, 20, 80, 0, 0.0},//x移動, 角度変化, 下降&バットマン駆動 |
TanakaTarou | 0:6db16ad02a1b | 32 | {3.0, 2.5, 0.0, 20, 80, 0, 0.0},//y移動 |
TanakaTarou | 0:6db16ad02a1b | 33 | {3.0, 2.5, 0.0, 20, 80, 1, 0.0},//下段に発射 |
TanakaTarou | 0:6db16ad02a1b | 34 | {3.0, 2.5, 0.0, 20, 90, 0, 6.8},//角度戻す, P上昇 |
TanakaTarou | 0:6db16ad02a1b | 35 | {3.0, 2.5, 0.0, 20, 80, 0, 0.0},//角度変化, 下降&バットマン駆動 |
TanakaTarou | 0:6db16ad02a1b | 36 | {3.0, 2.5, 0.0, 20, 80, 1, 0.0},//上段に発射 |
TanakaTarou | 0:6db16ad02a1b | 37 | {0.0, 0.0, 0.0, 20, 90, 0, 6.8} //x・y移動,スタートゾーンに戻る |
TanakaTarou | 0:6db16ad02a1b | 38 | */ |
TanakaTarou | 0:6db16ad02a1b | 39 | }; |
TanakaTarou | 0:6db16ad02a1b | 40 | |
TanakaTarou | 0:6db16ad02a1b | 41 | controller getPropoData(); |
TanakaTarou | 0:6db16ad02a1b | 42 | //bool isConvergence(int num); |
TanakaTarou | 0:6db16ad02a1b | 43 | |
TanakaTarou | 0:6db16ad02a1b | 44 | //x軸補正用 PID |
TanakaTarou | 0:6db16ad02a1b | 45 | PID pidRobotX(2, 0, 0, 0.01, 0.3); |
TanakaTarou | 0:6db16ad02a1b | 46 | float target_x = 0; |
TanakaTarou | 0:6db16ad02a1b | 47 | |
TanakaTarou | 0:6db16ad02a1b | 48 | //y軸補正用 PID |
TanakaTarou | 0:6db16ad02a1b | 49 | PID pidRobotY(2, 0, 0, 0.01, 0.3); |
TanakaTarou | 0:6db16ad02a1b | 50 | float target_y = 0; |
TanakaTarou | 0:6db16ad02a1b | 51 | |
TanakaTarou | 0:6db16ad02a1b | 52 | //USS用 |
TanakaTarou | 0:6db16ad02a1b | 53 | PID pidUss(0.02, 0, 0, 0.01, 0.3); |
TanakaTarou | 0:6db16ad02a1b | 54 | float target_uss = 25.0; |
TanakaTarou | 0:6db16ad02a1b | 55 | |
TanakaTarou | 0:6db16ad02a1b | 56 | int main() |
TanakaTarou | 0:6db16ad02a1b | 57 | { |
TanakaTarou | 0:6db16ad02a1b | 58 | //タイマー3の優先度を最低にする |
TanakaTarou | 0:6db16ad02a1b | 59 | NVIC_SetPriority(TIMER3_IRQn, 100); |
TanakaTarou | 0:6db16ad02a1b | 60 | |
TanakaTarou | 0:6db16ad02a1b | 61 | //IMUのキャリブレーション |
TanakaTarou | 0:6db16ad02a1b | 62 | imu.performCalibration(); |
TanakaTarou | 0:6db16ad02a1b | 63 | imu.startAngleComputing(); |
TanakaTarou | 0:6db16ad02a1b | 64 | |
TanakaTarou | 0:6db16ad02a1b | 65 | //yow角補正用 (Pgain, Igain, Dgain, 制御ループ時間[s], 計算出力100%定義) |
TanakaTarou | 0:6db16ad02a1b | 66 | PID pidRobotYow(0.05, 0, 0, 0.01, 0.95); |
TanakaTarou | 0:6db16ad02a1b | 67 | float target = 0; |
TanakaTarou | 0:6db16ad02a1b | 68 | mecanum.imu_yow = &imu.angle[2]; |
TanakaTarou | 0:6db16ad02a1b | 69 | pidRobotYow.sensor = &imu.angle[2]; |
TanakaTarou | 0:6db16ad02a1b | 70 | pidRobotYow.target = ⌖ |
TanakaTarou | 0:6db16ad02a1b | 71 | pidRobotYow.start(); |
TanakaTarou | 0:6db16ad02a1b | 72 | |
TanakaTarou | 0:6db16ad02a1b | 73 | for(int i; i < 3; i++) |
TanakaTarou | 0:6db16ad02a1b | 74 | enc[i].changeDirection(); |
TanakaTarou | 0:6db16ad02a1b | 75 | |
TanakaTarou | 0:6db16ad02a1b | 76 | //オドメーターの定義 |
TanakaTarou | 0:6db16ad02a1b | 77 | float matrix[3][3] = {{1, 0, 0}, |
TanakaTarou | 0:6db16ad02a1b | 78 | {0, 1, 0}, |
TanakaTarou | 0:6db16ad02a1b | 79 | {0, 0, 0} |
TanakaTarou | 0:6db16ad02a1b | 80 | }; |
TanakaTarou | 0:6db16ad02a1b | 81 | Odometer odm(matrix, 0.048); |
TanakaTarou | 0:6db16ad02a1b | 82 | float tmp = 0; |
TanakaTarou | 0:6db16ad02a1b | 83 | float *encoders[3] = {&enc[0].rotations, &enc[1].rotations, &tmp}; |
TanakaTarou | 0:6db16ad02a1b | 84 | odm.setupOdometerSensors(encoders, &imu.angle[2]); |
TanakaTarou | 0:6db16ad02a1b | 85 | odm.startComputingOdometry(0.005, 0, 0, 0); |
TanakaTarou | 0:6db16ad02a1b | 86 | |
TanakaTarou | 0:6db16ad02a1b | 87 | //オドメーターX |
TanakaTarou | 0:6db16ad02a1b | 88 | pidRobotX.sensor = &odm.x; |
TanakaTarou | 0:6db16ad02a1b | 89 | pidRobotX.target = &target_x; |
TanakaTarou | 0:6db16ad02a1b | 90 | pidRobotX.start(); |
TanakaTarou | 0:6db16ad02a1b | 91 | |
TanakaTarou | 0:6db16ad02a1b | 92 | //オドメーターY |
TanakaTarou | 0:6db16ad02a1b | 93 | pidRobotY.sensor = &odm.y; |
TanakaTarou | 0:6db16ad02a1b | 94 | pidRobotY.target = &target_y; |
TanakaTarou | 0:6db16ad02a1b | 95 | pidRobotY.start(); |
TanakaTarou | 0:6db16ad02a1b | 96 | |
TanakaTarou | 0:6db16ad02a1b | 97 | //USS pid設定 |
TanakaTarou | 0:6db16ad02a1b | 98 | uss.startTriger(); |
TanakaTarou | 0:6db16ad02a1b | 99 | pidUss.sensor = &uss.distance; |
TanakaTarou | 0:6db16ad02a1b | 100 | pidUss.target = &target_uss; |
TanakaTarou | 0:6db16ad02a1b | 101 | pidUss.start(); |
TanakaTarou | 0:6db16ad02a1b | 102 | |
TanakaTarou | 0:6db16ad02a1b | 103 | while(1) |
TanakaTarou | 0:6db16ad02a1b | 104 | { |
TanakaTarou | 0:6db16ad02a1b | 105 | controller cmd = getPropoData(); //getPropoData & getCanData |
TanakaTarou | 0:6db16ad02a1b | 106 | |
TanakaTarou | 0:6db16ad02a1b | 107 | static int posi_num = 0; |
TanakaTarou | 0:6db16ad02a1b | 108 | static int reset_swich = 0; |
TanakaTarou | 0:6db16ad02a1b | 109 | if(cmd.H == 2 && reset_swich == 0) |
TanakaTarou | 0:6db16ad02a1b | 110 | { |
TanakaTarou | 0:6db16ad02a1b | 111 | posi_num += 1; |
TanakaTarou | 0:6db16ad02a1b | 112 | if(posi_num > 9) |
TanakaTarou | 0:6db16ad02a1b | 113 | posi_num = 0; |
TanakaTarou | 0:6db16ad02a1b | 114 | reset_swich = 1; |
TanakaTarou | 0:6db16ad02a1b | 115 | } |
TanakaTarou | 0:6db16ad02a1b | 116 | else if(cmd.H == 0 && reset_swich == 1) |
TanakaTarou | 0:6db16ad02a1b | 117 | reset_swich = 0; |
TanakaTarou | 0:6db16ad02a1b | 118 | |
TanakaTarou | 0:6db16ad02a1b | 119 | if(position[posi_num][5] == 1) |
TanakaTarou | 0:6db16ad02a1b | 120 | can.set(1, 1, position[posi_num][3]); |
TanakaTarou | 0:6db16ad02a1b | 121 | else |
TanakaTarou | 0:6db16ad02a1b | 122 | can.set(1, 1, 0); |
TanakaTarou | 0:6db16ad02a1b | 123 | can.set(1, 2, position[posi_num][4]); |
TanakaTarou | 0:6db16ad02a1b | 124 | can.set(2, 1, position[posi_num][6]); |
TanakaTarou | 0:6db16ad02a1b | 125 | can.send(); |
TanakaTarou | 0:6db16ad02a1b | 126 | |
TanakaTarou | 0:6db16ad02a1b | 127 | //ロボットの移動速度(LX, LY, RX) |
TanakaTarou | 0:6db16ad02a1b | 128 | float robot_velocity[3]; |
TanakaTarou | 0:6db16ad02a1b | 129 | |
TanakaTarou | 0:6db16ad02a1b | 130 | //yow角調整処理 |
TanakaTarou | 0:6db16ad02a1b | 131 | *pidRobotYow.target = position[posi_num][2]; |
TanakaTarou | 0:6db16ad02a1b | 132 | robot_velocity[2] = pidRobotYow.output; |
TanakaTarou | 0:6db16ad02a1b | 133 | |
TanakaTarou | 0:6db16ad02a1b | 134 | //x軸調整処理 |
TanakaTarou | 0:6db16ad02a1b | 135 | *pidRobotX.target = position[posi_num][0]; |
TanakaTarou | 0:6db16ad02a1b | 136 | robot_velocity[0] = pidRobotX.output; |
TanakaTarou | 0:6db16ad02a1b | 137 | |
TanakaTarou | 0:6db16ad02a1b | 138 | //USS距離調整処理 |
TanakaTarou | 0:6db16ad02a1b | 139 | if(posi_num == 2 || posi_num == 5 || posi_num == 8) |
TanakaTarou | 0:6db16ad02a1b | 140 | { |
TanakaTarou | 0:6db16ad02a1b | 141 | *pidUss.target = position[posi_num][1]; |
TanakaTarou | 0:6db16ad02a1b | 142 | robot_velocity[1] = -pidUss.output; |
TanakaTarou | 0:6db16ad02a1b | 143 | } |
TanakaTarou | 0:6db16ad02a1b | 144 | else |
TanakaTarou | 0:6db16ad02a1b | 145 | { |
TanakaTarou | 0:6db16ad02a1b | 146 | //y軸調整処理 |
TanakaTarou | 0:6db16ad02a1b | 147 | *pidRobotY.target = position[posi_num][1]; |
TanakaTarou | 0:6db16ad02a1b | 148 | robot_velocity[1] = pidRobotY.output; |
TanakaTarou | 0:6db16ad02a1b | 149 | } |
TanakaTarou | 0:6db16ad02a1b | 150 | |
TanakaTarou | 0:6db16ad02a1b | 151 | //角度・XYリセット |
TanakaTarou | 0:6db16ad02a1b | 152 | if(cmd.F == 2) |
TanakaTarou | 0:6db16ad02a1b | 153 | { |
TanakaTarou | 0:6db16ad02a1b | 154 | imu.angle[2] = 0; |
TanakaTarou | 0:6db16ad02a1b | 155 | *pidRobotYow.target = 0; |
TanakaTarou | 0:6db16ad02a1b | 156 | odm.x = 0; |
TanakaTarou | 0:6db16ad02a1b | 157 | *pidRobotX.target = 0; |
TanakaTarou | 0:6db16ad02a1b | 158 | odm.y = 0; |
TanakaTarou | 0:6db16ad02a1b | 159 | *pidRobotY.target = 0; |
TanakaTarou | 0:6db16ad02a1b | 160 | } |
TanakaTarou | 0:6db16ad02a1b | 161 | |
TanakaTarou | 0:6db16ad02a1b | 162 | //ホイール速度計算 |
TanakaTarou | 0:6db16ad02a1b | 163 | mecanum.setVelL(robot_velocity); |
TanakaTarou | 0:6db16ad02a1b | 164 | mecanum.computeWheelVel(); |
TanakaTarou | 0:6db16ad02a1b | 165 | mecanum.rescaleWheelVel(); |
TanakaTarou | 0:6db16ad02a1b | 166 | |
TanakaTarou | 0:6db16ad02a1b | 167 | //モーターの駆動 |
TanakaTarou | 0:6db16ad02a1b | 168 | for(int i = 0; i < 4; i++) |
TanakaTarou | 0:6db16ad02a1b | 169 | Motor[i].drive(mecanum.wheel_vel[i]); |
TanakaTarou | 0:6db16ad02a1b | 170 | |
TanakaTarou | 0:6db16ad02a1b | 171 | //posi_num += isConvergence(posi_num); |
TanakaTarou | 0:6db16ad02a1b | 172 | |
TanakaTarou | 0:6db16ad02a1b | 173 | pc.printf("%.2f\t", odm.x); |
TanakaTarou | 0:6db16ad02a1b | 174 | pc.printf("%.2f\t", odm.y); |
TanakaTarou | 0:6db16ad02a1b | 175 | |
TanakaTarou | 0:6db16ad02a1b | 176 | pc.printf("\n"); |
TanakaTarou | 0:6db16ad02a1b | 177 | wait(0.02); |
TanakaTarou | 0:6db16ad02a1b | 178 | } |
TanakaTarou | 0:6db16ad02a1b | 179 | } |
TanakaTarou | 0:6db16ad02a1b | 180 | |
TanakaTarou | 0:6db16ad02a1b | 181 | controller getPropoData() |
TanakaTarou | 0:6db16ad02a1b | 182 | { |
TanakaTarou | 0:6db16ad02a1b | 183 | float dead_zone = 0.05; |
TanakaTarou | 0:6db16ad02a1b | 184 | controller propo; |
TanakaTarou | 0:6db16ad02a1b | 185 | sbus.isFailSafe(); |
TanakaTarou | 0:6db16ad02a1b | 186 | |
TanakaTarou | 0:6db16ad02a1b | 187 | //propo直接コントロール |
TanakaTarou | 0:6db16ad02a1b | 188 | if(sbus.isFailSafe()) |
TanakaTarou | 0:6db16ad02a1b | 189 | { |
TanakaTarou | 0:6db16ad02a1b | 190 | propo.LX = propo.LY = propo.RX = propo.RY = 0; |
TanakaTarou | 0:6db16ad02a1b | 191 | propo.H = propo.A = propo.D = propo.F = propo.G = propo.fail_safe = 0; |
TanakaTarou | 0:6db16ad02a1b | 192 | } |
TanakaTarou | 0:6db16ad02a1b | 193 | else |
TanakaTarou | 0:6db16ad02a1b | 194 | { |
TanakaTarou | 0:6db16ad02a1b | 195 | propo.LX = sbus.getStickVal(0) / 255.0; |
TanakaTarou | 0:6db16ad02a1b | 196 | propo.LY = sbus.getStickVal(1) / 255.0; |
TanakaTarou | 0:6db16ad02a1b | 197 | propo.RX = -sbus.getStickVal(2) / 255.0; |
TanakaTarou | 0:6db16ad02a1b | 198 | propo.RY = sbus.getStickVal(3) / 255.0; |
TanakaTarou | 0:6db16ad02a1b | 199 | propo.H = sbus.getSwitchVal(0); |
TanakaTarou | 0:6db16ad02a1b | 200 | propo.C = sbus.getSwitchVal(1); |
TanakaTarou | 0:6db16ad02a1b | 201 | propo.E = sbus.getSwitchVal(2); |
TanakaTarou | 0:6db16ad02a1b | 202 | propo.F = sbus.getSwitchVal(3); |
TanakaTarou | 0:6db16ad02a1b | 203 | propo.G = sbus.getSwitchVal(4); |
TanakaTarou | 0:6db16ad02a1b | 204 | propo.fail_safe = 1; |
TanakaTarou | 0:6db16ad02a1b | 205 | } |
TanakaTarou | 0:6db16ad02a1b | 206 | |
TanakaTarou | 0:6db16ad02a1b | 207 | if(propo.RX < dead_zone && propo.RX > -dead_zone) propo.RX = 0; |
TanakaTarou | 0:6db16ad02a1b | 208 | if(propo.RY < dead_zone && propo.RY > -dead_zone) propo.RY = 0; |
TanakaTarou | 0:6db16ad02a1b | 209 | if(propo.LX < dead_zone && propo.LX > -dead_zone) propo.LX = 0; |
TanakaTarou | 0:6db16ad02a1b | 210 | if(propo.LY < dead_zone && propo.LY > -dead_zone) propo.LY = 0; |
TanakaTarou | 0:6db16ad02a1b | 211 | return propo; |
TanakaTarou | 0:6db16ad02a1b | 212 | } |
TanakaTarou | 0:6db16ad02a1b | 213 | |
TanakaTarou | 0:6db16ad02a1b | 214 | /* |
TanakaTarou | 0:6db16ad02a1b | 215 | bool isConvergence(int num) |
TanakaTarou | 0:6db16ad02a1b | 216 | { |
TanakaTarou | 0:6db16ad02a1b | 217 | bool tf; |
TanakaTarou | 0:6db16ad02a1b | 218 | if(num > 3 && num < 8) |
TanakaTarou | 0:6db16ad02a1b | 219 | num -= 4; |
TanakaTarou | 0:6db16ad02a1b | 220 | else if(num > 7 && num < 12) |
TanakaTarou | 0:6db16ad02a1b | 221 | num -= 8; |
TanakaTarou | 0:6db16ad02a1b | 222 | else if(num > 11 && num < 15) |
TanakaTarou | 0:6db16ad02a1b | 223 | num -= 8; |
TanakaTarou | 0:6db16ad02a1b | 224 | |
TanakaTarou | 0:6db16ad02a1b | 225 | if(num == 0) |
TanakaTarou | 0:6db16ad02a1b | 226 | { |
TanakaTarou | 0:6db16ad02a1b | 227 | if(pidRobotX.output == 0) |
TanakaTarou | 0:6db16ad02a1b | 228 | tf = 1; |
TanakaTarou | 0:6db16ad02a1b | 229 | else |
TanakaTarou | 0:6db16ad02a1b | 230 | tf = 0; |
TanakaTarou | 0:6db16ad02a1b | 231 | } |
TanakaTarou | 0:6db16ad02a1b | 232 | else if(num == 1) |
TanakaTarou | 0:6db16ad02a1b | 233 | { |
TanakaTarou | 0:6db16ad02a1b | 234 | if(pidUss.output == 0) |
TanakaTarou | 0:6db16ad02a1b | 235 | tf = 1; |
TanakaTarou | 0:6db16ad02a1b | 236 | else |
TanakaTarou | 0:6db16ad02a1b | 237 | tf = 0; |
TanakaTarou | 0:6db16ad02a1b | 238 | } |
TanakaTarou | 0:6db16ad02a1b | 239 | else if(num == 2) |
TanakaTarou | 0:6db16ad02a1b | 240 | { |
TanakaTarou | 0:6db16ad02a1b | 241 | wait(1.0); |
TanakaTarou | 0:6db16ad02a1b | 242 | tf = 1; |
TanakaTarou | 0:6db16ad02a1b | 243 | } |
TanakaTarou | 0:6db16ad02a1b | 244 | else if(num == 3) |
TanakaTarou | 0:6db16ad02a1b | 245 | { |
TanakaTarou | 0:6db16ad02a1b | 246 | if(pidRobotY.output == 0) |
TanakaTarou | 0:6db16ad02a1b | 247 | tf = 1; |
TanakaTarou | 0:6db16ad02a1b | 248 | else |
TanakaTarou | 0:6db16ad02a1b | 249 | tf = 0; |
TanakaTarou | 0:6db16ad02a1b | 250 | } |
TanakaTarou | 0:6db16ad02a1b | 251 | else if(num == 15) |
TanakaTarou | 0:6db16ad02a1b | 252 | { |
TanakaTarou | 0:6db16ad02a1b | 253 | |
TanakaTarou | 0:6db16ad02a1b | 254 | } |
TanakaTarou | 0:6db16ad02a1b | 255 | else if(num == 16) |
TanakaTarou | 0:6db16ad02a1b | 256 | { |
TanakaTarou | 0:6db16ad02a1b | 257 | |
TanakaTarou | 0:6db16ad02a1b | 258 | } |
TanakaTarou | 0:6db16ad02a1b | 259 | else if(num == 17) |
TanakaTarou | 0:6db16ad02a1b | 260 | { |
TanakaTarou | 0:6db16ad02a1b | 261 | |
TanakaTarou | 0:6db16ad02a1b | 262 | } |
TanakaTarou | 0:6db16ad02a1b | 263 | |
TanakaTarou | 0:6db16ad02a1b | 264 | return tf; |
TanakaTarou | 0:6db16ad02a1b | 265 | } |
TanakaTarou | 0:6db16ad02a1b | 266 | */ |