harurobo-main-ver5
Dependencies: mbed EC PathFollowing-ver11 CruizCore_R1370P
main.cpp@8:84d10508818a, 2018-12-05 (annotated)
- Committer:
- yuki0701
- Date:
- Wed Dec 05 07:02:46 2018 +0000
- Revision:
- 8:84d10508818a
- Parent:
- 7:e269985951bf
a
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
la00noix | 0:f5992b0c6e00 | 1 | #include "mbed.h" |
la00noix | 0:f5992b0c6e00 | 2 | #include "EC.h" |
la00noix | 0:f5992b0c6e00 | 3 | #include "R1370P.h" |
la00noix | 0:f5992b0c6e00 | 4 | #include "move4wheel.h" |
la00noix | 0:f5992b0c6e00 | 5 | #include "PathFollowing.h" |
la00noix | 0:f5992b0c6e00 | 6 | #include <stdarg.h> |
la00noix | 0:f5992b0c6e00 | 7 | |
la00noix | 0:f5992b0c6e00 | 8 | #define PI 3.141592 |
la00noix | 0:f5992b0c6e00 | 9 | |
la00noix | 0:f5992b0c6e00 | 10 | #define DEBUG_MODE // compile as debug mode (comment out if you don't use) |
la00noix | 0:f5992b0c6e00 | 11 | #ifdef DEBUG_MODE |
la00noix | 0:f5992b0c6e00 | 12 | #define DEBUG_PRINT // enable debug_printf |
la00noix | 0:f5992b0c6e00 | 13 | #endif |
la00noix | 0:f5992b0c6e00 | 14 | |
la00noix | 0:f5992b0c6e00 | 15 | Serial pc(USBTX,USBRX); |
la00noix | 0:f5992b0c6e00 | 16 | void debug_printf(const char* format,...); // work as printf in debug |
la00noix | 0:f5992b0c6e00 | 17 | void Debug_Control(); // control by PC keybord |
la00noix | 0:f5992b0c6e00 | 18 | |
la00noix | 0:f5992b0c6e00 | 19 | #define SPI_FREQ 1000000 // 1MHz |
la00noix | 0:f5992b0c6e00 | 20 | #define SPI_BITS 16 |
la00noix | 0:f5992b0c6e00 | 21 | #define SPI_MODE 0 |
la00noix | 0:f5992b0c6e00 | 22 | #define SPI_WAIT_US 1 // 1us |
yuki0701 | 3:e696a6dd4254 | 23 | //SPI spi(PB_5,PB_4,PB_3); //Nucleo |
yuki0701 | 3:e696a6dd4254 | 24 | SPI spi(p5,p6,p7); //mbed |
la00noix | 0:f5992b0c6e00 | 25 | |
yuki0701 | 3:e696a6dd4254 | 26 | /*DigitalOut ss_md1(PB_15); //エスコンの設定 |
la00noix | 0:f5992b0c6e00 | 27 | DigitalOut ss_md2(PB_14); |
la00noix | 0:f5992b0c6e00 | 28 | DigitalOut ss_md3(PB_13); |
la00noix | 0:f5992b0c6e00 | 29 | DigitalOut ss_md4(PC_4); |
la00noix | 0:f5992b0c6e00 | 30 | |
la00noix | 0:f5992b0c6e00 | 31 | DigitalOut md_enable(PA_13); // do all motor driver enable |
la00noix | 0:f5992b0c6e00 | 32 | //DigitalIn md_ch_enable(p10); // check enable switch is open or close |
la00noix | 0:f5992b0c6e00 | 33 | //Timer md_disable; |
la00noix | 0:f5992b0c6e00 | 34 | DigitalOut md_stop(PA_14); // stop all motor |
yuki0701 | 3:e696a6dd4254 | 35 | DigitalIn md_check(PB_7); // check error of all motor driver //とりあえず使わない*/ |
yuki0701 | 3:e696a6dd4254 | 36 | |
yuki0701 | 3:e696a6dd4254 | 37 | DigitalOut ss_md1(p15); //エスコンの設定 |
yuki0701 | 3:e696a6dd4254 | 38 | DigitalOut ss_md2(p16); |
yuki0701 | 3:e696a6dd4254 | 39 | DigitalOut ss_md3(p17); |
yuki0701 | 3:e696a6dd4254 | 40 | DigitalOut ss_md4(p18); |
yuki0701 | 3:e696a6dd4254 | 41 | |
yuki0701 | 3:e696a6dd4254 | 42 | DigitalOut md_enable(p25); |
yuki0701 | 3:e696a6dd4254 | 43 | //Timer md_disable; |
yuki0701 | 3:e696a6dd4254 | 44 | DigitalOut md_stop(p24); // stop all motor |
yuki0701 | 3:e696a6dd4254 | 45 | DigitalIn md_check(p23); // check error of all motor driver //とりあえず使わない |
yuki0701 | 3:e696a6dd4254 | 46 | |
la00noix | 0:f5992b0c6e00 | 47 | |
la00noix | 0:f5992b0c6e00 | 48 | /*モーターの配置 |
la00noix | 0:f5992b0c6e00 | 49 | * md1//---F---\\md4 |
la00noix | 0:f5992b0c6e00 | 50 | * | | |
la00noix | 0:f5992b0c6e00 | 51 | * L + R |
la00noix | 0:f5992b0c6e00 | 52 | * | | |
la00noix | 0:f5992b0c6e00 | 53 | * md2\\---B---//md3 |
la00noix | 0:f5992b0c6e00 | 54 | */ |
la00noix | 0:f5992b0c6e00 | 55 | |
la00noix | 0:f5992b0c6e00 | 56 | |
yuki0701 | 3:e696a6dd4254 | 57 | //Ec EC1(PC_6,PC_8,NC,500,0.05); |
yuki0701 | 3:e696a6dd4254 | 58 | //Ec EC2(PB_1,PB_12,NC,500,0.05); //Nucleo |
yuki0701 | 3:e696a6dd4254 | 59 | |
yuki0701 | 5:7493649d098b | 60 | Ec EC1(p21,p22,NC,500,0.05); |
yuki0701 | 3:e696a6dd4254 | 61 | Ec EC2(p8,p26,NC,500,0.05); //←mbad |
la00noix | 0:f5992b0c6e00 | 62 | Ticker motor_tick; //角速度計算用ticker |
la00noix | 0:f5992b0c6e00 | 63 | Ticker ticker; //for enc |
la00noix | 0:f5992b0c6e00 | 64 | |
yuki0701 | 3:e696a6dd4254 | 65 | //R1370P gyro(PC_6,PC_7); //ジャイロ |
yuki0701 | 3:e696a6dd4254 | 66 | R1370P gyro(p28,p27); |
la00noix | 0:f5992b0c6e00 | 67 | |
la00noix | 0:f5992b0c6e00 | 68 | //DigitalOut can_led(LED1); //if can enable -> toggle |
la00noix | 0:f5992b0c6e00 | 69 | DigitalOut debug_led(LED2); //if debugmode -> on |
la00noix | 0:f5992b0c6e00 | 70 | DigitalOut md_stop_led(LED3); //if motor stop -> on |
la00noix | 0:f5992b0c6e00 | 71 | DigitalOut md_err_led(LED4); //if driver error -> on //とりあえず使わない |
la00noix | 0:f5992b0c6e00 | 72 | |
la00noix | 0:f5992b0c6e00 | 73 | double new_dist1=0,new_dist2=0; |
la00noix | 0:f5992b0c6e00 | 74 | double old_dist1=0,old_dist2=0; |
la00noix | 0:f5992b0c6e00 | 75 | double d_dist1=0,d_dist2=0; //座標計算用関数 |
la00noix | 0:f5992b0c6e00 | 76 | double d_x,d_y; |
la00noix | 0:f5992b0c6e00 | 77 | //現在地X,y座標、現在角度については、PathFollowingでnow_x,now_y,now_angleを定義済 |
la00noix | 0:f5992b0c6e00 | 78 | double start_x=0,start_y=0; //スタート位置 |
la00noix | 0:f5992b0c6e00 | 79 | |
yuki0701 | 3:e696a6dd4254 | 80 | double x_out,y_out,r_out;//出力値 |
yuki0701 | 3:e696a6dd4254 | 81 | |
la00noix | 0:f5992b0c6e00 | 82 | static int16_t m1=0, m2=0, m3=0, m4=0; //int16bit = int2byte |
la00noix | 0:f5992b0c6e00 | 83 | |
yuki0701 | 3:e696a6dd4254 | 84 | ///////////////////////////////////////////////////関数のプロトタイプ宣言//////////////////////////////////////////////////// |
la00noix | 0:f5992b0c6e00 | 85 | void UserLoopSetting(); // initialize setting |
la00noix | 0:f5992b0c6e00 | 86 | void DAC_Write(int16_t data, DigitalOut* DAC_cs); |
la00noix | 0:f5992b0c6e00 | 87 | void MotorControl(int16_t val_md1, int16_t val_md2, int16_t val_md3, int16_t val_md4); |
la00noix | 0:f5992b0c6e00 | 88 | |
la00noix | 0:f5992b0c6e00 | 89 | void calOmega() //角速度計算関数 |
la00noix | 0:f5992b0c6e00 | 90 | { |
la00noix | 0:f5992b0c6e00 | 91 | EC1.CalOmega(); |
la00noix | 0:f5992b0c6e00 | 92 | EC2.CalOmega(); |
la00noix | 0:f5992b0c6e00 | 93 | } |
la00noix | 0:f5992b0c6e00 | 94 | |
la00noix | 0:f5992b0c6e00 | 95 | void output(double FL,double BL,double BR,double FR) |
la00noix | 0:f5992b0c6e00 | 96 | { |
la00noix | 0:f5992b0c6e00 | 97 | m1=FL; |
la00noix | 0:f5992b0c6e00 | 98 | m2=BL; |
la00noix | 0:f5992b0c6e00 | 99 | m3=BR; |
la00noix | 0:f5992b0c6e00 | 100 | m4=FR; |
la00noix | 0:f5992b0c6e00 | 101 | } |
la00noix | 0:f5992b0c6e00 | 102 | |
yuki0701 | 7:e269985951bf | 103 | /*void base(double FL,double BL,double BR,double FR,double Max) |
la00noix | 0:f5992b0c6e00 | 104 | //いろんな加算をしても最大OR最小が1になるような補正(?)//絶対値が一番でかいやつで除算//double Max(0~1) |
la00noix | 0:f5992b0c6e00 | 105 | //マクソンは-4095~4095だからMax=4095にする//最速スピードを出すための関数になってる |
la00noix | 0:f5992b0c6e00 | 106 | { |
yuki0701 | 3:e696a6dd4254 | 107 | if (fabs(FL)>=fabs(BL)&&fabs(FL)>=fabs(BR)&&fabs(FL)>=fabs(FR))output(Max*FL/fabs(FL),Max*BL/fabs(FL),Max*BR/fabs(FL),Max*FR/fabs(FL)); |
yuki0701 | 3:e696a6dd4254 | 108 | else if(fabs(BL)>=fabs(FL)&&fabs(BL)>=fabs(BR)&&fabs(BL)>=fabs(FR))output(Max*FL/fabs(BL),Max*BL/fabs(BL),Max*BR/fabs(BL),Max*FR/fabs(BL)); |
yuki0701 | 3:e696a6dd4254 | 109 | else if(fabs(BR)>=fabs(FL)&&fabs(BR)>=fabs(BL)&&fabs(BR)>=fabs(FR))output(Max*FL/fabs(BR),Max*BL/fabs(BR),Max*BR/fabs(BR),Max*FR/fabs(BR)); |
yuki0701 | 3:e696a6dd4254 | 110 | else output(Max*FL/fabs(FR),Max*BL/fabs(FR),Max*BR/fabs(FR),Max*FR/fabs(FR)); |
yuki0701 | 7:e269985951bf | 111 | }*/ |
yuki0701 | 7:e269985951bf | 112 | |
yuki0701 | 7:e269985951bf | 113 | void base(double FL,double BL,double BR,double FR,double Max) |
yuki0701 | 7:e269985951bf | 114 | //いろんな加算をしても最大OR最小が1になるような補正(?)//絶対値が一番でかいやつで除算//double Max(0~1) |
yuki0701 | 7:e269985951bf | 115 | //マクソンは-4095~4095だからMax=4095にする//最速スピードを出すための関数になってる |
yuki0701 | 7:e269985951bf | 116 | { |
yuki0701 | 7:e269985951bf | 117 | if(fabs(FL)>=Max||fabs(BL)>=Max||fabs(BR)>=Max||fabs(FR)>=Max) { |
yuki0701 | 7:e269985951bf | 118 | |
yuki0701 | 7:e269985951bf | 119 | if (fabs(FL)>=fabs(BL)&&fabs(FL)>=fabs(BR)&&fabs(FL)>=fabs(FR))output(Max*FL/fabs(FL),Max*BL/fabs(FL),Max*BR/fabs(FL),Max*FR/fabs(FL)); |
yuki0701 | 7:e269985951bf | 120 | else if(fabs(BL)>=fabs(FL)&&fabs(BL)>=fabs(BR)&&fabs(BL)>=fabs(FR))output(Max*FL/fabs(BL),Max*BL/fabs(BL),Max*BR/fabs(BL),Max*FR/fabs(BL)); |
yuki0701 | 7:e269985951bf | 121 | else if(fabs(BR)>=fabs(FL)&&fabs(BR)>=fabs(BL)&&fabs(BR)>=fabs(FR))output(Max*FL/fabs(BR),Max*BL/fabs(BR),Max*BR/fabs(BR),Max*FR/fabs(BR)); |
yuki0701 | 7:e269985951bf | 122 | else output(Max*FL/fabs(FR),Max*BL/fabs(FR),Max*BR/fabs(FR),Max*FR/fabs(FR)); |
yuki0701 | 7:e269985951bf | 123 | } else { |
yuki0701 | 7:e269985951bf | 124 | output(FL,BL,BR,FR); |
yuki0701 | 7:e269985951bf | 125 | } |
yuki0701 | 7:e269985951bf | 126 | |
yuki0701 | 3:e696a6dd4254 | 127 | } |
yuki0701 | 3:e696a6dd4254 | 128 | void calc_xy() |
yuki0701 | 3:e696a6dd4254 | 129 | { |
yuki0701 | 3:e696a6dd4254 | 130 | now_angle=gyro.getAngle(); //ジャイロの値読み込み |
yuki0701 | 3:e696a6dd4254 | 131 | |
yuki0701 | 3:e696a6dd4254 | 132 | new_dist1=EC1.getDistance_mm(); |
yuki0701 | 3:e696a6dd4254 | 133 | new_dist2=EC2.getDistance_mm(); |
yuki0701 | 3:e696a6dd4254 | 134 | d_dist1=new_dist1-old_dist1; |
yuki0701 | 3:e696a6dd4254 | 135 | d_dist2=new_dist2-old_dist2; |
yuki0701 | 3:e696a6dd4254 | 136 | old_dist1=new_dist1; |
yuki0701 | 3:e696a6dd4254 | 137 | old_dist2=new_dist2; //微小時間当たりのエンコーダ読み込み |
yuki0701 | 3:e696a6dd4254 | 138 | |
yuki0701 | 3:e696a6dd4254 | 139 | d_x=d_dist2*sin(now_angle*PI/180)-d_dist1*cos(now_angle*PI/180); |
yuki0701 | 3:e696a6dd4254 | 140 | d_y=d_dist2*cos(now_angle*PI/180)+d_dist1*sin(now_angle*PI/180); //微小時間毎の座標変化 |
yuki0701 | 3:e696a6dd4254 | 141 | now_x=now_x+d_x; |
yuki0701 | 3:e696a6dd4254 | 142 | now_y=now_y-d_y; //微小時間毎に座標に加算 |
yuki0701 | 5:7493649d098b | 143 | |
la00noix | 0:f5992b0c6e00 | 144 | } |
la00noix | 0:f5992b0c6e00 | 145 | |
la00noix | 0:f5992b0c6e00 | 146 | //ここからそれぞれのプログラム////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// |
la00noix | 0:f5992b0c6e00 | 147 | //now_x(現在のx座標),now_y(現在のy座標),now_angle(機体角度(ラジアンではない)(0~360や-180~180とは限らない))(反時計回りが正) |
la00noix | 0:f5992b0c6e00 | 148 | //ジャイロの出力は角度だが三角関数はラジアンとして計算する |
la00noix | 0:f5992b0c6e00 | 149 | //通常の移動+座標のずれ補正+機体の角度補正(+必要に応じさらに別補正) |
la00noix | 0:f5992b0c6e00 | 150 | //ジャイロの仕様上、角度補正をするときに計算式内で角度はそのままよりsinをとったほうがいいかもね |
la00noix | 0:f5992b0c6e00 | 151 | |
yuki0701 | 8:84d10508818a | 152 | void purecurve(int type,double X,double Y,double r,int theta,double speed1,double speed2) |
la00noix | 0:f5992b0c6e00 | 153 | { |
la00noix | 0:f5992b0c6e00 | 154 | //正面を変えずに円弧を描いて90°曲がる |
la00noix | 0:f5992b0c6e00 | 155 | //X=円弧の中心座標、Y=円弧の中心座標、r=円弧の半径、theta=plotの間隔(0~90°)、v=目標速度 |
yuki0701 | 8:84d10508818a | 156 | //speed1:初速度, speed2:目標速度 |
la00noix | 0:f5992b0c6e00 | 157 | |
la00noix | 0:f5992b0c6e00 | 158 | int s; |
yuki0701 | 3:e696a6dd4254 | 159 | int t = 0; |
la00noix | 0:f5992b0c6e00 | 160 | double plotx[(90/theta)+1]; //円弧にとるplotのx座標 |
la00noix | 0:f5992b0c6e00 | 161 | double ploty[(90/theta)+1]; |
la00noix | 0:f5992b0c6e00 | 162 | //double plotvx[(90/theta)+1]; //各plotにおける速度 |
la00noix | 0:f5992b0c6e00 | 163 | //double plotvy[(90/theta)+1]; |
la00noix | 0:f5992b0c6e00 | 164 | |
la00noix | 0:f5992b0c6e00 | 165 | double x_out,y_out,r_out; |
la00noix | 0:f5992b0c6e00 | 166 | |
la00noix | 0:f5992b0c6e00 | 167 | switch(type) { |
la00noix | 0:f5992b0c6e00 | 168 | case 1://↑から→ |
la00noix | 0:f5992b0c6e00 | 169 | |
la00noix | 0:f5992b0c6e00 | 170 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 3:e696a6dd4254 | 171 | plotx[s] = X + r * cos(PI - s * (PI*theta/180)); |
la00noix | 0:f5992b0c6e00 | 172 | ploty[s] = Y + r * sin(PI - s * (PI*theta/180)); |
la00noix | 0:f5992b0c6e00 | 173 | //plotvx[s] = -v * cos(PI - s * (PI*theta/180)); |
la00noix | 0:f5992b0c6e00 | 174 | //plotvy[s] = v * sin(PI - s * (PI*theta/180)); |
yuki0701 | 5:7493649d098b | 175 | debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
la00noix | 0:f5992b0c6e00 | 176 | } |
la00noix | 0:f5992b0c6e00 | 177 | |
la00noix | 0:f5992b0c6e00 | 178 | while(1) { |
yuki0701 | 8:84d10508818a | 179 | //now_angle=gyro.getAngle(); //ジャイロの値読み込み |
la00noix | 0:f5992b0c6e00 | 180 | |
yuki0701 | 3:e696a6dd4254 | 181 | calc_xy(); |
la00noix | 0:f5992b0c6e00 | 182 | |
yuki0701 | 8:84d10508818a | 183 | XYRmotorout(plotx[t],ploty[t],plotx[t+1],ploty[t+1],&x_out,&y_out,&r_out,speed1,speed2); |
la00noix | 0:f5992b0c6e00 | 184 | CalMotorOut(x_out,y_out,r_out); //move4wheel内のモーター番号定義または成分分解が違うかも? |
la00noix | 0:f5992b0c6e00 | 185 | //CalMotorOut(plotvx[t], plotvy[t],0); |
la00noix | 0:f5992b0c6e00 | 186 | |
yuki0701 | 3:e696a6dd4254 | 187 | //debug_printf("t=%d now_x=%f now_y=%f x_out=%f y_out=%f\n\r",t,now_x,now_y,x_out,y_out); |
yuki0701 | 3:e696a6dd4254 | 188 | //debug_printf("t=%d (0)=%f (1)=%f (2)=%f (3)=%f\n\r",t,GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3)); |
la00noix | 0:f5992b0c6e00 | 189 | |
yuki0701 | 3:e696a6dd4254 | 190 | base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),1000); //m1~m4に代入 |
la00noix | 0:f5992b0c6e00 | 191 | |
yuki0701 | 3:e696a6dd4254 | 192 | if(((plotx[t+1] - now_x)*(plotx[t+1] - plotx[t]) + (ploty[t+1] - now_y)*(ploty[t+1] - ploty[t])) < 0)t++; |
la00noix | 0:f5992b0c6e00 | 193 | if(t == (90/theta))break; |
la00noix | 2:e04e6b5d6584 | 194 | |
la00noix | 0:f5992b0c6e00 | 195 | MotorControl(m1,m2,m3,m4); //出力 |
la00noix | 2:e04e6b5d6584 | 196 | |
yuki0701 | 5:7493649d098b | 197 | //debug_printf("t=%d m1=%d m2=%d m3=%d m4=%d x=%f y=%f, angle = %f\n\r",t,m1,m2,m3,m4,now_x,now_y,now_angle); |
la00noix | 0:f5992b0c6e00 | 198 | |
la00noix | 0:f5992b0c6e00 | 199 | } |
la00noix | 0:f5992b0c6e00 | 200 | |
la00noix | 0:f5992b0c6e00 | 201 | case 2://↑から← //まだ編集してない |
la00noix | 0:f5992b0c6e00 | 202 | |
la00noix | 0:f5992b0c6e00 | 203 | for(s=0; s<((90/theta)+1); s++) { |
la00noix | 0:f5992b0c6e00 | 204 | plotx[s] = X + r * cos(s * (PI*theta/180)); |
la00noix | 0:f5992b0c6e00 | 205 | ploty[s] = Y + r * sin(s * (PI*theta/180)); |
la00noix | 0:f5992b0c6e00 | 206 | } |
la00noix | 0:f5992b0c6e00 | 207 | |
la00noix | 0:f5992b0c6e00 | 208 | while(1) { |
la00noix | 0:f5992b0c6e00 | 209 | |
yuki0701 | 8:84d10508818a | 210 | //now_angle=gyro.getAngle(); //ジャイロの値読み込み |
yuki0701 | 5:7493649d098b | 211 | |
yuki0701 | 3:e696a6dd4254 | 212 | calc_xy(); |
la00noix | 0:f5992b0c6e00 | 213 | |
yuki0701 | 8:84d10508818a | 214 | XYRmotorout(plotx[t],ploty[t],plotx[t+1],ploty[t+1],&x_out,&y_out,&r_out,speed1,speed2); |
la00noix | 0:f5992b0c6e00 | 215 | CalMotorOut(x_out,y_out,r_out); |
yuki0701 | 3:e696a6dd4254 | 216 | base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),1000); |
yuki0701 | 3:e696a6dd4254 | 217 | if(((plotx[t+1] - now_x)*(plotx[t+1] - plotx[t]) + (ploty[t+1] - now_y)*(ploty[t+1] - ploty[t])) < 0)t++; |
la00noix | 0:f5992b0c6e00 | 218 | if(t == (90/theta))break; |
la00noix | 0:f5992b0c6e00 | 219 | |
yuki0701 | 3:e696a6dd4254 | 220 | MotorControl(m1,m2,m3,m4); |
la00noix | 0:f5992b0c6e00 | 221 | } |
la00noix | 0:f5992b0c6e00 | 222 | } |
la00noix | 0:f5992b0c6e00 | 223 | } |
yuki0701 | 3:e696a6dd4254 | 224 | |
yuki0701 | 8:84d10508818a | 225 | void purecurve2(int type,double point_x1,double point_y1,double point_x2,double point_y2,int theta,double speed1,double speed2) |
yuki0701 | 5:7493649d098b | 226 | { |
yuki0701 | 5:7493649d098b | 227 | //正面を変えずに円弧を描いて90°曲がる |
yuki0701 | 5:7493649d098b | 228 | //point_x1,point_y1=出発地点の座標 point_x2,point_x2=目標地点の座標,theta=plotの間隔(0~90°)、v=目標速度 |
yuki0701 | 5:7493649d098b | 229 | //type:動きの種類(8パターン) |
yuki0701 | 5:7493649d098b | 230 | |
yuki0701 | 5:7493649d098b | 231 | int s; |
yuki0701 | 5:7493649d098b | 232 | int t = 0; |
yuki0701 | 5:7493649d098b | 233 | double X,Y;//X=楕円の中心座標、Y=楕円の中心座標 |
yuki0701 | 5:7493649d098b | 234 | double a,b; //a=楕円のx軸方向の幅の半分,b=楕円のy軸方向の幅の半分 |
yuki0701 | 5:7493649d098b | 235 | double plotx[(90/theta)+1]; //楕円にとるplotのx座標 |
yuki0701 | 5:7493649d098b | 236 | double ploty[(90/theta)+1]; |
yuki0701 | 5:7493649d098b | 237 | //double plotvx[(90/theta)+1]; //各plotにおける速度 |
yuki0701 | 5:7493649d098b | 238 | //double plotvy[(90/theta)+1]; |
yuki0701 | 5:7493649d098b | 239 | double x_out,y_out,r_out; |
yuki0701 | 5:7493649d098b | 240 | |
yuki0701 | 5:7493649d098b | 241 | a=fabs(point_x1-point_x2); |
yuki0701 | 5:7493649d098b | 242 | b=fabs(point_y1-point_y2); |
yuki0701 | 5:7493649d098b | 243 | |
yuki0701 | 5:7493649d098b | 244 | switch(type) { |
yuki0701 | 5:7493649d098b | 245 | |
yuki0701 | 5:7493649d098b | 246 | case 1://→↑移動 |
yuki0701 | 5:7493649d098b | 247 | X=point_x1; |
yuki0701 | 5:7493649d098b | 248 | Y=point_y2; |
yuki0701 | 5:7493649d098b | 249 | |
yuki0701 | 5:7493649d098b | 250 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 5:7493649d098b | 251 | plotx[s] = X + a * cos(-PI/2 + s * (PI*theta/180)); |
yuki0701 | 5:7493649d098b | 252 | ploty[s] = Y + b * sin(-PI/2 + s * (PI*theta/180)); |
yuki0701 | 5:7493649d098b | 253 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 5:7493649d098b | 254 | } |
yuki0701 | 5:7493649d098b | 255 | break; |
yuki0701 | 5:7493649d098b | 256 | |
yuki0701 | 5:7493649d098b | 257 | case 2://↑→移動 |
yuki0701 | 5:7493649d098b | 258 | X=point_x2; |
yuki0701 | 5:7493649d098b | 259 | Y=point_y1; |
yuki0701 | 5:7493649d098b | 260 | |
yuki0701 | 5:7493649d098b | 261 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 5:7493649d098b | 262 | plotx[s] = X + a * cos(PI - s * (PI*theta/180)); |
yuki0701 | 5:7493649d098b | 263 | ploty[s] = Y + b * sin(PI - s * (PI*theta/180)); |
yuki0701 | 5:7493649d098b | 264 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 5:7493649d098b | 265 | } |
yuki0701 | 5:7493649d098b | 266 | break; |
yuki0701 | 5:7493649d098b | 267 | |
yuki0701 | 5:7493649d098b | 268 | case 3://↑←移動 |
yuki0701 | 5:7493649d098b | 269 | X=point_x2; |
yuki0701 | 5:7493649d098b | 270 | Y=point_y1; |
yuki0701 | 5:7493649d098b | 271 | |
yuki0701 | 5:7493649d098b | 272 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 5:7493649d098b | 273 | plotx[s] = X + a * cos(s * (PI*theta/180)); |
yuki0701 | 5:7493649d098b | 274 | ploty[s] = Y + b * sin(s * (PI*theta/180)); |
yuki0701 | 5:7493649d098b | 275 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 5:7493649d098b | 276 | } |
yuki0701 | 5:7493649d098b | 277 | break; |
yuki0701 | 5:7493649d098b | 278 | |
yuki0701 | 5:7493649d098b | 279 | case 4://←↑移動 |
yuki0701 | 5:7493649d098b | 280 | X=point_x1; |
yuki0701 | 5:7493649d098b | 281 | Y=point_y2; |
yuki0701 | 5:7493649d098b | 282 | |
yuki0701 | 5:7493649d098b | 283 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 5:7493649d098b | 284 | plotx[s] = X + a * cos(-PI/2 - s * (PI*theta/180)); |
yuki0701 | 5:7493649d098b | 285 | ploty[s] = Y + b * sin(-PI/2 - s * (PI*theta/180)); |
yuki0701 | 5:7493649d098b | 286 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 5:7493649d098b | 287 | } |
yuki0701 | 5:7493649d098b | 288 | break; |
yuki0701 | 5:7493649d098b | 289 | |
yuki0701 | 5:7493649d098b | 290 | case 5://←↓移動 |
yuki0701 | 5:7493649d098b | 291 | X=point_x1; |
yuki0701 | 5:7493649d098b | 292 | Y=point_y2; |
yuki0701 | 5:7493649d098b | 293 | |
yuki0701 | 5:7493649d098b | 294 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 5:7493649d098b | 295 | plotx[s] = X + a * cos(PI/2 + s * (PI*theta/180)); |
yuki0701 | 5:7493649d098b | 296 | ploty[s] = Y + b * sin(PI/2 + s * (PI*theta/180)); |
yuki0701 | 5:7493649d098b | 297 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 5:7493649d098b | 298 | } |
yuki0701 | 5:7493649d098b | 299 | break; |
yuki0701 | 5:7493649d098b | 300 | |
yuki0701 | 5:7493649d098b | 301 | case 6://↓←移動 |
yuki0701 | 5:7493649d098b | 302 | X=point_x2; |
yuki0701 | 5:7493649d098b | 303 | Y=point_y1; |
yuki0701 | 5:7493649d098b | 304 | |
yuki0701 | 5:7493649d098b | 305 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 5:7493649d098b | 306 | plotx[s] = X + a * cos(-s * (PI*theta/180)); |
yuki0701 | 5:7493649d098b | 307 | ploty[s] = Y + b * sin(-s * (PI*theta/180)); |
yuki0701 | 5:7493649d098b | 308 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 5:7493649d098b | 309 | } |
yuki0701 | 5:7493649d098b | 310 | break; |
yuki0701 | 5:7493649d098b | 311 | |
yuki0701 | 5:7493649d098b | 312 | case 7://↓→移動 |
yuki0701 | 5:7493649d098b | 313 | X=point_x2; |
yuki0701 | 5:7493649d098b | 314 | Y=point_y1; |
yuki0701 | 5:7493649d098b | 315 | |
yuki0701 | 5:7493649d098b | 316 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 5:7493649d098b | 317 | plotx[s] = X + a * cos(PI + s * (PI*theta/180)); |
yuki0701 | 5:7493649d098b | 318 | ploty[s] = Y + b * sin(PI + s * (PI*theta/180)); |
yuki0701 | 5:7493649d098b | 319 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 5:7493649d098b | 320 | } |
yuki0701 | 5:7493649d098b | 321 | break; |
yuki0701 | 5:7493649d098b | 322 | |
yuki0701 | 5:7493649d098b | 323 | case 8://→↓移動 |
yuki0701 | 5:7493649d098b | 324 | X=point_x1; |
yuki0701 | 5:7493649d098b | 325 | Y=point_y2; |
yuki0701 | 5:7493649d098b | 326 | |
yuki0701 | 5:7493649d098b | 327 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 5:7493649d098b | 328 | plotx[s] = X + a * cos(PI/2 - s * (PI*theta/180)); |
yuki0701 | 5:7493649d098b | 329 | ploty[s] = Y + b * sin(PI/2 - s * (PI*theta/180)); |
yuki0701 | 5:7493649d098b | 330 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 5:7493649d098b | 331 | } |
yuki0701 | 5:7493649d098b | 332 | break; |
yuki0701 | 5:7493649d098b | 333 | } |
yuki0701 | 5:7493649d098b | 334 | |
yuki0701 | 5:7493649d098b | 335 | while(1) { |
yuki0701 | 6:14cb400f99f7 | 336 | //now_angle=gyro.getAngle(); //ジャイロの値読み込み |
yuki0701 | 5:7493649d098b | 337 | |
yuki0701 | 5:7493649d098b | 338 | calc_xy(); |
yuki0701 | 5:7493649d098b | 339 | |
yuki0701 | 8:84d10508818a | 340 | XYRmotorout(plotx[t],ploty[t],plotx[t+1],ploty[t+1],&x_out,&y_out,&r_out,speed1,speed2); |
yuki0701 | 5:7493649d098b | 341 | CalMotorOut(x_out,y_out,r_out); //move4wheel内のモーター番号定義または成分分解が違うかも? |
yuki0701 | 5:7493649d098b | 342 | //CalMotorOut(plotvx[t], plotvy[t],0); |
yuki0701 | 5:7493649d098b | 343 | |
yuki0701 | 7:e269985951bf | 344 | debug_printf("t=%d now_x=%f now_y=%f x_out=%f y_out=%f\n\r",t,now_x,now_y,x_out,y_out); |
yuki0701 | 5:7493649d098b | 345 | //debug_printf("t=%d (0)=%f (1)=%f (2)=%f (3)=%f\n\r",t,GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3)); |
yuki0701 | 5:7493649d098b | 346 | |
yuki0701 | 5:7493649d098b | 347 | base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),1000); //m1~m4に代入 |
yuki0701 | 5:7493649d098b | 348 | |
yuki0701 | 5:7493649d098b | 349 | if(((plotx[t+1] - now_x)*(plotx[t+1] - plotx[t]) + (ploty[t+1] - now_y)*(ploty[t+1] - ploty[t])) < 0)t++; |
yuki0701 | 5:7493649d098b | 350 | if(t == (90/theta))break; |
yuki0701 | 5:7493649d098b | 351 | |
yuki0701 | 5:7493649d098b | 352 | MotorControl(m1,m2,m3,m4); //出力 |
yuki0701 | 5:7493649d098b | 353 | |
yuki0701 | 7:e269985951bf | 354 | //debug_printf("t=%d m1=%d m2=%d m3=%d m4=%d x=%f y=%f, angle = %f\n\r",t,m1,m2,m3,m4,now_x,now_y,now_angle); |
yuki0701 | 5:7493649d098b | 355 | |
yuki0701 | 5:7493649d098b | 356 | } |
yuki0701 | 5:7493649d098b | 357 | } |
yuki0701 | 5:7493649d098b | 358 | |
yuki0701 | 5:7493649d098b | 359 | |
yuki0701 | 5:7493649d098b | 360 | |
yuki0701 | 5:7493649d098b | 361 | |
yuki0701 | 8:84d10508818a | 362 | void gogo_straight(double x1_point,double y1_point,double x2_point,double y2_point,double speed1,double speed2) //直線運動プログラム |
yuki0701 | 8:84d10508818a | 363 | //引数:出発地点の座標(x,y)、目標地点の座標(x,y)、初速度(speed1)、目標速度(speed2) |
yuki0701 | 3:e696a6dd4254 | 364 | { |
yuki0701 | 3:e696a6dd4254 | 365 | while (1) { |
yuki0701 | 3:e696a6dd4254 | 366 | |
yuki0701 | 3:e696a6dd4254 | 367 | //now_angle=gyro.getAngle(); |
yuki0701 | 3:e696a6dd4254 | 368 | |
yuki0701 | 3:e696a6dd4254 | 369 | calc_xy(); |
yuki0701 | 3:e696a6dd4254 | 370 | printf("x = %f, y = %f, angle = %f\r\n",now_x,now_y,now_angle); |
yuki0701 | 3:e696a6dd4254 | 371 | |
yuki0701 | 3:e696a6dd4254 | 372 | |
yuki0701 | 3:e696a6dd4254 | 373 | //Debug_Control(); |
yuki0701 | 8:84d10508818a | 374 | XYRmotorout(x1_point,y1_point,x2_point,y2_point,&x_out,&y_out,&r_out,speed1,speed2); |
yuki0701 | 7:e269985951bf | 375 | //printf("x = %f, y = %f,angle = %f,x_out=%lf, y_out=%lf, r_out=%lf\n\r",now_x,now_y,now_angle,x_out, y_out,r_out); |
yuki0701 | 3:e696a6dd4254 | 376 | |
yuki0701 | 3:e696a6dd4254 | 377 | CalMotorOut(x_out,y_out,r_out); |
yuki0701 | 3:e696a6dd4254 | 378 | //printf("out1=%lf, out2=%lf, out3=%lf, out4=%lf\n",GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3)); |
yuki0701 | 3:e696a6dd4254 | 379 | |
yuki0701 | 3:e696a6dd4254 | 380 | base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),1000); |
yuki0701 | 3:e696a6dd4254 | 381 | //printf("m1=%d, m2=%d, m3=%d, m4=%d\r\n",m1,m2,m3,m4); |
yuki0701 | 3:e696a6dd4254 | 382 | MotorControl(m1,m2,m3,m4); |
yuki0701 | 5:7493649d098b | 383 | |
yuki0701 | 3:e696a6dd4254 | 384 | if(((x2_point - now_x)*(x2_point - x1_point) + (y2_point - now_y)*(y2_point - y1_point)) < 0) break; |
yuki0701 | 3:e696a6dd4254 | 385 | |
yuki0701 | 3:e696a6dd4254 | 386 | } |
yuki0701 | 3:e696a6dd4254 | 387 | |
yuki0701 | 3:e696a6dd4254 | 388 | } |
yuki0701 | 3:e696a6dd4254 | 389 | |
yuki0701 | 5:7493649d098b | 390 | void go_straight(int type,double goal_x,double goal_y,double speed,double front) //移動パターン(1,2,3,4)、目標X、目標Y、最高速度(0~1)、正面角度 |
yuki0701 | 3:e696a6dd4254 | 391 | { |
yuki0701 | 3:e696a6dd4254 | 392 | double y_hosei=(now_y-goal_y)*0.001;//Y座標(mm単位)にP処理 |
yuki0701 | 3:e696a6dd4254 | 393 | double x_hosei=(now_x-goal_x)*0.001;//X座標(mm単位)にP処理 |
yuki0701 | 3:e696a6dd4254 | 394 | double incl_hosei=sin(now_angle-front)*(PI/180)*0.1;//機体角度(sin(数度→ラジアンに変換))にP処理 |
yuki0701 | 3:e696a6dd4254 | 395 | |
yuki0701 | 3:e696a6dd4254 | 396 | switch(type) { |
yuki0701 | 3:e696a6dd4254 | 397 | case 1://Y座標一定の正方向横移動 |
yuki0701 | 5:7493649d098b | 398 | while(now_x<goal_x) { |
yuki0701 | 5:7493649d098b | 399 | base(-1-y_hosei-incl_hosei,-1+y_hosei-incl_hosei,1+y_hosei-incl_hosei,1-y_hosei-incl_hosei,speed); |
yuki0701 | 3:e696a6dd4254 | 400 | } |
yuki0701 | 3:e696a6dd4254 | 401 | break; |
yuki0701 | 5:7493649d098b | 402 | |
yuki0701 | 3:e696a6dd4254 | 403 | case 2://Y座標一定の負方向横移動 |
yuki0701 | 5:7493649d098b | 404 | while(now_x>goal_x) { |
yuki0701 | 5:7493649d098b | 405 | base(1-y_hosei-incl_hosei,1+y_hosei-incl_hosei,-1+y_hosei-incl_hosei,-1-y_hosei-incl_hosei,speed); |
yuki0701 | 3:e696a6dd4254 | 406 | } |
yuki0701 | 3:e696a6dd4254 | 407 | break; |
yuki0701 | 5:7493649d098b | 408 | |
yuki0701 | 3:e696a6dd4254 | 409 | case 3://Y座標一定の正方向横移動 |
yuki0701 | 5:7493649d098b | 410 | while(now_y<goal_y) { |
yuki0701 | 5:7493649d098b | 411 | base(1+x_hosei-incl_hosei,-1+x_hosei-incl_hosei,-1-x_hosei-incl_hosei,1-x_hosei-incl_hosei,speed); |
yuki0701 | 3:e696a6dd4254 | 412 | } |
yuki0701 | 3:e696a6dd4254 | 413 | break; |
yuki0701 | 5:7493649d098b | 414 | |
yuki0701 | 3:e696a6dd4254 | 415 | case 4://X座標一定の負方向横移動 |
yuki0701 | 5:7493649d098b | 416 | while(now_y>goal_y) { |
yuki0701 | 5:7493649d098b | 417 | base(-1+x_hosei-incl_hosei,1+x_hosei-incl_hosei,1-x_hosei-incl_hosei,-1-x_hosei-incl_hosei,speed); |
yuki0701 | 3:e696a6dd4254 | 418 | } |
yuki0701 | 3:e696a6dd4254 | 419 | break; |
yuki0701 | 3:e696a6dd4254 | 420 | } |
yuki0701 | 3:e696a6dd4254 | 421 | } |
yuki0701 | 3:e696a6dd4254 | 422 | |
yuki0701 | 6:14cb400f99f7 | 423 | |
yuki0701 | 6:14cb400f99f7 | 424 | |
yuki0701 | 3:e696a6dd4254 | 425 | //////////////////////////////////////////////////////////////以下main文//////////////////////////////////////////////////////////////////////// |
la00noix | 0:f5992b0c6e00 | 426 | |
la00noix | 0:f5992b0c6e00 | 427 | int main() |
la00noix | 0:f5992b0c6e00 | 428 | { |
la00noix | 0:f5992b0c6e00 | 429 | UserLoopSetting(); |
la00noix | 0:f5992b0c6e00 | 430 | |
yuki0701 | 3:e696a6dd4254 | 431 | void reset(); |
la00noix | 0:f5992b0c6e00 | 432 | EC1.reset(); |
yuki0701 | 3:e696a6dd4254 | 433 | EC2.reset(); |
la00noix | 0:f5992b0c6e00 | 434 | |
la00noix | 0:f5992b0c6e00 | 435 | now_x=start_x; |
la00noix | 0:f5992b0c6e00 | 436 | now_y=start_y; |
yuki0701 | 5:7493649d098b | 437 | |
yuki0701 | 6:14cb400f99f7 | 438 | /*set_target_angle(0); |
yuki0701 | 6:14cb400f99f7 | 439 | purecurve2(1,0,0,1000,1000,9); |
yuki0701 | 6:14cb400f99f7 | 440 | MotorControl(0,0,0,0);*/ |
yuki0701 | 6:14cb400f99f7 | 441 | |
yuki0701 | 6:14cb400f99f7 | 442 | /* set_target_angle(0); |
yuki0701 | 6:14cb400f99f7 | 443 | while(1){ |
yuki0701 | 6:14cb400f99f7 | 444 | purecurve2(7,0,0,500,-500,9); |
yuki0701 | 6:14cb400f99f7 | 445 | MotorControl(0,0,0,0); |
yuki0701 | 6:14cb400f99f7 | 446 | purecurve2(1,500,-500,1000,0,9); |
yuki0701 | 6:14cb400f99f7 | 447 | MotorControl(0,0,0,0); |
yuki0701 | 6:14cb400f99f7 | 448 | purecurve2(3,1000,0,500,500,9); |
yuki0701 | 6:14cb400f99f7 | 449 | MotorControl(0,0,0,0); |
yuki0701 | 6:14cb400f99f7 | 450 | purecurve2(5,500,500,0,0,9); |
yuki0701 | 6:14cb400f99f7 | 451 | MotorControl(0,0,0,0); |
yuki0701 | 6:14cb400f99f7 | 452 | }*/ |
yuki0701 | 5:7493649d098b | 453 | |
yuki0701 | 7:e269985951bf | 454 | int a=0; |
yuki0701 | 6:14cb400f99f7 | 455 | while(1) { |
yuki0701 | 6:14cb400f99f7 | 456 | set_target_angle(a); |
yuki0701 | 8:84d10508818a | 457 | gogo_straight(0,0,0,-1200,1000,1000); |
yuki0701 | 8:84d10508818a | 458 | gogo_straight(0,-1200,0,-1500,1000,1000); |
yuki0701 | 6:14cb400f99f7 | 459 | MotorControl(0,0,0,0); |
yuki0701 | 6:14cb400f99f7 | 460 | wait(1); |
yuki0701 | 5:7493649d098b | 461 | |
yuki0701 | 7:e269985951bf | 462 | //a=a+90; |
yuki0701 | 6:14cb400f99f7 | 463 | |
yuki0701 | 6:14cb400f99f7 | 464 | set_target_angle(a); |
yuki0701 | 8:84d10508818a | 465 | gogo_straight(0,-1500,0,-300,1000,1000); |
yuki0701 | 8:84d10508818a | 466 | gogo_straight(0,-300,0,0,1000,1000); |
yuki0701 | 6:14cb400f99f7 | 467 | MotorControl(0,0,0,0); |
yuki0701 | 6:14cb400f99f7 | 468 | wait(1); |
yuki0701 | 6:14cb400f99f7 | 469 | |
yuki0701 | 7:e269985951bf | 470 | //a=a+90; |
yuki0701 | 6:14cb400f99f7 | 471 | |
yuki0701 | 6:14cb400f99f7 | 472 | } |
la00noix | 0:f5992b0c6e00 | 473 | |
la00noix | 0:f5992b0c6e00 | 474 | } |
yuki0701 | 3:e696a6dd4254 | 475 | ///////////////////////////////////////////////////////////////////////以下マクソン関連/////////////////////////////////////////////////////////////////////////// |
la00noix | 0:f5992b0c6e00 | 476 | |
la00noix | 0:f5992b0c6e00 | 477 | void UserLoopSetting() |
la00noix | 0:f5992b0c6e00 | 478 | { |
la00noix | 0:f5992b0c6e00 | 479 | //-----エスコンの初期設定-----// |
la00noix | 0:f5992b0c6e00 | 480 | spi.format(SPI_BITS, SPI_MODE); |
la00noix | 0:f5992b0c6e00 | 481 | spi.frequency(SPI_FREQ); |
la00noix | 0:f5992b0c6e00 | 482 | ss_md1 = 1; |
la00noix | 0:f5992b0c6e00 | 483 | ss_md2 = 1; |
la00noix | 0:f5992b0c6e00 | 484 | ss_md3 = 1; |
la00noix | 0:f5992b0c6e00 | 485 | ss_md4 = 1; |
la00noix | 0:f5992b0c6e00 | 486 | md_enable = 1; //enable on |
la00noix | 0:f5992b0c6e00 | 487 | md_err_led = 0; |
la00noix | 0:f5992b0c6e00 | 488 | md_stop = 1; |
la00noix | 0:f5992b0c6e00 | 489 | md_stop_led = 1; |
la00noix | 0:f5992b0c6e00 | 490 | //-----センサーの初期設定-----// |
la00noix | 0:f5992b0c6e00 | 491 | gyro.initialize(); |
la00noix | 0:f5992b0c6e00 | 492 | motor_tick.attach(&calOmega,0.05); //0.05秒間隔で角速度を計算 |
la00noix | 0:f5992b0c6e00 | 493 | EC1.setDiameter_mm(48); |
la00noix | 0:f5992b0c6e00 | 494 | EC2.setDiameter_mm(48); //測定輪半径 |
la00noix | 0:f5992b0c6e00 | 495 | //-----PathFollowingのパラメーター設定-----// |
yuki0701 | 8:84d10508818a | 496 | //set_p_out(1000); //ベクトルABに平行方向の出力値設定関数(カーブを曲がる速度) |
yuki0701 | 6:14cb400f99f7 | 497 | q_setPDparam(5,0.1); //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数 |
yuki0701 | 3:e696a6dd4254 | 498 | r_setPDparam(10,0.1); //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数 |
yuki0701 | 6:14cb400f99f7 | 499 | set_r_out(600); //旋回時の最大出力値設定関数 |
yuki0701 | 5:7493649d098b | 500 | // set_target_angle(0); //機体目標角度設定関数 |
la00noix | 0:f5992b0c6e00 | 501 | |
la00noix | 0:f5992b0c6e00 | 502 | #ifdef DEBUG_MODE |
la00noix | 0:f5992b0c6e00 | 503 | debug_led = 1; |
la00noix | 0:f5992b0c6e00 | 504 | pc.attach(Debug_Control, Serial::RxIrq); |
la00noix | 0:f5992b0c6e00 | 505 | #else |
la00noix | 0:f5992b0c6e00 | 506 | debug_led = 0; |
la00noix | 0:f5992b0c6e00 | 507 | #endif |
la00noix | 0:f5992b0c6e00 | 508 | } |
la00noix | 0:f5992b0c6e00 | 509 | |
la00noix | 0:f5992b0c6e00 | 510 | #define MCP4922_AB (1<<15) |
la00noix | 0:f5992b0c6e00 | 511 | #define MCP4922_BUF (1<<14) |
la00noix | 0:f5992b0c6e00 | 512 | #define MCP4922_GA (1<<13) |
la00noix | 0:f5992b0c6e00 | 513 | #define MCP4922_SHDN (1<<12) |
la00noix | 0:f5992b0c6e00 | 514 | |
la00noix | 0:f5992b0c6e00 | 515 | #define MCP4922_SET_OUTA (0x3000) //( MCP4922_GA || MCP4922_SHDN ) //12288 |
la00noix | 0:f5992b0c6e00 | 516 | #define MCP4922_SET_OUTB (0xB000) //( MCP4922_AB || MCP4922_GA || MCP4922_SHDN ) //45056 |
la00noix | 0:f5992b0c6e00 | 517 | #define MCP4922_MASKSET (0x0FFF) //4095 |
la00noix | 0:f5992b0c6e00 | 518 | |
yuki0701 | 5:7493649d098b | 519 | void DAC_Write(int16_t data, DigitalOut* DAC_cs) //(出力,出力場所) |
la00noix | 0:f5992b0c6e00 | 520 | { |
la00noix | 0:f5992b0c6e00 | 521 | static uint16_t dataA; //送るデータ |
la00noix | 0:f5992b0c6e00 | 522 | static uint16_t dataB; |
la00noix | 0:f5992b0c6e00 | 523 | |
la00noix | 0:f5992b0c6e00 | 524 | dataA = MCP4922_SET_OUTA; |
la00noix | 0:f5992b0c6e00 | 525 | dataB = MCP4922_SET_OUTB; |
la00noix | 0:f5992b0c6e00 | 526 | |
la00noix | 0:f5992b0c6e00 | 527 | if(data >= 0) { |
la00noix | 0:f5992b0c6e00 | 528 | if(data > 4095) { |
la00noix | 0:f5992b0c6e00 | 529 | data = 4095; |
la00noix | 0:f5992b0c6e00 | 530 | } |
la00noix | 0:f5992b0c6e00 | 531 | dataA += (MCP4922_MASKSET & (uint16_t)(data)); |
la00noix | 0:f5992b0c6e00 | 532 | } else { |
la00noix | 0:f5992b0c6e00 | 533 | if(data < -4095) { |
la00noix | 0:f5992b0c6e00 | 534 | data = -4095; |
la00noix | 0:f5992b0c6e00 | 535 | } |
la00noix | 0:f5992b0c6e00 | 536 | dataB += (MCP4922_MASKSET & (uint16_t)(-data)); |
la00noix | 0:f5992b0c6e00 | 537 | } |
la00noix | 0:f5992b0c6e00 | 538 | |
la00noix | 0:f5992b0c6e00 | 539 | //Aの出力設定 |
la00noix | 0:f5992b0c6e00 | 540 | (DigitalOut)(*DAC_cs)=0; |
la00noix | 0:f5992b0c6e00 | 541 | wait_us(SPI_WAIT_US); |
la00noix | 0:f5992b0c6e00 | 542 | spi.write(dataA); |
la00noix | 0:f5992b0c6e00 | 543 | wait_us(SPI_WAIT_US); |
la00noix | 0:f5992b0c6e00 | 544 | (DigitalOut)(*DAC_cs)=1; |
la00noix | 0:f5992b0c6e00 | 545 | wait_us(SPI_WAIT_US); |
la00noix | 0:f5992b0c6e00 | 546 | |
la00noix | 0:f5992b0c6e00 | 547 | //Bの出力設定 |
la00noix | 0:f5992b0c6e00 | 548 | (DigitalOut)(*DAC_cs)=0; |
la00noix | 0:f5992b0c6e00 | 549 | wait_us(SPI_WAIT_US); |
la00noix | 0:f5992b0c6e00 | 550 | spi.write(dataB); |
la00noix | 0:f5992b0c6e00 | 551 | wait_us(SPI_WAIT_US); |
la00noix | 0:f5992b0c6e00 | 552 | (DigitalOut)(*DAC_cs)=1; |
la00noix | 0:f5992b0c6e00 | 553 | |
la00noix | 0:f5992b0c6e00 | 554 | } |
la00noix | 0:f5992b0c6e00 | 555 | |
yuki0701 | 5:7493649d098b | 556 | void MotorControl(int16_t val_md1, int16_t val_md2, int16_t val_md3, int16_t val_md4) //出力 |
la00noix | 0:f5992b0c6e00 | 557 | { |
la00noix | 0:f5992b0c6e00 | 558 | static int16_t zero_check; |
la00noix | 0:f5992b0c6e00 | 559 | |
la00noix | 0:f5992b0c6e00 | 560 | DAC_Write(val_md1, &ss_md1); |
la00noix | 0:f5992b0c6e00 | 561 | DAC_Write(val_md2, &ss_md2); |
la00noix | 0:f5992b0c6e00 | 562 | DAC_Write(val_md3, &ss_md3); |
la00noix | 0:f5992b0c6e00 | 563 | DAC_Write(val_md4, &ss_md4); |
la00noix | 0:f5992b0c6e00 | 564 | |
la00noix | 0:f5992b0c6e00 | 565 | zero_check = (val_md1 | val_md2 | val_md3 | val_md4); //すべての出力が0なら強制停止 |
la00noix | 0:f5992b0c6e00 | 566 | if(zero_check == 0) { |
la00noix | 0:f5992b0c6e00 | 567 | md_stop = 1; |
la00noix | 0:f5992b0c6e00 | 568 | md_stop_led = 1; |
la00noix | 0:f5992b0c6e00 | 569 | } else { |
la00noix | 0:f5992b0c6e00 | 570 | md_stop = 0; |
la00noix | 0:f5992b0c6e00 | 571 | md_stop_led = 0; |
la00noix | 0:f5992b0c6e00 | 572 | } |
la00noix | 0:f5992b0c6e00 | 573 | } |
la00noix | 0:f5992b0c6e00 | 574 | |
la00noix | 0:f5992b0c6e00 | 575 | #ifdef DEBUG_MODE |
la00noix | 0:f5992b0c6e00 | 576 | void Debug_Control() |
la00noix | 0:f5992b0c6e00 | 577 | { |
la00noix | 0:f5992b0c6e00 | 578 | static char pc_command = '\0'; |
la00noix | 0:f5992b0c6e00 | 579 | |
la00noix | 0:f5992b0c6e00 | 580 | pc_command = pc.getc(); |
la00noix | 0:f5992b0c6e00 | 581 | |
la00noix | 1:86eae1cf26d2 | 582 | if(pc_command == 'w') { //前進 |
la00noix | 0:f5992b0c6e00 | 583 | m1+=500; |
la00noix | 0:f5992b0c6e00 | 584 | m2+=500; |
la00noix | 0:f5992b0c6e00 | 585 | m3-=500; |
la00noix | 0:f5992b0c6e00 | 586 | m4-=500; |
la00noix | 1:86eae1cf26d2 | 587 | } else if(pc_command == 's') { //後進 |
la00noix | 0:f5992b0c6e00 | 588 | m1-=500; |
la00noix | 0:f5992b0c6e00 | 589 | m2-=500; |
la00noix | 0:f5992b0c6e00 | 590 | m3+=500; |
la00noix | 0:f5992b0c6e00 | 591 | m4+=500; |
la00noix | 1:86eae1cf26d2 | 592 | } else if(pc_command == 'd') { //右回り |
la00noix | 0:f5992b0c6e00 | 593 | m1+=500; |
la00noix | 0:f5992b0c6e00 | 594 | m2+=500; |
la00noix | 0:f5992b0c6e00 | 595 | m3+=500; |
la00noix | 0:f5992b0c6e00 | 596 | m4+=500; |
la00noix | 1:86eae1cf26d2 | 597 | } else if(pc_command == 'a') { //左回り |
la00noix | 0:f5992b0c6e00 | 598 | m1-=500; |
la00noix | 0:f5992b0c6e00 | 599 | m2-=500; |
la00noix | 0:f5992b0c6e00 | 600 | m3-=500; |
la00noix | 0:f5992b0c6e00 | 601 | m4-=500; |
la00noix | 0:f5992b0c6e00 | 602 | } else { |
la00noix | 0:f5992b0c6e00 | 603 | m1=0; |
la00noix | 0:f5992b0c6e00 | 604 | m2=0; |
la00noix | 0:f5992b0c6e00 | 605 | m3=0; |
la00noix | 0:f5992b0c6e00 | 606 | m4=0; |
la00noix | 0:f5992b0c6e00 | 607 | } |
la00noix | 0:f5992b0c6e00 | 608 | |
la00noix | 0:f5992b0c6e00 | 609 | if(m1>4095) { //最大値を超えないように |
la00noix | 0:f5992b0c6e00 | 610 | m1=4095; |
la00noix | 0:f5992b0c6e00 | 611 | } else if(m1<-4095) { |
la00noix | 0:f5992b0c6e00 | 612 | m1=-4095; |
la00noix | 0:f5992b0c6e00 | 613 | } |
la00noix | 0:f5992b0c6e00 | 614 | if(m2>4095) { |
la00noix | 0:f5992b0c6e00 | 615 | m2=4095; |
la00noix | 0:f5992b0c6e00 | 616 | } else if(m2<-4095) { |
la00noix | 0:f5992b0c6e00 | 617 | m2=-4095; |
la00noix | 0:f5992b0c6e00 | 618 | } |
la00noix | 0:f5992b0c6e00 | 619 | if(m3>4095) { |
la00noix | 0:f5992b0c6e00 | 620 | m3=4095; |
la00noix | 0:f5992b0c6e00 | 621 | } else if(m3<-4095) { |
la00noix | 0:f5992b0c6e00 | 622 | m3=-4095; |
la00noix | 0:f5992b0c6e00 | 623 | } |
la00noix | 0:f5992b0c6e00 | 624 | if(m4>4095) { |
la00noix | 0:f5992b0c6e00 | 625 | m4=4095; |
la00noix | 0:f5992b0c6e00 | 626 | } else if(m4<-4095) { |
la00noix | 0:f5992b0c6e00 | 627 | m4=-4095; |
la00noix | 0:f5992b0c6e00 | 628 | } |
la00noix | 0:f5992b0c6e00 | 629 | |
la00noix | 0:f5992b0c6e00 | 630 | debug_printf("%d %d %d %d\r\n",m1,m2,m3,m4); |
la00noix | 0:f5992b0c6e00 | 631 | MotorControl(m1,m2,m3,m4); |
la00noix | 0:f5992b0c6e00 | 632 | pc_command = '\0'; |
la00noix | 0:f5992b0c6e00 | 633 | } |
la00noix | 0:f5992b0c6e00 | 634 | #endif |
la00noix | 0:f5992b0c6e00 | 635 | |
la00noix | 0:f5992b0c6e00 | 636 | #ifdef DEBUG_PRINT |
la00noix | 0:f5992b0c6e00 | 637 | void debug_printf(const char* format,...) |
la00noix | 0:f5992b0c6e00 | 638 | { |
la00noix | 0:f5992b0c6e00 | 639 | va_list arg; |
la00noix | 0:f5992b0c6e00 | 640 | va_start(arg, format); |
la00noix | 0:f5992b0c6e00 | 641 | vprintf(format, arg); |
la00noix | 0:f5992b0c6e00 | 642 | va_end(arg); |
la00noix | 0:f5992b0c6e00 | 643 | } |
la00noix | 0:f5992b0c6e00 | 644 | #endif |