春ロボ1班(元F3RC4班+) / Mbed 2 deprecated harurobo_main_ver4

Dependencies:   mbed EC PathFollowing-ver10 CruizCore_R1370P

Committer:
yuki0701
Date:
Sat Dec 01 05:17:16 2018 +0000
Revision:
6:14cb400f99f7
Parent:
5:7493649d098b
Child:
7:e269985951bf
a

Who changed what in which revision?

UserRevisionLine numberNew 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
la00noix 0:f5992b0c6e00 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 3:e696a6dd4254 111 }
yuki0701 3:e696a6dd4254 112
yuki0701 3:e696a6dd4254 113 void calc_xy()
yuki0701 3:e696a6dd4254 114 {
yuki0701 3:e696a6dd4254 115 now_angle=gyro.getAngle(); //ジャイロの値読み込み
yuki0701 3:e696a6dd4254 116
yuki0701 3:e696a6dd4254 117 new_dist1=EC1.getDistance_mm();
yuki0701 3:e696a6dd4254 118 new_dist2=EC2.getDistance_mm();
yuki0701 3:e696a6dd4254 119 d_dist1=new_dist1-old_dist1;
yuki0701 3:e696a6dd4254 120 d_dist2=new_dist2-old_dist2;
yuki0701 3:e696a6dd4254 121 old_dist1=new_dist1;
yuki0701 3:e696a6dd4254 122 old_dist2=new_dist2; //微小時間当たりのエンコーダ読み込み
yuki0701 3:e696a6dd4254 123
yuki0701 3:e696a6dd4254 124 d_x=d_dist2*sin(now_angle*PI/180)-d_dist1*cos(now_angle*PI/180);
yuki0701 3:e696a6dd4254 125 d_y=d_dist2*cos(now_angle*PI/180)+d_dist1*sin(now_angle*PI/180); //微小時間毎の座標変化
yuki0701 3:e696a6dd4254 126 now_x=now_x+d_x;
yuki0701 3:e696a6dd4254 127 now_y=now_y-d_y; //微小時間毎に座標に加算
yuki0701 5:7493649d098b 128
la00noix 0:f5992b0c6e00 129 }
la00noix 0:f5992b0c6e00 130
la00noix 0:f5992b0c6e00 131 //ここからそれぞれのプログラム//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
la00noix 0:f5992b0c6e00 132 //now_x(現在のx座標),now_y(現在のy座標),now_angle(機体角度(ラジアンではない)(0~360や-180~180とは限らない))(反時計回りが正)
la00noix 0:f5992b0c6e00 133 //ジャイロの出力は角度だが三角関数はラジアンとして計算する
la00noix 0:f5992b0c6e00 134 //通常の移動+座標のずれ補正+機体の角度補正(+必要に応じさらに別補正)
la00noix 0:f5992b0c6e00 135 //ジャイロの仕様上、角度補正をするときに計算式内で角度はそのままよりsinをとったほうがいいかもね
la00noix 0:f5992b0c6e00 136
la00noix 0:f5992b0c6e00 137 void purecurve(int type,double X,double Y,double r,int theta,double speed/*,double v*/)
la00noix 0:f5992b0c6e00 138 {
la00noix 0:f5992b0c6e00 139 //正面を変えずに円弧を描いて90°曲がる
la00noix 0:f5992b0c6e00 140 //X=円弧の中心座標、Y=円弧の中心座標、r=円弧の半径、theta=plotの間隔(0~90°)、v=目標速度
la00noix 0:f5992b0c6e00 141
la00noix 0:f5992b0c6e00 142 int s;
yuki0701 3:e696a6dd4254 143 int t = 0;
la00noix 0:f5992b0c6e00 144 double plotx[(90/theta)+1]; //円弧にとるplotのx座標
la00noix 0:f5992b0c6e00 145 double ploty[(90/theta)+1];
la00noix 0:f5992b0c6e00 146 //double plotvx[(90/theta)+1]; //各plotにおける速度
la00noix 0:f5992b0c6e00 147 //double plotvy[(90/theta)+1];
la00noix 0:f5992b0c6e00 148
la00noix 0:f5992b0c6e00 149 double x_out,y_out,r_out;
la00noix 0:f5992b0c6e00 150
la00noix 0:f5992b0c6e00 151 switch(type) {
la00noix 0:f5992b0c6e00 152 case 1://↑から→
la00noix 0:f5992b0c6e00 153
la00noix 0:f5992b0c6e00 154 for(s=0; s<((90/theta)+1); s++) {
yuki0701 3:e696a6dd4254 155 plotx[s] = X + r * cos(PI - s * (PI*theta/180));
la00noix 0:f5992b0c6e00 156 ploty[s] = Y + r * sin(PI - s * (PI*theta/180));
la00noix 0:f5992b0c6e00 157 //plotvx[s] = -v * cos(PI - s * (PI*theta/180));
la00noix 0:f5992b0c6e00 158 //plotvy[s] = v * sin(PI - s * (PI*theta/180));
yuki0701 5:7493649d098b 159 debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
la00noix 0:f5992b0c6e00 160 }
la00noix 0:f5992b0c6e00 161
la00noix 0:f5992b0c6e00 162 while(1) {
la00noix 0:f5992b0c6e00 163 now_angle=gyro.getAngle(); //ジャイロの値読み込み
la00noix 0:f5992b0c6e00 164
yuki0701 3:e696a6dd4254 165 calc_xy();
la00noix 0:f5992b0c6e00 166
yuki0701 6:14cb400f99f7 167 XYRmotorout(1,plotx[t],ploty[t],plotx[t+1],ploty[t+1],&x_out,&y_out,&r_out);
la00noix 0:f5992b0c6e00 168 CalMotorOut(x_out,y_out,r_out); //move4wheel内のモーター番号定義または成分分解が違うかも?
la00noix 0:f5992b0c6e00 169 //CalMotorOut(plotvx[t], plotvy[t],0);
la00noix 0:f5992b0c6e00 170
yuki0701 3:e696a6dd4254 171 //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 172 //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 173
yuki0701 3:e696a6dd4254 174 base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),1000); //m1~m4に代入
la00noix 0:f5992b0c6e00 175
yuki0701 3:e696a6dd4254 176 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 177 if(t == (90/theta))break;
la00noix 2:e04e6b5d6584 178
la00noix 0:f5992b0c6e00 179 MotorControl(m1,m2,m3,m4); //出力
la00noix 2:e04e6b5d6584 180
yuki0701 5:7493649d098b 181 //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 182
la00noix 0:f5992b0c6e00 183 }
la00noix 0:f5992b0c6e00 184
la00noix 0:f5992b0c6e00 185 case 2://↑から← //まだ編集してない
la00noix 0:f5992b0c6e00 186
la00noix 0:f5992b0c6e00 187 for(s=0; s<((90/theta)+1); s++) {
la00noix 0:f5992b0c6e00 188 plotx[s] = X + r * cos(s * (PI*theta/180));
la00noix 0:f5992b0c6e00 189 ploty[s] = Y + r * sin(s * (PI*theta/180));
la00noix 0:f5992b0c6e00 190 }
la00noix 0:f5992b0c6e00 191
la00noix 0:f5992b0c6e00 192 while(1) {
la00noix 0:f5992b0c6e00 193
la00noix 0:f5992b0c6e00 194 now_angle=gyro.getAngle(); //ジャイロの値読み込み
yuki0701 5:7493649d098b 195
yuki0701 3:e696a6dd4254 196 calc_xy();
la00noix 0:f5992b0c6e00 197
yuki0701 6:14cb400f99f7 198 XYRmotorout(1,plotx[t],ploty[t],plotx[t+1],ploty[t+1],&x_out,&y_out,&r_out);
la00noix 0:f5992b0c6e00 199 CalMotorOut(x_out,y_out,r_out);
yuki0701 3:e696a6dd4254 200 base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),1000);
yuki0701 3:e696a6dd4254 201 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 202 if(t == (90/theta))break;
la00noix 0:f5992b0c6e00 203
yuki0701 3:e696a6dd4254 204 MotorControl(m1,m2,m3,m4);
la00noix 0:f5992b0c6e00 205 }
la00noix 0:f5992b0c6e00 206 }
la00noix 0:f5992b0c6e00 207 }
yuki0701 3:e696a6dd4254 208
yuki0701 5:7493649d098b 209 void purecurve2(int type,double point_x1,double point_y1,double point_x2,double point_y2,int theta/*,double speed,double v*/)
yuki0701 5:7493649d098b 210 {
yuki0701 5:7493649d098b 211 //正面を変えずに円弧を描いて90°曲がる
yuki0701 5:7493649d098b 212 //point_x1,point_y1=出発地点の座標 point_x2,point_x2=目標地点の座標,theta=plotの間隔(0~90°)、v=目標速度
yuki0701 5:7493649d098b 213 //type:動きの種類(8パターン)
yuki0701 5:7493649d098b 214
yuki0701 5:7493649d098b 215 int s;
yuki0701 5:7493649d098b 216 int t = 0;
yuki0701 5:7493649d098b 217 double X,Y;//X=楕円の中心座標、Y=楕円の中心座標
yuki0701 5:7493649d098b 218 double a,b; //a=楕円のx軸方向の幅の半分,b=楕円のy軸方向の幅の半分
yuki0701 5:7493649d098b 219 double plotx[(90/theta)+1]; //楕円にとるplotのx座標
yuki0701 5:7493649d098b 220 double ploty[(90/theta)+1];
yuki0701 5:7493649d098b 221 //double plotvx[(90/theta)+1]; //各plotにおける速度
yuki0701 5:7493649d098b 222 //double plotvy[(90/theta)+1];
yuki0701 5:7493649d098b 223 double x_out,y_out,r_out;
yuki0701 5:7493649d098b 224
yuki0701 5:7493649d098b 225 a=fabs(point_x1-point_x2);
yuki0701 5:7493649d098b 226 b=fabs(point_y1-point_y2);
yuki0701 5:7493649d098b 227
yuki0701 5:7493649d098b 228 switch(type) {
yuki0701 5:7493649d098b 229
yuki0701 5:7493649d098b 230 case 1://→↑移動
yuki0701 5:7493649d098b 231 X=point_x1;
yuki0701 5:7493649d098b 232 Y=point_y2;
yuki0701 5:7493649d098b 233
yuki0701 5:7493649d098b 234 for(s=0; s<((90/theta)+1); s++) {
yuki0701 5:7493649d098b 235 plotx[s] = X + a * cos(-PI/2 + s * (PI*theta/180));
yuki0701 5:7493649d098b 236 ploty[s] = Y + b * sin(-PI/2 + s * (PI*theta/180));
yuki0701 5:7493649d098b 237 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 5:7493649d098b 238 }
yuki0701 5:7493649d098b 239 break;
yuki0701 5:7493649d098b 240
yuki0701 5:7493649d098b 241 case 2://↑→移動
yuki0701 5:7493649d098b 242 X=point_x2;
yuki0701 5:7493649d098b 243 Y=point_y1;
yuki0701 5:7493649d098b 244
yuki0701 5:7493649d098b 245 for(s=0; s<((90/theta)+1); s++) {
yuki0701 5:7493649d098b 246 plotx[s] = X + a * cos(PI - s * (PI*theta/180));
yuki0701 5:7493649d098b 247 ploty[s] = Y + b * sin(PI - s * (PI*theta/180));
yuki0701 5:7493649d098b 248 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 5:7493649d098b 249 }
yuki0701 5:7493649d098b 250 break;
yuki0701 5:7493649d098b 251
yuki0701 5:7493649d098b 252 case 3://↑←移動
yuki0701 5:7493649d098b 253 X=point_x2;
yuki0701 5:7493649d098b 254 Y=point_y1;
yuki0701 5:7493649d098b 255
yuki0701 5:7493649d098b 256 for(s=0; s<((90/theta)+1); s++) {
yuki0701 5:7493649d098b 257 plotx[s] = X + a * cos(s * (PI*theta/180));
yuki0701 5:7493649d098b 258 ploty[s] = Y + b * sin(s * (PI*theta/180));
yuki0701 5:7493649d098b 259 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 5:7493649d098b 260 }
yuki0701 5:7493649d098b 261 break;
yuki0701 5:7493649d098b 262
yuki0701 5:7493649d098b 263 case 4://←↑移動
yuki0701 5:7493649d098b 264 X=point_x1;
yuki0701 5:7493649d098b 265 Y=point_y2;
yuki0701 5:7493649d098b 266
yuki0701 5:7493649d098b 267 for(s=0; s<((90/theta)+1); s++) {
yuki0701 5:7493649d098b 268 plotx[s] = X + a * cos(-PI/2 - s * (PI*theta/180));
yuki0701 5:7493649d098b 269 ploty[s] = Y + b * sin(-PI/2 - s * (PI*theta/180));
yuki0701 5:7493649d098b 270 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 5:7493649d098b 271 }
yuki0701 5:7493649d098b 272 break;
yuki0701 5:7493649d098b 273
yuki0701 5:7493649d098b 274 case 5://←↓移動
yuki0701 5:7493649d098b 275 X=point_x1;
yuki0701 5:7493649d098b 276 Y=point_y2;
yuki0701 5:7493649d098b 277
yuki0701 5:7493649d098b 278 for(s=0; s<((90/theta)+1); s++) {
yuki0701 5:7493649d098b 279 plotx[s] = X + a * cos(PI/2 + s * (PI*theta/180));
yuki0701 5:7493649d098b 280 ploty[s] = Y + b * sin(PI/2 + s * (PI*theta/180));
yuki0701 5:7493649d098b 281 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 5:7493649d098b 282 }
yuki0701 5:7493649d098b 283 break;
yuki0701 5:7493649d098b 284
yuki0701 5:7493649d098b 285 case 6://↓←移動
yuki0701 5:7493649d098b 286 X=point_x2;
yuki0701 5:7493649d098b 287 Y=point_y1;
yuki0701 5:7493649d098b 288
yuki0701 5:7493649d098b 289 for(s=0; s<((90/theta)+1); s++) {
yuki0701 5:7493649d098b 290 plotx[s] = X + a * cos(-s * (PI*theta/180));
yuki0701 5:7493649d098b 291 ploty[s] = Y + b * sin(-s * (PI*theta/180));
yuki0701 5:7493649d098b 292 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 5:7493649d098b 293 }
yuki0701 5:7493649d098b 294 break;
yuki0701 5:7493649d098b 295
yuki0701 5:7493649d098b 296 case 7://↓→移動
yuki0701 5:7493649d098b 297 X=point_x2;
yuki0701 5:7493649d098b 298 Y=point_y1;
yuki0701 5:7493649d098b 299
yuki0701 5:7493649d098b 300 for(s=0; s<((90/theta)+1); s++) {
yuki0701 5:7493649d098b 301 plotx[s] = X + a * cos(PI + s * (PI*theta/180));
yuki0701 5:7493649d098b 302 ploty[s] = Y + b * sin(PI + s * (PI*theta/180));
yuki0701 5:7493649d098b 303 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 5:7493649d098b 304 }
yuki0701 5:7493649d098b 305 break;
yuki0701 5:7493649d098b 306
yuki0701 5:7493649d098b 307 case 8://→↓移動
yuki0701 5:7493649d098b 308 X=point_x1;
yuki0701 5:7493649d098b 309 Y=point_y2;
yuki0701 5:7493649d098b 310
yuki0701 5:7493649d098b 311 for(s=0; s<((90/theta)+1); s++) {
yuki0701 5:7493649d098b 312 plotx[s] = X + a * cos(PI/2 - s * (PI*theta/180));
yuki0701 5:7493649d098b 313 ploty[s] = Y + b * sin(PI/2 - s * (PI*theta/180));
yuki0701 5:7493649d098b 314 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 5:7493649d098b 315 }
yuki0701 5:7493649d098b 316 break;
yuki0701 5:7493649d098b 317 }
yuki0701 5:7493649d098b 318
yuki0701 5:7493649d098b 319 while(1) {
yuki0701 6:14cb400f99f7 320 //now_angle=gyro.getAngle(); //ジャイロの値読み込み
yuki0701 5:7493649d098b 321
yuki0701 5:7493649d098b 322 calc_xy();
yuki0701 5:7493649d098b 323
yuki0701 6:14cb400f99f7 324 XYRmotorout(1,plotx[t],ploty[t],plotx[t+1],ploty[t+1],&x_out,&y_out,&r_out);
yuki0701 5:7493649d098b 325 CalMotorOut(x_out,y_out,r_out); //move4wheel内のモーター番号定義または成分分解が違うかも?
yuki0701 5:7493649d098b 326 //CalMotorOut(plotvx[t], plotvy[t],0);
yuki0701 5:7493649d098b 327
yuki0701 5:7493649d098b 328 //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 329 //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 330
yuki0701 5:7493649d098b 331 base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),1000); //m1~m4に代入
yuki0701 5:7493649d098b 332
yuki0701 5:7493649d098b 333 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 334 if(t == (90/theta))break;
yuki0701 5:7493649d098b 335
yuki0701 5:7493649d098b 336 MotorControl(m1,m2,m3,m4); //出力
yuki0701 5:7493649d098b 337
yuki0701 5:7493649d098b 338 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 339
yuki0701 5:7493649d098b 340 }
yuki0701 5:7493649d098b 341 }
yuki0701 5:7493649d098b 342
yuki0701 5:7493649d098b 343
yuki0701 5:7493649d098b 344
yuki0701 5:7493649d098b 345
yuki0701 6:14cb400f99f7 346 void gogo_straight(int type, double x1_point,double y1_point,double x2_point,double y2_point) //直線運動プログラム(引数:type→(1:減速なし/2:減速あり)、出発地点の座標(x,y)、目標地点の座標(x,y))
yuki0701 3:e696a6dd4254 347 {
yuki0701 3:e696a6dd4254 348 while (1) {
yuki0701 3:e696a6dd4254 349
yuki0701 3:e696a6dd4254 350 //now_angle=gyro.getAngle();
yuki0701 3:e696a6dd4254 351
yuki0701 3:e696a6dd4254 352 calc_xy();
yuki0701 3:e696a6dd4254 353 printf("x = %f, y = %f, angle = %f\r\n",now_x,now_y,now_angle);
yuki0701 3:e696a6dd4254 354
yuki0701 3:e696a6dd4254 355
yuki0701 3:e696a6dd4254 356 //Debug_Control();
yuki0701 6:14cb400f99f7 357 XYRmotorout(type,x1_point,y1_point,x2_point,y2_point,&x_out,&y_out,&r_out);
yuki0701 3:e696a6dd4254 358 //printf("x=%lf, y=%lf, r=%lf",x_out, y_out,r_out);
yuki0701 3:e696a6dd4254 359
yuki0701 3:e696a6dd4254 360 CalMotorOut(x_out,y_out,r_out);
yuki0701 3:e696a6dd4254 361 //printf("out1=%lf, out2=%lf, out3=%lf, out4=%lf\n",GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3));
yuki0701 3:e696a6dd4254 362
yuki0701 3:e696a6dd4254 363 base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),1000);
yuki0701 3:e696a6dd4254 364 //printf("m1=%d, m2=%d, m3=%d, m4=%d\r\n",m1,m2,m3,m4);
yuki0701 3:e696a6dd4254 365 MotorControl(m1,m2,m3,m4);
yuki0701 5:7493649d098b 366
yuki0701 5:7493649d098b 367
yuki0701 3:e696a6dd4254 368
yuki0701 3:e696a6dd4254 369 if(((x2_point - now_x)*(x2_point - x1_point) + (y2_point - now_y)*(y2_point - y1_point)) < 0) break;
yuki0701 3:e696a6dd4254 370
yuki0701 3:e696a6dd4254 371 }
yuki0701 3:e696a6dd4254 372
yuki0701 3:e696a6dd4254 373 MotorControl(0,0,0,0);
yuki0701 3:e696a6dd4254 374 }
yuki0701 3:e696a6dd4254 375
yuki0701 5:7493649d098b 376 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 377 {
yuki0701 3:e696a6dd4254 378 double y_hosei=(now_y-goal_y)*0.001;//Y座標(mm単位)にP処理
yuki0701 3:e696a6dd4254 379 double x_hosei=(now_x-goal_x)*0.001;//X座標(mm単位)にP処理
yuki0701 3:e696a6dd4254 380 double incl_hosei=sin(now_angle-front)*(PI/180)*0.1;//機体角度(sin(数度→ラジアンに変換))にP処理
yuki0701 3:e696a6dd4254 381
yuki0701 3:e696a6dd4254 382 switch(type) {
yuki0701 3:e696a6dd4254 383 case 1://Y座標一定の正方向横移動
yuki0701 5:7493649d098b 384 while(now_x<goal_x) {
yuki0701 5:7493649d098b 385 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 386 }
yuki0701 3:e696a6dd4254 387 break;
yuki0701 5:7493649d098b 388
yuki0701 3:e696a6dd4254 389 case 2://Y座標一定の負方向横移動
yuki0701 5:7493649d098b 390 while(now_x>goal_x) {
yuki0701 5:7493649d098b 391 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 392 }
yuki0701 3:e696a6dd4254 393 break;
yuki0701 5:7493649d098b 394
yuki0701 3:e696a6dd4254 395 case 3://Y座標一定の正方向横移動
yuki0701 5:7493649d098b 396 while(now_y<goal_y) {
yuki0701 5:7493649d098b 397 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 398 }
yuki0701 3:e696a6dd4254 399 break;
yuki0701 5:7493649d098b 400
yuki0701 3:e696a6dd4254 401 case 4://X座標一定の負方向横移動
yuki0701 5:7493649d098b 402 while(now_y>goal_y) {
yuki0701 5:7493649d098b 403 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 404 }
yuki0701 3:e696a6dd4254 405 break;
yuki0701 3:e696a6dd4254 406 }
yuki0701 3:e696a6dd4254 407 }
yuki0701 3:e696a6dd4254 408
yuki0701 6:14cb400f99f7 409
yuki0701 6:14cb400f99f7 410
yuki0701 3:e696a6dd4254 411 //////////////////////////////////////////////////////////////以下main文////////////////////////////////////////////////////////////////////////
la00noix 0:f5992b0c6e00 412
la00noix 0:f5992b0c6e00 413 int main()
la00noix 0:f5992b0c6e00 414 {
la00noix 0:f5992b0c6e00 415 UserLoopSetting();
la00noix 0:f5992b0c6e00 416
yuki0701 3:e696a6dd4254 417 void reset();
la00noix 0:f5992b0c6e00 418 EC1.reset();
yuki0701 3:e696a6dd4254 419 EC2.reset();
la00noix 0:f5992b0c6e00 420
la00noix 0:f5992b0c6e00 421 now_x=start_x;
la00noix 0:f5992b0c6e00 422 now_y=start_y;
yuki0701 5:7493649d098b 423
yuki0701 6:14cb400f99f7 424 /*set_target_angle(0);
yuki0701 6:14cb400f99f7 425 purecurve2(1,0,0,1000,1000,9);
yuki0701 6:14cb400f99f7 426 MotorControl(0,0,0,0);*/
yuki0701 6:14cb400f99f7 427
yuki0701 6:14cb400f99f7 428 /* set_target_angle(0);
yuki0701 6:14cb400f99f7 429 while(1){
yuki0701 6:14cb400f99f7 430 purecurve2(7,0,0,500,-500,9);
yuki0701 6:14cb400f99f7 431 MotorControl(0,0,0,0);
yuki0701 6:14cb400f99f7 432 purecurve2(1,500,-500,1000,0,9);
yuki0701 6:14cb400f99f7 433 MotorControl(0,0,0,0);
yuki0701 6:14cb400f99f7 434 purecurve2(3,1000,0,500,500,9);
yuki0701 6:14cb400f99f7 435 MotorControl(0,0,0,0);
yuki0701 6:14cb400f99f7 436 purecurve2(5,500,500,0,0,9);
yuki0701 6:14cb400f99f7 437 MotorControl(0,0,0,0);
yuki0701 6:14cb400f99f7 438 }*/
yuki0701 5:7493649d098b 439
yuki0701 6:14cb400f99f7 440 int a=0;
yuki0701 6:14cb400f99f7 441 while(1) {
yuki0701 6:14cb400f99f7 442 set_target_angle(a);
yuki0701 6:14cb400f99f7 443 gogo_straight(2,0,0,0,-1500);
yuki0701 6:14cb400f99f7 444 MotorControl(0,0,0,0);
yuki0701 6:14cb400f99f7 445 wait(1);
yuki0701 5:7493649d098b 446
yuki0701 6:14cb400f99f7 447 a=a+90;
yuki0701 6:14cb400f99f7 448
yuki0701 6:14cb400f99f7 449 set_target_angle(a);
yuki0701 6:14cb400f99f7 450 gogo_straight(2,0,-1500,0,0);
yuki0701 6:14cb400f99f7 451 MotorControl(0,0,0,0);
yuki0701 6:14cb400f99f7 452 wait(1);
yuki0701 6:14cb400f99f7 453
yuki0701 6:14cb400f99f7 454 a=a+90;
yuki0701 6:14cb400f99f7 455
yuki0701 6:14cb400f99f7 456 }
la00noix 0:f5992b0c6e00 457
la00noix 0:f5992b0c6e00 458 }
yuki0701 3:e696a6dd4254 459 ///////////////////////////////////////////////////////////////////////以下マクソン関連///////////////////////////////////////////////////////////////////////////
la00noix 0:f5992b0c6e00 460
la00noix 0:f5992b0c6e00 461 void UserLoopSetting()
la00noix 0:f5992b0c6e00 462 {
la00noix 0:f5992b0c6e00 463 //-----エスコンの初期設定-----//
la00noix 0:f5992b0c6e00 464 spi.format(SPI_BITS, SPI_MODE);
la00noix 0:f5992b0c6e00 465 spi.frequency(SPI_FREQ);
la00noix 0:f5992b0c6e00 466 ss_md1 = 1;
la00noix 0:f5992b0c6e00 467 ss_md2 = 1;
la00noix 0:f5992b0c6e00 468 ss_md3 = 1;
la00noix 0:f5992b0c6e00 469 ss_md4 = 1;
la00noix 0:f5992b0c6e00 470 md_enable = 1; //enable on
la00noix 0:f5992b0c6e00 471 md_err_led = 0;
la00noix 0:f5992b0c6e00 472 md_stop = 1;
la00noix 0:f5992b0c6e00 473 md_stop_led = 1;
la00noix 0:f5992b0c6e00 474 //-----センサーの初期設定-----//
la00noix 0:f5992b0c6e00 475 gyro.initialize();
la00noix 0:f5992b0c6e00 476 motor_tick.attach(&calOmega,0.05); //0.05秒間隔で角速度を計算
la00noix 0:f5992b0c6e00 477 EC1.setDiameter_mm(48);
la00noix 0:f5992b0c6e00 478 EC2.setDiameter_mm(48); //測定輪半径
la00noix 0:f5992b0c6e00 479 //-----PathFollowingのパラメーター設定-----//
yuki0701 3:e696a6dd4254 480 set_p_out(800); //ベクトルABに平行方向の出力値設定関数(カーブを曲がる速度)
yuki0701 6:14cb400f99f7 481 q_setPDparam(5,0.1); //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数
yuki0701 3:e696a6dd4254 482 r_setPDparam(10,0.1); //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数
yuki0701 6:14cb400f99f7 483 set_r_out(600); //旋回時の最大出力値設定関数
yuki0701 5:7493649d098b 484 // set_target_angle(0); //機体目標角度設定関数
la00noix 0:f5992b0c6e00 485
la00noix 0:f5992b0c6e00 486 #ifdef DEBUG_MODE
la00noix 0:f5992b0c6e00 487 debug_led = 1;
la00noix 0:f5992b0c6e00 488 pc.attach(Debug_Control, Serial::RxIrq);
la00noix 0:f5992b0c6e00 489 #else
la00noix 0:f5992b0c6e00 490 debug_led = 0;
la00noix 0:f5992b0c6e00 491 #endif
la00noix 0:f5992b0c6e00 492 }
la00noix 0:f5992b0c6e00 493
la00noix 0:f5992b0c6e00 494 #define MCP4922_AB (1<<15)
la00noix 0:f5992b0c6e00 495 #define MCP4922_BUF (1<<14)
la00noix 0:f5992b0c6e00 496 #define MCP4922_GA (1<<13)
la00noix 0:f5992b0c6e00 497 #define MCP4922_SHDN (1<<12)
la00noix 0:f5992b0c6e00 498
la00noix 0:f5992b0c6e00 499 #define MCP4922_SET_OUTA (0x3000) //( MCP4922_GA || MCP4922_SHDN ) //12288
la00noix 0:f5992b0c6e00 500 #define MCP4922_SET_OUTB (0xB000) //( MCP4922_AB || MCP4922_GA || MCP4922_SHDN ) //45056
la00noix 0:f5992b0c6e00 501 #define MCP4922_MASKSET (0x0FFF) //4095
la00noix 0:f5992b0c6e00 502
yuki0701 5:7493649d098b 503 void DAC_Write(int16_t data, DigitalOut* DAC_cs) //(出力,出力場所)
la00noix 0:f5992b0c6e00 504 {
la00noix 0:f5992b0c6e00 505 static uint16_t dataA; //送るデータ
la00noix 0:f5992b0c6e00 506 static uint16_t dataB;
la00noix 0:f5992b0c6e00 507
la00noix 0:f5992b0c6e00 508 dataA = MCP4922_SET_OUTA;
la00noix 0:f5992b0c6e00 509 dataB = MCP4922_SET_OUTB;
la00noix 0:f5992b0c6e00 510
la00noix 0:f5992b0c6e00 511 if(data >= 0) {
la00noix 0:f5992b0c6e00 512 if(data > 4095) {
la00noix 0:f5992b0c6e00 513 data = 4095;
la00noix 0:f5992b0c6e00 514 }
la00noix 0:f5992b0c6e00 515 dataA += (MCP4922_MASKSET & (uint16_t)(data));
la00noix 0:f5992b0c6e00 516 } else {
la00noix 0:f5992b0c6e00 517 if(data < -4095) {
la00noix 0:f5992b0c6e00 518 data = -4095;
la00noix 0:f5992b0c6e00 519 }
la00noix 0:f5992b0c6e00 520 dataB += (MCP4922_MASKSET & (uint16_t)(-data));
la00noix 0:f5992b0c6e00 521 }
la00noix 0:f5992b0c6e00 522
la00noix 0:f5992b0c6e00 523 //Aの出力設定
la00noix 0:f5992b0c6e00 524 (DigitalOut)(*DAC_cs)=0;
la00noix 0:f5992b0c6e00 525 wait_us(SPI_WAIT_US);
la00noix 0:f5992b0c6e00 526 spi.write(dataA);
la00noix 0:f5992b0c6e00 527 wait_us(SPI_WAIT_US);
la00noix 0:f5992b0c6e00 528 (DigitalOut)(*DAC_cs)=1;
la00noix 0:f5992b0c6e00 529 wait_us(SPI_WAIT_US);
la00noix 0:f5992b0c6e00 530
la00noix 0:f5992b0c6e00 531 //Bの出力設定
la00noix 0:f5992b0c6e00 532 (DigitalOut)(*DAC_cs)=0;
la00noix 0:f5992b0c6e00 533 wait_us(SPI_WAIT_US);
la00noix 0:f5992b0c6e00 534 spi.write(dataB);
la00noix 0:f5992b0c6e00 535 wait_us(SPI_WAIT_US);
la00noix 0:f5992b0c6e00 536 (DigitalOut)(*DAC_cs)=1;
la00noix 0:f5992b0c6e00 537
la00noix 0:f5992b0c6e00 538 }
la00noix 0:f5992b0c6e00 539
yuki0701 5:7493649d098b 540 void MotorControl(int16_t val_md1, int16_t val_md2, int16_t val_md3, int16_t val_md4) //出力
la00noix 0:f5992b0c6e00 541 {
la00noix 0:f5992b0c6e00 542 static int16_t zero_check;
la00noix 0:f5992b0c6e00 543
la00noix 0:f5992b0c6e00 544 DAC_Write(val_md1, &ss_md1);
la00noix 0:f5992b0c6e00 545 DAC_Write(val_md2, &ss_md2);
la00noix 0:f5992b0c6e00 546 DAC_Write(val_md3, &ss_md3);
la00noix 0:f5992b0c6e00 547 DAC_Write(val_md4, &ss_md4);
la00noix 0:f5992b0c6e00 548
la00noix 0:f5992b0c6e00 549 zero_check = (val_md1 | val_md2 | val_md3 | val_md4); //すべての出力が0なら強制停止
la00noix 0:f5992b0c6e00 550 if(zero_check == 0) {
la00noix 0:f5992b0c6e00 551 md_stop = 1;
la00noix 0:f5992b0c6e00 552 md_stop_led = 1;
la00noix 0:f5992b0c6e00 553 } else {
la00noix 0:f5992b0c6e00 554 md_stop = 0;
la00noix 0:f5992b0c6e00 555 md_stop_led = 0;
la00noix 0:f5992b0c6e00 556 }
la00noix 0:f5992b0c6e00 557 }
la00noix 0:f5992b0c6e00 558
la00noix 0:f5992b0c6e00 559 #ifdef DEBUG_MODE
la00noix 0:f5992b0c6e00 560 void Debug_Control()
la00noix 0:f5992b0c6e00 561 {
la00noix 0:f5992b0c6e00 562 static char pc_command = '\0';
la00noix 0:f5992b0c6e00 563
la00noix 0:f5992b0c6e00 564 pc_command = pc.getc();
la00noix 0:f5992b0c6e00 565
la00noix 1:86eae1cf26d2 566 if(pc_command == 'w') { //前進
la00noix 0:f5992b0c6e00 567 m1+=500;
la00noix 0:f5992b0c6e00 568 m2+=500;
la00noix 0:f5992b0c6e00 569 m3-=500;
la00noix 0:f5992b0c6e00 570 m4-=500;
la00noix 1:86eae1cf26d2 571 } else if(pc_command == 's') { //後進
la00noix 0:f5992b0c6e00 572 m1-=500;
la00noix 0:f5992b0c6e00 573 m2-=500;
la00noix 0:f5992b0c6e00 574 m3+=500;
la00noix 0:f5992b0c6e00 575 m4+=500;
la00noix 1:86eae1cf26d2 576 } else if(pc_command == 'd') { //右回り
la00noix 0:f5992b0c6e00 577 m1+=500;
la00noix 0:f5992b0c6e00 578 m2+=500;
la00noix 0:f5992b0c6e00 579 m3+=500;
la00noix 0:f5992b0c6e00 580 m4+=500;
la00noix 1:86eae1cf26d2 581 } else if(pc_command == 'a') { //左回り
la00noix 0:f5992b0c6e00 582 m1-=500;
la00noix 0:f5992b0c6e00 583 m2-=500;
la00noix 0:f5992b0c6e00 584 m3-=500;
la00noix 0:f5992b0c6e00 585 m4-=500;
la00noix 0:f5992b0c6e00 586 } else {
la00noix 0:f5992b0c6e00 587 m1=0;
la00noix 0:f5992b0c6e00 588 m2=0;
la00noix 0:f5992b0c6e00 589 m3=0;
la00noix 0:f5992b0c6e00 590 m4=0;
la00noix 0:f5992b0c6e00 591 }
la00noix 0:f5992b0c6e00 592
la00noix 0:f5992b0c6e00 593 if(m1>4095) { //最大値を超えないように
la00noix 0:f5992b0c6e00 594 m1=4095;
la00noix 0:f5992b0c6e00 595 } else if(m1<-4095) {
la00noix 0:f5992b0c6e00 596 m1=-4095;
la00noix 0:f5992b0c6e00 597 }
la00noix 0:f5992b0c6e00 598 if(m2>4095) {
la00noix 0:f5992b0c6e00 599 m2=4095;
la00noix 0:f5992b0c6e00 600 } else if(m2<-4095) {
la00noix 0:f5992b0c6e00 601 m2=-4095;
la00noix 0:f5992b0c6e00 602 }
la00noix 0:f5992b0c6e00 603 if(m3>4095) {
la00noix 0:f5992b0c6e00 604 m3=4095;
la00noix 0:f5992b0c6e00 605 } else if(m3<-4095) {
la00noix 0:f5992b0c6e00 606 m3=-4095;
la00noix 0:f5992b0c6e00 607 }
la00noix 0:f5992b0c6e00 608 if(m4>4095) {
la00noix 0:f5992b0c6e00 609 m4=4095;
la00noix 0:f5992b0c6e00 610 } else if(m4<-4095) {
la00noix 0:f5992b0c6e00 611 m4=-4095;
la00noix 0:f5992b0c6e00 612 }
la00noix 0:f5992b0c6e00 613
la00noix 0:f5992b0c6e00 614 debug_printf("%d %d %d %d\r\n",m1,m2,m3,m4);
la00noix 0:f5992b0c6e00 615 MotorControl(m1,m2,m3,m4);
la00noix 0:f5992b0c6e00 616 pc_command = '\0';
la00noix 0:f5992b0c6e00 617 }
la00noix 0:f5992b0c6e00 618 #endif
la00noix 0:f5992b0c6e00 619
la00noix 0:f5992b0c6e00 620 #ifdef DEBUG_PRINT
la00noix 0:f5992b0c6e00 621 void debug_printf(const char* format,...)
la00noix 0:f5992b0c6e00 622 {
la00noix 0:f5992b0c6e00 623 va_list arg;
la00noix 0:f5992b0c6e00 624 va_start(arg, format);
la00noix 0:f5992b0c6e00 625 vprintf(format, arg);
la00noix 0:f5992b0c6e00 626 va_end(arg);
la00noix 0:f5992b0c6e00 627 }
la00noix 0:f5992b0c6e00 628 #endif