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.
Process.cpp
00001 00002 00003 00004 /* 00005 このプログラムを見る人へ 00006 00007 用語解説 00008 00009 ご挨拶モード:足回りでロボットを左右に振りご挨拶しつつ、回路リセットを行うおれたおになくてはならないモード 00010 足回り:宮川は十字キー足回りを、新村はアナログスティック足回りを担当しました。宮川のプログラムは猫でも書けますが、新村のは難易度S+です。わからないことがあれば新村へ 00011 00012 わからないことがあればアナログスティック以外、なんでも宮川に聞いてください 00013 */ 00014 00015 00016 00017 00018 //------------------------------------------------------------------------------------------------------------------------------------------ 00019 #include "Process.h" 00020 00021 #include "mbed.h" 00022 #include "../../Communication/XBee/XBee.h" 00023 //#include "../../Input/Switch/Switch.h" 00024 #include "../../Output/Motor/Motor.h" 00025 #include "../../Output/Servo/Servo.h" 00026 00027 //_____________________ 00028 /*---------------- HOW TO WRITE ----------------/ 00029 00030 ・motor の割り当てを決める 00031 #define TIRE_L 1 00032 00033 ・リミットスイッチの割り当てを決める 00034 #define ARM_L 1 00035 00036 ・他にも自由に定義してもいいです (pwmとか) 00037 00038 /---------------- HOW TO WRITE ----------------*/ 00039 //↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓ 00040 00041 00042 #define TIRE_1 0 00043 #define TIRE_2 1 00044 #define TIRE_3 2 00045 #define ARM 3 00046 00047 #define ARMlim 0 00048 00049 int Air0=0; 00050 int Air1=1; 00051 00052 #define a 0 00053 #define b 1 00054 #define c 2 00055 00056 int a_array[15][15] = { 00057 { -30, -20, -10, 0, 0, 0, 0, 0, 0, 0, 0, 0, 10, 20, 30 }, 00058 { -40, -30, -20, -10, 0, 0, 0, 0, 0, 0, 0, 10, 20, 30, 40 }, 00059 { -50, -40, -30, -20, -10, 0, 0, 0, 0, 0, 10, 20, 30, 40, 50 }, 00060 { -60, -50, -40, -30, -20, -10, 0, 0, 0, 10, 20, 30, 40, 50, 60 }, 00061 { -70, -60, -50, -40, -30, -20, -10, 0, 10, 20, 30, 40, 50, 60, 70 }, 00062 { -80, -70, -60, -50, -40, -30, -20, 0, 20, 30, 40, 50, 60, 70, 80 }, 00063 { -90, -80, -70, -60, -50, -40, -30, 0, 30, 40, 50, 60, 70, 80, 90 }, 00064 { -100, -90, -80, -70, -60, -50, -40, 0, 40, 50, 60, 70, 80, 90, 100 }, 00065 { -90, -80, -70, -60, -50, -40, -30, 0, 30, 40, 50, 60, 70, 80, 90 }, 00066 { -80, -70, -60, -50, -40, -30, -20, 0, 20, 30, 40, 50, 60, 70, 80 }, 00067 { -70, -60, -50, -40, -30, -20, -10, 0, 10, 20, 30, 40, 50, 60, 70 }, 00068 { -60, -50, -40, -30, -20, -10, 0, 0, 0, 10, 20, 30, 40, 50, 60 }, 00069 { -50, -40, -30, -20, -10, 0, 0, 0, 0, 0, 10, 20, 30, 40, 50 }, 00070 { -40, -30, -20, -10, 0, 0, 0, 0, 0, 0, 0, 10, 20, 30, 40 }, 00071 { -30, -20, -10, 0, 0, 0, 0, 0, 0, 0, 0, 0, 10, 20, 30 } 00072 }; 00073 00074 int b_array[15][15] = { 00075 { 100, 92, 84, 76, 68, 60, 52, 100, 36, 28, 20, 12, 4, 0, 0 }, 00076 { 92, 84, 76, 68, 60, 52, 44, 36, 28, 20, 12, 4, 0, 0, 0 }, 00077 { 84, 76, 68, 60, 52, 44, 36, 28, 20, 12, 4, 0, 0, 0, -4 }, 00078 { 76, 68, 60, 52, 44, 36, 28, 20, 12, 4, 0, 0, 0, -4, -12 }, 00079 { 68, 60, 52, 44, 36, 28, 20, 12, 4, 0, 0, 0, -4, -12, -20 }, 00080 { 60, 52, 44, 36, 28, 20, 12, 4, 0, 0, 0, -4, -12, -20, -28 }, 00081 { 52, 44, 36, 28, 20, 12, 4, 0, 0, 0, -4, -12, -20, -28, -36 }, 00082 { 100, 36, 28, 20, 12, 4, 0, 0, 0, -4, -12, -20, -28, -36, -44 }, 00083 { 85, 28, 20, 12, 4, 0, 0, 0, -4, -12, -20, -28, -36, -44, -52 }, 00084 { 70, 20, 12, 4, 0, 0, 0, -4, -12, -20, -28, -36, -44, -52, -60 }, 00085 { 55, 12, 4, 0, 0, 0, -4, -12, -20, -28, -36, -44, -52, -60, -68 }, 00086 { 40, 4, 0, 0, 0, -4, -12, -20, -28, -36, -44, -52, -60, -68, -76 }, 00087 { 25, 0, 0, 0, -4, -12, -20, -28, -36, -44, -52, -60, -68, -76, -84 }, 00088 { 10, 0, 0, -4, -12, -20, -28, -36, -44, -52, -60, -68, -76, -84, -92 }, 00089 { 0, 0, -4, -12, -20, -28, -36, -100, -52, -60, -68, -76, -84, -92, -100 } 00090 }; 00091 00092 00093 int c_array[15][15] = { 00094 { 0, 0, 4, 12, 20, 28, 36, 100, 52, 60, 68, 76, 84, 92, 100 }, 00095 { 0, 0, 0, 4, 12, 20, 28, 36, 44, 52, 60, 68, 76, 84, 92 }, 00096 { -4, 0, 0, 0, 4, 12, 20, 28, 36, 44, 52, 60, 68, 76, 84 }, 00097 { -12, -4, 0, 0, 0, 4, 12, 20, 28, 36, 44, 52, 60, 68, 76 }, 00098 { -20, -12, -4, 0, 0, 0, 4, 12, 20, 28, 36, 44, 52, 60, 68 }, 00099 { -28, -20, -12, -4, 0, 0, 0, 4, 12, 20, 28, 36, 44, 52, 60 }, 00100 { -36, -28, -20, -12, -4, 0, 0, 0, 4, 12, 20, 28, 36, 44, 52 }, 00101 { -44, -36, -28, -20, -12, -4, 0, 0, 0, 4, 12, 20, 28, 36, 44 }, 00102 { -52, -44, -36, -28, -20, -12, 4, 0, 0, 0, 4, 12, 20, 28, 36 }, 00103 { -60, -52, -44, -36, -28, -20, -12, -4, 0, 0, 0, 4, 12, 20, 28 }, 00104 { -68, -60, -52, -44, -36, -28, -20, -12, -4, 0, 0, 0, 4, 12, 20 }, 00105 { -76, -68, -60, -52, -44, -36, -28, -20, -12, -4, 0, 0, 0, 4, 12 }, 00106 { -84, -76, -68, -60, -52, -44, -36, -28, -20, -12, -4, 0, 0, 0, 4 }, 00107 { -92, -84, -76, -68, -60, -52, -44, -36, -28, -20, -12, -4, 0, 0, 0 }, 00108 { -100, -92, -84, -76, -76, -60, -100, -100, -36, -28, -20, -12, -4, 0, 0 } 00109 }; 00110 00111 int pwm_array[15] = { 30, 25, 20, 15, 10, 5, 0, 0, 0, -5, -10, -15, -20, -25, -30 }; 00112 00113 #define usiro 0 00114 #define mae 0 00115 uint8_t motorData[5]; 00116 uint8_t pwmData[5]; 00117 00118 int conlx; 00119 int conly; 00120 int conrx; 00121 int conry; 00122 int conba; 00123 int conbb; 00124 int conbx; 00125 int conby; 00126 int homes=0; 00127 //↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑ 00128 //_____________________ 00129 00130 //#define USE_USB_SERIAL 00131 #ifdef USE_USB_SERIAL 00132 Serial pc(SERIAL_TX, SERIAL_RX); 00133 #endif 00134 Serial pc(SERIAL_TX,SERIAL_RX); 00135 XBEE::ControllerData *controller; 00136 MOTOR::MotorStatus motor[MOUNTING_MOTOR_NUM]; 00137 ////////////////////////////////// 00138 //関数、タイマーの宣言 00139 DigitalOut Air[]= { 00140 DigitalOut(A5), 00141 DigitalOut(A4), 00142 }; 00143 DigitalIn limit[]= { 00144 DigitalIn(A7), 00145 DigitalIn(A6), 00146 }; 00147 Timer Airtime; 00148 Timer home; 00149 void AirOut(int pin,int mode) 00150 { 00151 Air[pin]=mode; 00152 } 00153 bool LimitRead(int pin) 00154 { 00155 int x; 00156 x=limit[pin]; 00157 if(x==0) { 00158 return false; 00159 } else if(x==1) { 00160 return true; 00161 } else { 00162 return false; 00163 } 00164 } 00165 //関数、タイマーの宣言 00166 ////////////////////////////////// 00167 //using namespace SWITCH; 00168 00169 void SystemProcess(void) 00170 { 00171 while(true) { 00172 controller = XBEE::Controller::GetData(); 00173 //____________________________ 00174 /*------------------------ HOW TO WRITE ------------------------/ 00175 00176 ここにメインのプログラムを書く 00177 00178 ・コントローラから受け取ったデータをもとに動作のプログラムを書く 00179 (コントローラのデータは controller-> で取る) 00180 00181 if(controller->Button.RIGHT) { 00182 motor[TIRE_L].dir = FOR; 00183 motor[TIRE_R].dir = BACK; 00184 motor[TIRE_L].pwm = 12.3; 00185 motor[TIRE_R].pwm = 12.3; 00186 } 00187 00188 motor[0].dirは FOR (正転) 00189 BACK (逆転) 00190 BRAKE (ブレーキ) 00191 FREE (フリー) 00192 00193 motor[0].pwmは 0.0(%) ~ 100.0(%) 00194 00195 controllerは XBee.hの構造体の中身 00196 00197 (AnalogL・Rを使いたかったら、頑張って考える or 聞いてください) 00198 00199 ・リミットスイッチの値をもとに動作のプログラムを書く 00200 00201 if(Switch::CheckPushed(ARM_L)) 00202 { 00203 if(controller->Button.L) 00204 { 00205 motor[ARM].dir = FOR; 00206 motor[ARM].pwm = 80.0; 00207 } 00208 if(motor[ARM].dir == BACK) 00209 { 00210 motor[ARM].dir = BRAKE; 00211 } 00212 } 00213 00214 →関数 Switch::CheckPushed の引数はリミットスイッチの名前 (limitSw[0]みたいな), 返り値はbool型 (true or false) 00215 00216 ・他にもやりたいことがあったら自由にどうぞ 00217 00218 ps.わからないことがあったら聞いてください 00219 00220 /------------------------ HOW TO WRITE ------------------------*/ 00221 //↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓ 00222 00223 float precision; //精密モード変数 00224 float s=Airtime.read();//エアータイム 00225 float hometime=home.read();//ホームタイム(ご挨拶モード兼回路リセット) 00226 float goaisatsu_time=0.2;//ご挨拶タイム 00227 ////////////////////////////////////////////////////////////////////////////////// 00228 //ご挨拶モード 00229 00230 if(controller->Button.HOME) { 00231 home.start(); 00232 homes=1; 00233 } 00234 00235 if((hometime<=goaisatsu_time)&&(!(homes==0))) { 00236 homes=2; 00237 } else if(hometime<=2*goaisatsu_time) { 00238 homes=1; 00239 } else if(hometime<=3*goaisatsu_time) { 00240 homes=2; 00241 } else if(hometime<4*goaisatsu_time) { 00242 homes=1; 00243 } else if(hometime<5*goaisatsu_time) { 00244 homes=0; 00245 home.stop(); 00246 home.reset(); 00247 } else { 00248 homes=0; 00249 home.stop(); 00250 home.reset(); 00251 } 00252 00253 //ご挨拶モード 00254 //////////////////////////////////////////////////////////////////////////////////// 00255 00256 //////////////////////////////////////////////////////////////////////////////////// 00257 //精密モード 00258 if(controller->Button.ZR) { 00259 precision=0.5; 00260 } else { 00261 precision=1.0; 00262 } 00263 //精密モード 00264 //////////////////////////////////////////////////////////////////////////////////// 00265 00266 //////////////////////////////////////////////////////////////////////////////////// 00267 //アーム機構 00268 //motor[ARM].pwm=100; 00269 00270 if(controller->Button.X) { 00271 if(LimitRead(0)){ 00272 motor[ARM].dir = BACK; 00273 motor[ARM].pwm = 100; 00274 }else{ 00275 motor[ARM].dir = FREE; 00276 motor[ARM].pwm = 100; 00277 } 00278 }else if(controller->Button.Y) { 00279 motor[ARM].dir = FOR; 00280 motor[ARM].pwm = 100; 00281 }else{ 00282 motor[ARM].dir = FREE; 00283 motor[ARM].pwm = 100; 00284 } 00285 00286 //アーム機構 00287 //////////////////////////////////////////////////////////////////////////////////// 00288 00289 //////////////////////////////////////////////////////////////////////////////////// 00290 //十字キー足回り(宮川ver) 00291 00292 if(controller->Button.L) { 00293 motor[TIRE_1].dir = FOR; 00294 motor[TIRE_2].dir = FOR; 00295 motor[TIRE_3].dir = FOR; 00296 motor[TIRE_1].pwm = 100*precision; 00297 motor[TIRE_2].pwm = 100*precision; 00298 motor[TIRE_3].pwm = 100*precision; 00299 } else if(controller->Button.R) { 00300 motor[TIRE_1].dir = BACK; 00301 motor[TIRE_2].dir = BACK; 00302 motor[TIRE_3].dir = BACK; 00303 motor[TIRE_1].pwm = 100*precision; 00304 motor[TIRE_2].pwm = 100*precision; 00305 motor[TIRE_3].pwm = 100*precision; 00306 } else if(controller->Button.RIGHT) { 00307 motor[TIRE_1].dir = BACK; 00308 motor[TIRE_2].dir = FOR; 00309 motor[TIRE_3].dir = FOR; 00310 motor[TIRE_1].pwm = 100*precision; 00311 motor[TIRE_2].pwm = 60*precision; 00312 motor[TIRE_3].pwm = 60*precision; 00313 } else if(controller->Button.LEFT) { 00314 motor[TIRE_1].dir = FOR; 00315 motor[TIRE_2].dir = BACK; 00316 motor[TIRE_3].dir = BACK; 00317 motor[TIRE_1].pwm = 100*precision; 00318 motor[TIRE_2].pwm = 60*precision; 00319 motor[TIRE_3].pwm = 60*precision; 00320 } else if(controller->Button.DOWN) { 00321 motor[TIRE_1].dir = BRAKE; 00322 motor[TIRE_2].dir = FOR; 00323 motor[TIRE_3].dir = BACK; 00324 motor[TIRE_1].pwm = 100; 00325 motor[TIRE_2].pwm = 100*precision; 00326 motor[TIRE_3].pwm = 100*precision; 00327 } else if(controller->Button.UP) { 00328 motor[TIRE_1].dir = BRAKE; 00329 motor[TIRE_2].dir = BACK; 00330 motor[TIRE_3].dir = FOR; 00331 motor[TIRE_1].pwm = 100; 00332 motor[TIRE_2].pwm = 100*precision; 00333 motor[TIRE_3].pwm = 100*precision; 00334 } else if((controller->Button.UP) && (controller->Button.RIGHT)) { 00335 motor[TIRE_1].dir = BACK; 00336 motor[TIRE_2].dir = BRAKE; 00337 motor[TIRE_3].dir = FOR; 00338 motor[TIRE_1].pwm = 100*precision; 00339 motor[TIRE_2].pwm = 100; 00340 motor[TIRE_3].pwm = 100*precision; 00341 } else if((controller->Button.UP) && (controller->Button.LEFT)) { 00342 motor[TIRE_1].dir = FOR; 00343 motor[TIRE_2].dir = BACK; 00344 motor[TIRE_3].dir = BRAKE; 00345 motor[TIRE_1].pwm = 100*precision; 00346 motor[TIRE_2].pwm = 100*precision; 00347 motor[TIRE_3].pwm = 100; 00348 } else if((controller->Button.DOWN) && (controller->Button.RIGHT)) { 00349 motor[TIRE_1].dir = BACK; 00350 motor[TIRE_2].dir = FOR; 00351 motor[TIRE_3].dir = BRAKE; 00352 motor[TIRE_1].pwm = 100*precision; 00353 motor[TIRE_2].pwm = 100*precision; 00354 motor[TIRE_3].pwm = 100; 00355 } else if((controller->Button.DOWN) && (controller->Button.LEFT)) { 00356 motor[TIRE_1].dir = FOR; 00357 motor[TIRE_2].dir = BRAKE; 00358 motor[TIRE_3].dir = BACK; 00359 motor[TIRE_1].pwm = 100*precision; 00360 motor[TIRE_2].pwm = 100; 00361 motor[TIRE_3].pwm = 100*precision; 00362 } else if(homes==1) { 00363 motor[TIRE_1].dir = FOR; 00364 motor[TIRE_2].dir = FOR; 00365 motor[TIRE_3].dir = FOR; 00366 motor[TIRE_1].pwm = 70*precision; 00367 motor[TIRE_2].pwm = 70*precision; 00368 motor[TIRE_3].pwm = 70*precision; 00369 } else if(homes==2) { 00370 motor[TIRE_1].dir = BACK; 00371 motor[TIRE_2].dir = BACK; 00372 motor[TIRE_3].dir = BACK; 00373 motor[TIRE_1].pwm = 70*precision; 00374 motor[TIRE_2].pwm = 70*precision; 00375 motor[TIRE_3].pwm = 70*precision; 00376 } else { 00377 motor[TIRE_1].dir=BRAKE; 00378 motor[TIRE_2].dir=BRAKE; 00379 motor[TIRE_3].dir=BRAKE; 00380 motor[TIRE_1].pwm=100; 00381 motor[TIRE_2].pwm=100; 00382 motor[TIRE_3].pwm=100; 00383 } 00384 //十字キー足回り(みやがわver) 00385 /////////////////////////////////// 00386 00387 /////////////////////////////////// 00388 //課題1 00389 if(controller->Button.A) { 00390 AirOut(Air0,1); 00391 } else if(controller->Button.B) { 00392 AirOut(Air0,0); 00393 } 00394 00395 if(controller->Button.ZL) { 00396 Airtime.start(); 00397 AirOut(Air1,0); 00398 } 00399 if(s>1) { 00400 Airtime.stop(); 00401 Airtime.reset(); 00402 AirOut(Air1,1); 00403 } 00404 //課題1 00405 /////////////////////////////////// 00406 00407 ///////////////////////////////////////////////////////////////////////////////////// 00408 //アナログスティック足回り(新村ver) 00409 00410 conlx = controller->AnalogL.X; 00411 conly = controller->AnalogL.Y; 00412 conrx = controller->AnalogR.X; 00413 conry = controller->AnalogR.Y; 00414 if((!(controller->Button.RIGHT))&&(!(controller->Button.DOWN))&& 00415 (!(controller->Button.LEFT))&&(!(controller->Button.UP))&& 00416 (!(controller->Button.L))&&(!(controller->Button.R))&& 00417 (!(controller->Button.HOME))) { 00418 if(((conlx >6) && (conly <8)) ||((conrx >6)&&(conry <8))) { 00419 motor[a].dir = BRAKE; 00420 motor[b].dir = BRAKE; 00421 motor[c].dir = BRAKE; 00422 motor[a].pwm = 100.0; 00423 motor[b].pwm = 100.0; 00424 motor[c].pwm = 100.0; 00425 } 00426 00427 if(a_array[conly][conlx]<0) { 00428 motor[a].pwm = -1*a_array[conly][conlx]*precision; 00429 motor[a].dir = FOR; 00430 } else if(a_array[conly][conlx] > 0) { 00431 motor[a].pwm = a_array[conly][conlx]*precision; 00432 motor[a].dir = BACK; 00433 } else if(a_array[conly][conlx] == 0) { 00434 if(conry < 6) { 00435 motor[a].dir = BACK; 00436 motor[b].dir = BACK; 00437 motor[c].dir = BACK; 00438 motor[a].pwm = 100.0*precision; 00439 motor[b].pwm = 100.0*precision; 00440 motor[c].pwm = 100.0*precision; 00441 } else if(conry > 8) { 00442 motor[a].dir = FOR; 00443 motor[b].dir = FOR; 00444 motor[c].dir = FOR; 00445 motor[a].pwm = 100.0*precision; 00446 motor[b].pwm = 100.0*precision; 00447 motor[c].pwm = 100.0*precision; 00448 } else { 00449 motor[a].dir = BRAKE; 00450 motor[b].dir = BRAKE; 00451 motor[c].dir = BRAKE; 00452 motor[a].pwm = 100.0; 00453 motor[b].pwm = 100.0; 00454 motor[c].pwm = 100.0; 00455 } 00456 } 00457 00458 if(b_array[conly][conlx] <0 ) { 00459 motor[b].pwm = -1*b_array[conly][conlx]*precision; 00460 motor[b].dir = FOR; 00461 } else if(b_array[conly][conlx] > 0) { 00462 motor[b].pwm = b_array[conly][conlx]*precision; 00463 motor[b].dir = BACK; 00464 } else if(a_array[conly][conlx] == 0 ) { 00465 if(conrx < 6 ) { 00466 motor[a].dir = BACK; 00467 motor[b].dir = BACK; 00468 motor[c].dir = BACK; 00469 motor[a].pwm = 100.0*precision; 00470 motor[b].pwm = 100.0*precision; 00471 motor[c].pwm = 100.0*precision; 00472 } else if(conrx > 8) { 00473 motor[a].dir = FOR*precision; 00474 motor[b].dir = FOR*precision; 00475 motor[c].dir = FOR*precision; 00476 motor[a].pwm = 100.0*precision; 00477 motor[b].pwm = 100.0*precision; 00478 motor[c].pwm = 100.0*precision; 00479 } else { 00480 motor[a].dir = BRAKE; 00481 motor[b].dir = BRAKE; 00482 motor[c].dir = BRAKE; 00483 motor[a].pwm = 100.0; 00484 motor[b].pwm = 100.0; 00485 motor[c].pwm = 100.0; 00486 } 00487 } 00488 00489 00490 if(c_array[conly][conlx] <0 ) { 00491 motor[c].pwm =-1*c_array[conly][conlx]*precision; 00492 motor[c].dir = BACK; 00493 } else if(c_array[conly][conlx] > 0) { 00494 motor[c].pwm = c_array[conly][conlx]*precision; 00495 motor[c].dir = FOR; 00496 } else if(a_array[conly][conlx] == 0 ) { 00497 if(conrx < 6 ) { 00498 motor[a].dir = BACK; 00499 motor[b].dir = BACK; 00500 motor[c].dir = BACK; 00501 motor[a].pwm = 100.0*precision; 00502 motor[b].pwm = 100.0*precision; 00503 motor[c].pwm = 100.0*precision; 00504 } else if(conrx > 8) { 00505 motor[a].dir = FOR; 00506 motor[b].dir = FOR; 00507 motor[c].dir = FOR; 00508 motor[a].pwm = 100.0*precision; 00509 motor[b].pwm = 100.0*precision; 00510 motor[c].pwm = 100.0*precision; 00511 } else { 00512 motor[a].dir = BRAKE; 00513 motor[b].dir = BRAKE; 00514 motor[c].dir = BRAKE; 00515 motor[a].pwm = 100.0; 00516 motor[b].pwm = 100.0; 00517 motor[c].pwm = 100.0; 00518 } 00519 //アナログスティック足回り(新村ver) 00520 ///////////////////////////////////////////////////////////////////////////////////// 00521 00522 00523 00524 00525 00526 00527 } 00528 } 00529 00530 00531 00532 //↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑ 00533 00534 00535 MOTOR::Motor::Update(motor); 00536 } 00537 } 00538
Generated on Fri Jul 15 2022 17:22:44 by
1.7.2