にいむら にいむら
/
mainboardnrp2018
unkounko
System/Process/Process.cpp
- Committer:
- niimurasyou
- Date:
- 2019-02-21
- Revision:
- 10:a765515594bd
- Parent:
- 9:ec30ae33cc9e
- Child:
- 11:88f17bc0724f
File content as of revision 10:a765515594bd:
//2018/02/24のやつ #include "Process.h" #include "mbed.h" #include "../../Communication/XBee/XBee.h" #include "../../Input/Switch/Switch.h" #include "../../Output/Motor/Motor.h" #include "../../Output/Servo/Servo.h" //_____________________ /*---------------- HOW TO WRITE ----------------/ ・motor の割り当てを決める #define TIRE_L 1 ・リミットスイッチの割り当てを決める #define ARM_L 1 ・他にも自由に定義してもいいです (pwmとか) /---------------- HOW TO WRITE ----------------*/ //↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓ #define a 0 #define b 1 #define c 2 int a_array[15][15] = { {-80, -70, -60, -50, -40, -20, -10, 0, 10, 20, 40, 50, 60, 70, 80}, {-79, -69, -55, -47, -35, -20, -10, 0, 10, 20, 35, 47, 55, 69, 79}, {-77, -68, -50, -45, -30, -20, -10, 0, 10, 20, 30, 45, 50, 68, 77}, {-75, -67, -49, -40, -25, -20, -10, 0, 10, 20, 25, 40, 49, 67, 75}, {-73, -66, -48, -37, -20, -20, -10, 0, 10, 20, 20, 37, 48, 66, 73}, {-71, -62, -46, -32, -20, -10, 0 , 0, 0 , 10, 20, 32, 46, 62, 71}, {-70, -60, -45, -30, -20, -10, 0 , 0, 0 , 10, 20, 30, 45, 60, 70}, {-71, -62, -46, -32, 10 , -10, 0 , 0, 0 , 10, 20, 32, 46, 62, 71}, {-72, -64, -47, -35, 20 , -10, -10, 0, 10, 10, 20, 35, 47, 64, 72}, {-73, -66, -48, -37, -20, -20, -10, 0, 10, 20, 20, 37, 48, 66, 73}, {-75, -67, -49, -40, 40 , -20, -10, 0, 10, 20, 25, 40, 49, 67, 75}, {-77, -68, -50, -45, 60 , -20, -10, 0, 10, 20, 30, 45, 50, 68, 77}, {-79, -69, -55, -47, 70 , -20, -10, 0, 10, 20, 35, 47, 55, 69, 79}, {-80, -70, -60, -50, -40, -20, -10, 0, 10, 20, 40, 50, 60, 70, 80}}; int b_array[15][15] = { {80, 80, 80 , 77 , 75 , 72 , 71 , 70, 60, 50, 40, 30, 20, 10, 0}, {80, 80, 75 , 70 , 65 , 60 , 55 , 50, 45, 40, 30, 20, 10, 0 , -10}, {80, 71, 70 , 60 , 55 , 50 , 45 , 40, 35, 30, 20, 10, 0, -10, -13}, {60, 60, 57 , 50 , 45 , 40 , 35 , 30, 25, 20, 10, 0 , -10, -13, -17}, {50, 50, 50 , 40 , 35 , 30 , 23 , 20, 15, 10, 0 , -10, -15, -17, -20}, {45, 45, 43 , 35 , 30 , 25 , 10 , 10, 10, 0 , -10, -15, -20, -20, -25}, {40, 37, 35 , 30 , 25 , 20 , 0 , 0 , 0 , -10, -15, -20, -25, -25, -30}, {35, 30, 30 , 25 , 20 , 15 , 0 , 0 , 0 , -15, -20, -25, -30, -30, -35}, {30, 25, 25 , 20 , 15 , 10 , 0 , 0 , 0 , -20, -25, -30, -35, -37, -40}, {20, 17, 15 , 10 , 0 , -10, -15,-20, -23, -30 ,-35 ,-40 ,-50 ,-50 , -50}, {17, 13, 10 , 0 , -10, -20, -25,-30, -35, -40 ,-45 ,-50 ,-57 ,-60 , -60}, {13, 10, 0 , -10, -20, -30, -35,-40, -45, -50 ,-55 ,-60 , -70, -71, -80}, {10, 0 , -10, -20, -30, -40, -45,-50, -55, -60 ,-65 ,-70 ,-75 ,-80 , -80}, {0 , -10, -20, -30, -40, -50, -60,-70, -71, -72 ,-75 ,-77 ,-80 ,-80 , -80}}; int c_array[15][15] = { {0, 10, 20 , 30 , 40 , 50 , 60 ,70 , 71, 72 , 75 , 77 , 80 , 80 , 80}, {-10, 0 , 10 , 20 , 30 , 40 , 45 ,50 , 55 , 60 ,65 ,70 ,75 ,80 ,80}, {-13, -10, 0 , 10 , 20 , 30 , 35 ,40 , 45 , 50 ,55 ,60 ,70 ,71 ,80}, {-17, -13, -10, 0 , 10 , 20 , 25 ,30 , 35 , 40 ,45 ,50 ,57 ,60 ,60}, {-20, -17, -15, -10, 0 , 10 , 15 ,20 , 23 , 30 ,35 ,40 ,50 ,50 ,50}, {-25, -20, -20, -15, -10, 0 , 10 ,10 , 10 , 25 ,30 ,35 ,43 ,45 ,45}, {-30, -25, -25, -20, -15, -10, 0 ,0 , 0 , 20 ,25 ,30 ,35 ,37 ,40}, {-35, -30, -30, -25, -20, -15, 0 ,0 , 0 , 15 ,20 ,25 ,30 ,30 ,35}, {-40, -37, -35, -30, -25, -20, 0 ,0 , 0 , 10 ,15 ,20 ,25 ,25 ,30}, {-50, -50, -50, -40, -35, -30, -23,-20, -15, -10 ,0 ,10 ,15 ,17 ,20}, {-60, -60, -57, -50, -45, -40, -35,-30, -25, -20 ,-10 ,0 ,10 ,13 ,17}, {-80, -71, -70, -60, -55, -50, -45,-40, -35, -30 ,-20 ,-10 ,0 ,10 ,13}, {-80, -80, -75, -70, -65, -60, -55,-50, -45, -40 ,-30 ,-20 ,-10 ,0 ,10}, {-80, -80, -80, -77, -75, -72, -71,-70, -60, -50 ,-40 ,-30 ,-20 ,-10 ,0}}; int pwm_array[15] = { 30 , 25 , 20 , 15 , 10 , 5 , 0 , 0 , 0 , -5 , -10 , -15 , -20 , -25 , -30 }; #define usiro 0 #define mae 0 uint8_t motorData[5]; uint8_t pwmData[5]; int conlx; int conly; int conrx; int conry; int conba; int conbb; int conbx; int conby; //↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑ //_____________________ //#define USE_USB_SERIAL #ifdef USE_USB_SERIAL Serial pc(SERIAL_TX, SERIAL_RX); #endif XBEE::ControllerData *controller; MOTOR::MotorStatus motor[MOUNTING_MOTOR_NUM]; using namespace SWITCH; void SystemProcess(void) { while(true) { controller = XBEE::Controller::GetData(); //____________________________ /*------------------------ HOW TO WRITE ------------------------/ ここにメインのプログラムを書く ・コントローラから受け取ったデータをもとに動作のプログラムを書く (コントローラのデータは controller-> で取る) if(controller->Button.RIGHT) { motor[TIRE_L].dir = FOR; motor[TIRE_R].dir = BACK; motor[TIRE_L].pwm = 12.3; motor[TIRE_R].pwm = 12.3; } motor[0].dirは FOR (正転) BACK (逆転) BRAKE (ブレーキ) FREE (フリー) motor[0].pwmは 0.0(%) ~ 100.0(%) controllerは XBee.hの構造体の中身 (AnalogL・Rを使いたかったら、頑張って考える or 聞いてください) ・リミットスイッチの値をもとに動作のプログラムを書く if(Switch::CheckPushed(ARM_L)) { if(controller->Button.L) { motor[ARM].dir = FOR; motor[ARM].pwm = 80.0; } if(motor[ARM].dir == BACK) { motor[ARM].dir = BRAKE; } } →関数 Switch::CheckPushed の引数はリミットスイッチの名前 (limitSw[0]みたいな), 返り値はbool型 (true or false) ・他にもやりたいことがあったら自由にどうぞ ps.わからないことがあったら聞いてください /------------------------ HOW TO WRITE ------------------------*/ //↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓↓ conlx = controller->AnalogL.X; conly = controller->AnalogL.Y; conrx = controller->AnalogR.X; conry = controller->AnalogR.Y; //conba = controller->Button.A; //conbb = controller->Button.B; //conby = controller->Button.Y; //conbx = controller->Button.X; if(((conlx >6) && (conly <8)) ||((conrx >6)&&(conry <8))){ motor[a].dir = BRAKE; motor[b].dir = BRAKE; motor[c].dir = BRAKE; motor[a].pwm = 100.0; motor[b].pwm = 100.0; motor[c].pwm = 100.0; } if(a_array[conly][conlx]<0){ motor[a].pwm = (-1*a_array[conly][conlx]*100)/90; motor[a].dir = FOR; }else if(a_array[conly][conlx] > 0){ motor[a].pwm = a_array[conly][conlx]; motor[a].dir = FOR;// }else if(a_array[conly][conlx] == 0){ if(conry < 6){ motor[a].dir = BACK; motor[b].dir = BACK; motor[c].dir = BACK; motor[a].pwm = 100.0; motor[b].pwm = 100.0; motor[c].pwm = 100.0; }else if(conry > 8){ motor[a].dir = FOR; motor[b].dir = FOR; motor[c].dir = FOR; motor[a].pwm = 100.0; motor[b].pwm = 100.0; motor[c].pwm = 100.0; }else{ motor[a].dir = BRAKE; motor[b].dir = BRAKE; motor[c].dir = BRAKE; motor[a].pwm = 100.0; motor[b].pwm = 100.0; motor[c].pwm = 100.0; } } if(b_array[conly][conlx] <0 ){ motor[b].pwm = (-1*b_array[conly][conlx]*100)/90; motor[b].dir = FOR; }else if(b_array[conly][conlx] > 0){ motor[b].pwm = b_array[conly][conlx]; motor[b].dir = FOR;// }else if(a_array[conly][conlx] == 0 ){ if(conrx < 6 ) { motor[a].dir = BACK; motor[b].dir = BACK; motor[c].dir = BACK; motor[a].pwm = 100.0; motor[b].pwm = 100.0; motor[c].pwm = 100.0; }else if(conrx > 8){ motor[a].dir = FOR; motor[b].dir = FOR; motor[c].dir = FOR; motor[a].pwm = 100.0; motor[b].pwm = 100.0; motor[c].pwm = 100.0; }else{ motor[a].dir = BRAKE; motor[b].dir = BRAKE; motor[c].dir = BRAKE; motor[a].pwm = 100.0; motor[b].pwm = 100.0; motor[c].pwm = 100.0; } } if(c_array[conly][conlx] <0 ){ motor[c].pwm =(-1*c_array[conly][conlx]*100)/90; motor[c].dir = FOR;// }else if(c_array[conly][conlx] > 0){ motor[c].pwm = c_array[conly][conlx]; motor[c].dir = FOR; }else if(a_array[conly][conlx] == 0 ){ if(conrx < 6 ) { motor[a].dir = BACK; motor[b].dir = BACK; motor[c].dir = BACK; motor[a].pwm = 100.0; motor[b].pwm = 100.0; motor[c].pwm = 100.0; }else if(conrx > 8){ motor[a].dir = FOR; motor[b].dir = FOR; motor[c].dir = FOR; motor[a].pwm = 100.0; motor[b].pwm = 100.0; motor[c].pwm = 100.0; }else{ motor[a].dir = BRAKE; motor[b].dir = BRAKE; motor[c].dir = BRAKE; motor[a].pwm = 100.0; motor[b].pwm = 100.0; motor[c].pwm = 100.0; } // //if (a_array[conlx>6][conly<8]){ // motor[a].dir = BRAKE; // motor[a].pwm = 100.0; // } //if (b_array[conlx>6][conly<8]){ // motor[b].dir = BRAKE; // motor[b].pwm = 100.0; // } //if (c_array[conlx>6][conly<8]){ // motor[c].dir = BRAKE; // motor[c].pwm = 100.0; // } // // //(conba) //{aira=0;} // if(conbb) // {airb=0;} } // //↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑↑ //___________________________ MOTOR::Motor::Update(motor); } }