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

Dependencies:   mbed move4wheel2 EC CruizCore_R1370P

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers movement.cpp Source File

movement.cpp

00001 #include "EC.h"
00002 #include "R1370P.h"
00003 #include "move4wheel.h"
00004 #include "mbed.h"
00005 #include "math.h"
00006 #include "PathFollowing.h"
00007 #include "movement.h"
00008 #include "maxonsetting.h"
00009 #include "manual.h"
00010 #include "can.h"
00011 
00012 #define PI 3.141592
00013 
00014 char can_ashileddata[2]= {0};
00015 int can_ashileddata0_0,can_ashileddata0_1,can_ashileddata0_2,can_ashileddata0_3;
00016 
00017 Ec EC1(p22,p21,NC,500,0.05);
00018 Ec EC2(p26,p8,NC,500,0.05);
00019 
00020 Ticker ec_ticker;  //ec角速度計算用ticker
00021 
00022 R1370P gyro(p28,p27);
00023 
00024 double new_dist1=0,new_dist2=0;
00025 double old_dist1=0,old_dist2=0;
00026 double d_dist1=0,d_dist2=0;  //座標計算用関数
00027 double d_x,d_y;
00028 //現在地X,y座標、現在角度については、PathFollowingでnow_x,now_y,now_angleを定義済
00029 double start_x=0,start_y=0;  //スタート位置
00030 double x_out,y_out,r_out;  //出力値
00031 
00032 int16_t m1=0, m2=0, m3=0, m4=0;  //int16bit = int2byte
00033 
00034 double xy_type,pm_typeX,pm_typeY,x_base,y_base;
00035 
00036 ///////////////////機体情報をメンバとする構造体"robo_data"と構造体型変数info(←この変数に各センサーにより求めた機体情報(機体位置/機体角度)を格納する)の宣言/////////////////
00037 
00038 /*「info.(機体情報の種類).(使用センサーの種類)」に各情報を格納する
00039  *状況に応じて、どのセンサーにより算出した情報を信用するかを選択し、その都度now_angle,now_x,now_yに代入する。(何種類かのセンサーの情報を混ぜて使用することも可能)
00040  *(ex)
00041  *info.nowX.enc → エンコーダにより算出した機体位置のx座標
00042  *info.nowY.usw → 超音波センサーにより求めた機体位置のy座標
00043 */
00044 
00045 typedef struct { //使用センサーの種類
00046     double usw;  //超音波センサー
00047     double enc;  //エンコーダ
00048     double gyro; //ジャイロ
00049     //double line;//ラインセンサー
00050 } robo_sensor;
00051 
00052 typedef struct { //機体情報の種類
00053     robo_sensor angle; //←機体角度は超音波センサーやラインセンサーからも算出可能なので一応格納先を用意したが、ジャイロの値を完全に信用してもいいかも
00054     robo_sensor nowX;
00055     robo_sensor nowY;
00056 } robo_data;
00057 
00058 robo_data info= {{0,0,0},{0,0,0},{0,0,0}}; //全てのデータを0に初期化
00059 
00060 ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
00061 
00062 void UserLoopSetting_sensor()
00063 {
00064 
00065     gyro.initialize();
00066     ec_ticker.attach(&calOmega,0.05);  //0.05秒間隔で角速度を計算
00067     EC1.setDiameter_mm(25.5);
00068     EC2.setDiameter_mm(25.5);  //測定輪半径//後で測定
00069     info.nowX.enc = -2962; //初期位置の設定
00070     info.nowY.enc = 3500;
00071 }
00072 
00073 void calOmega()  //角速度計算関数
00074 {
00075     EC1.CalOmega();
00076     EC2.CalOmega();
00077 }
00078 
00079 void output(double FL,double BL,double BR,double FR)
00080 {
00081     m1=FL;
00082     m2=BL;
00083     m3=BR;
00084     m4=FR;
00085 }
00086 
00087 void base(double FL,double BL,double BR,double FR,double Max)
00088 //いろんな加算をしても最大OR最小がMaxになるような補正//絶対値が一番でかいやつで除算
00089 //DCモーターならMax=1、マクソンは-4095~4095だからMax=4095にする
00090 {
00091     if(fabs(FL)>=Max||fabs(BL)>=Max||fabs(BR)>=Max||fabs(FR)>=Max) {
00092 
00093         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));
00094         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));
00095         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));
00096         else                                                               output(Max*FL/fabs(FR),Max*BL/fabs(FR),Max*BR/fabs(FR),Max*FR/fabs(FR));
00097     } else {
00098         output(FL,BL,BR,FR);
00099     }
00100 }
00101 
00102 void ashi_led()
00103 {
00104 
00105     if(now_angle > -1 && now_angle < 1) {
00106         can_ashileddata0_0 = 1;
00107     } else {
00108         can_ashileddata0_0 = 0;
00109     }
00110 
00111     if(now_angle > 350) {
00112         can_ashileddata0_1 = 1;
00113     } else {
00114         can_ashileddata0_1 = 0;
00115     }
00116 
00117     if(now_x > -1 && now_x < 1) {
00118         can_ashileddata0_2 = 1;
00119     } else {
00120         can_ashileddata0_2 = 0;
00121     }
00122 
00123     if(now_y > -1 && now_y < 1) {
00124         can_ashileddata0_3 = 1;
00125     } else {
00126         can_ashileddata0_3 = 0;
00127     }
00128 
00129     can_ashileddata[0] = (can_ashileddata0_0<<7 | can_ashileddata0_1<<6 | can_ashileddata0_2<<5 | can_ashileddata0_3<<4);
00130 }
00131 
00132 void calc_gyro()
00133 {
00134     now_angle=gyro.getAngle();  //ジャイロの値読み込み
00135 }
00136 
00137 void calc_xy_enc()  //エンコーダ&ジャイロによる座標計算
00138 {
00139     now_angle=gyro.getAngle();  //ジャイロの値読み込み
00140 
00141     new_dist1=EC1.getDistance_mm();
00142     new_dist2=EC2.getDistance_mm();
00143     d_dist1=new_dist1-old_dist1;
00144     d_dist2=new_dist2-old_dist2;
00145     old_dist1=new_dist1;
00146     old_dist2=new_dist2;  //微小時間当たりのエンコーダ読み込み
00147 
00148     d_x=d_dist2*sin(now_angle*PI/180)-d_dist1*cos(now_angle*PI/180);
00149     d_y=d_dist2*cos(now_angle*PI/180)+d_dist1*sin(now_angle*PI/180);  //微小時間毎の座標変化
00150     info.nowX.enc = info.nowX.enc + d_x;
00151     info.nowY.enc = info.nowY.enc - d_y;  //微小時間毎に座標に加算
00152 }
00153 
00154 void set_cond(int t, int px, double bx, int py, double by)   //超音波センサーを使用するときの条件設定関数
00155 {
00156 //引数の詳細は関数"calc_xy_usw"参照
00157 
00158     xy_type = t;
00159 
00160     pm_typeX = px;
00161     x_base = bx;
00162 
00163     pm_typeY = py;
00164     y_base = by;
00165 }
00166 
00167 void calc_xy_usw(double tgt_angle)   //超音波センサーによる座標計算(機体が旋回する場合はこの方法による座標計算は出来ない)
00168 {
00169 //tgt_angle:機体の目標角度(運動初期角度と同じ/今大会では0,90,180のみ)
00170 //xy_type:(0:Y軸平行の壁を読む/1:X軸平行の壁を読む/2:X,Y軸平行の壁を共に読む)
00171 //pm_typeX,pm_typeY:(0:各軸正方向側の壁を読む/1:各軸負方向側の壁を読む)
00172 //x_base,y_base:超音波センサーで読む壁の座標(y軸並行の壁のx座標/x軸平行の壁のy座標)
00173 
00174     double R1=240,R2=240,R3=240,R4=240; //機体の中心から各超音波センサーが付いている面までの距離
00175     double D1=42,D2=0,D3=0,D4=0; //各超音波センサーが付いている面の中心から各超音波センサーまでの距離
00176 
00177     now_angle=gyro.getAngle();  //ジャイロの値読み込み
00178 
00179     if(tgt_angle==0) {
00180         if((xy_type==0 || xy_type==2) && pm_typeX==0) {
00181 
00182             info.nowX.usw = x_base - (usw_data4 + R4*cos(now_angle*PI/180) + D4*sin(now_angle*PI/180));
00183 
00184         } else if((xy_type==0 || xy_type==2) && pm_typeX==1) {
00185 
00186             info.nowX.usw = x_base + (usw_data3 + R3*cos(now_angle*PI/180) + D3*sin(now_angle*PI/180));
00187 
00188         }
00189         if((xy_type==1 || xy_type==2) && pm_typeY==0) {
00190 
00191             info.nowY.usw = y_base - (usw_data2 + R2*cos(now_angle*PI/180) + D2*sin(now_angle*PI/180));
00192 
00193         } else if((xy_type==1 || xy_type==2) && pm_typeY==1) {
00194 
00195             info.nowY.usw = y_base + (usw_data1 + R1*cos(now_angle*PI/180) + D1*sin(now_angle*PI/180));
00196 
00197         }
00198 
00199     } else if(tgt_angle==90) {
00200         if((xy_type==0 || xy_type==2) && pm_typeX==0) {
00201 
00202             info.nowX.usw = x_base - (usw_data1 + R1*cos(now_angle*PI/180) + D1*sin(now_angle*PI/180));
00203 
00204         } else if((xy_type==0 || xy_type==2) && pm_typeX==1) {
00205 
00206             info.nowX.usw = x_base + (usw_data2 + R2*cos(now_angle*PI/180) + D2*sin(now_angle*PI/180));
00207 
00208         }
00209         if((xy_type==1 || xy_type==2) && pm_typeY==0) {
00210 
00211             info.nowY.usw = y_base - (usw_data4 + R4*cos(now_angle*PI/180) + D4*sin(now_angle*PI/180));
00212 
00213         } else if((xy_type==1 || xy_type==2) && pm_typeY==1) {
00214 
00215             info.nowY.usw = y_base + (usw_data3 + R3*cos(now_angle*PI/180) + D3*sin(now_angle*PI/180));
00216 
00217         }
00218 
00219     } else if(tgt_angle==180 || tgt_angle == -180) {
00220         if((xy_type==0 || xy_type==2) && pm_typeX==0) {
00221 
00222             info.nowX.usw = x_base - (usw_data3 + R3*cos(now_angle*PI/180) + D3*sin(now_angle*PI/180));
00223 
00224         } else if((xy_type==0 || xy_type==2) && pm_typeX==1) {
00225 
00226             info.nowX.usw = x_base + (usw_data4 + R4*cos(now_angle*PI/180) + D4*sin(now_angle*PI/180));
00227 
00228         }
00229         if((xy_type==1 || xy_type==2) && pm_typeY==0) {
00230 
00231             info.nowY.usw = y_base - (usw_data1+ R1*cos(now_angle*PI/180) + D1*sin(now_angle*PI/180));
00232 
00233         } else if((xy_type==1 || xy_type==2) && pm_typeY==1) {
00234 
00235             info.nowY.usw = y_base + (usw_data2 + R2*cos(now_angle*PI/180) + D2*sin(now_angle*PI/180));
00236 
00237         }
00238     }else if(tgt_angle==-90) {
00239         if((xy_type==0 || xy_type==2) && pm_typeX==0) {
00240 
00241             info.nowX.usw = x_base - (usw_data2 + R2*cos(now_angle*PI/180) + D2*sin(now_angle*PI/180));
00242 
00243         } else if((xy_type==0 || xy_type==2) && pm_typeX==1) {
00244 
00245             info.nowX.usw = x_base + (usw_data1 + R1*cos(now_angle*PI/180) + D1*sin(now_angle*PI/180));
00246 
00247         }
00248         if((xy_type==1 || xy_type==2) && pm_typeY==0) {
00249 
00250             info.nowY.usw = y_base - (usw_data3 + R3*cos(now_angle*PI/180) + D3*sin(now_angle*PI/180));
00251 
00252         } else if((xy_type==1 || xy_type==2) && pm_typeY==1) {
00253 
00254             info.nowY.usw = y_base + (usw_data4 + R4*cos(now_angle*PI/180) + D4*sin(now_angle*PI/180));
00255 
00256         }
00257 
00258     }
00259 }
00260 
00261 void calc_xy(double target_angle, double u,double v)
00262 {
00263 //エンコーダにより求めた機体の座標と超音波センサーにより求めた機体の座標を(エンコーダ : 超音波 = u : 1-u / v : 1-v)の割合で混ぜて now_x,now_y に代入する
00264 
00265     calc_xy_enc();
00266 
00267     if(u != 1 || v != 1) {
00268         calc_xy_usw(target_angle);  //エンコーダの値しか使用しない場合は超音波センサーによる座標計算は行わずに計算量を減らす。
00269     }
00270 
00271     now_x = u * info.nowX.enc + (1-u) * info.nowX.usw;
00272     now_y = v * info.nowY.enc + (1-v) * info.nowY.usw;
00273 
00274     /*if(now_x >-1 && now_x <1 && now_y >-1 && now_y <1){  //スタート時の0合わせ用
00275         ec_led = 1;
00276     }else{
00277         ec_led = 0;
00278     }
00279 
00280     if(now_angle >-0.5 && now_angle <0.5){
00281         gyro_led = 1;
00282     }else{
00283         gyro_led = 0;
00284     }*/
00285 }
00286 
00287 void enc_correction(int x_select,int y_select){ //エンコーダの座標を超音波センサの座標で上書き
00288 //x_select,y_select → (0:上書きしない/1:上書きする)
00289 
00290     if(x_select == 1){
00291         info.nowX.enc = info.nowX.usw;
00292     }
00293     if(y_select == 1){
00294         info.nowY.enc = info.nowY.usw;
00295     }
00296     
00297 }
00298 
00299 //ここからそれぞれのプログラム/////////////////////////////////////////////////////////////////////////////////////////////////////////////////
00300 //now_x(現在のx座標),now_y(現在のy座標),now_angle(機体角度(ラジアンではない)(0~360や-180~180とは限らない))(反時計回りが正)
00301 //ジャイロの出力は角度だが三角関数はラジアンとして計算する
00302 //通常の移動+座標のずれ補正+機体の角度補正(+必要に応じさらに別補正)
00303 //ジャイロの仕様上、角度補正をするときに計算式内で角度はそのままよりsinをとったほうがいいかもね
00304 
00305 void purecurve(int type,double u,double v,       //正面を変えずに円弧or楕円を描いて曲がる
00306                double point_x1,double point_y1,
00307                double point_x2,double point_y2,
00308                int theta,
00309                double speed,
00310                double q_p,double q_d,
00311                double r_p,double r_d,
00312                double r_out_max,
00313                double target_angle)
00314 //type:動きの種類(8パターン) point_x1,point_y1=出発地点の座標 point_x2,point_x2=目標地点の座標 theta=plotの間隔(0~90°) speed=速度
00315 {
00316     //-----PathFollowingのパラメーター設定-----//
00317     q_setPDparam(q_p,q_d);  //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数
00318     r_setPDparam(r_p,r_d);  //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数
00319     set_r_out(r_out_max);  //旋回時の最大出力値設定関数
00320     set_target_angle(target_angle);  //機体目標角度設定関数
00321 
00322     int s;
00323     int t = 0;
00324     double X,Y;//X=楕円の中心座標、Y=楕円の中心座標
00325     double a,b; //a=楕円のx軸方向の幅の半分,b=楕円のy軸方向の幅の半分
00326     double plotx[(90/theta)+1];  //楕円にとるplotのx座標
00327     double ploty[(90/theta)+1];
00328 
00329     double x_out,y_out,r_out;
00330 
00331     a=fabs(point_x1-point_x2);
00332     b=fabs(point_y1-point_y2);
00333 
00334     switch(type) {
00335 
00336         case 1://→↑移動
00337             X=point_x1;
00338             Y=point_y2;
00339 
00340             for(s=0; s<((90/theta)+1); s++) {
00341                 plotx[s] = X + a * cos(-PI/2 + s * (PI*theta/180));
00342                 ploty[s] = Y + b * sin(-PI/2 + s * (PI*theta/180));
00343                 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
00344             }
00345             break;
00346 
00347         case 2://↑→移動
00348             X=point_x2;
00349             Y=point_y1;
00350 
00351             for(s=0; s<((90/theta)+1); s++) {
00352                 plotx[s] = X + a * cos(PI - s * (PI*theta/180));
00353                 ploty[s] = Y + b * sin(PI - s * (PI*theta/180));
00354                 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
00355             }
00356             break;
00357 
00358         case 3://↑←移動
00359             X=point_x2;
00360             Y=point_y1;
00361 
00362             for(s=0; s<((90/theta)+1); s++) {
00363                 plotx[s] = X + a * cos(s * (PI*theta/180));
00364                 ploty[s] = Y + b * sin(s * (PI*theta/180));
00365                 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
00366             }
00367             break;
00368 
00369         case 4://←↑移動
00370             X=point_x1;
00371             Y=point_y2;
00372 
00373             for(s=0; s<((90/theta)+1); s++) {
00374                 plotx[s] = X + a * cos(-PI/2 - s * (PI*theta/180));
00375                 ploty[s] = Y + b * sin(-PI/2 - s * (PI*theta/180));
00376                 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
00377             }
00378             break;
00379 
00380         case 5://←↓移動
00381             X=point_x1;
00382             Y=point_y2;
00383 
00384             for(s=0; s<((90/theta)+1); s++) {
00385                 plotx[s] = X + a * cos(PI/2 + s * (PI*theta/180));
00386                 ploty[s] = Y + b * sin(PI/2 + s * (PI*theta/180));
00387                 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
00388             }
00389             break;
00390 
00391         case 6://↓←移動
00392             X=point_x2;
00393             Y=point_y1;
00394 
00395             for(s=0; s<((90/theta)+1); s++) {
00396                 plotx[s] = X + a * cos(-s * (PI*theta/180));
00397                 ploty[s] = Y + b * sin(-s * (PI*theta/180));
00398                 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
00399             }
00400             break;
00401 
00402         case 7://↓→移動
00403             X=point_x2;
00404             Y=point_y1;
00405 
00406             for(s=0; s<((90/theta)+1); s++) {
00407                 plotx[s] = X + a * cos(PI + s * (PI*theta/180));
00408                 ploty[s] = Y + b * sin(PI + s * (PI*theta/180));
00409                 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
00410             }
00411             break;
00412 
00413         case 8://→↓移動
00414             X=point_x1;
00415             Y=point_y2;
00416 
00417             for(s=0; s<((90/theta)+1); s++) {
00418                 plotx[s] = X + a * cos(PI/2 - s * (PI*theta/180));
00419                 ploty[s] = Y + b * sin(PI/2 - s * (PI*theta/180));
00420                 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
00421             }
00422             break;
00423     }
00424 
00425     while(1) {
00426 
00427         calc_xy(target_angle,u,v);
00428 
00429         XYRmotorout(plotx[t],ploty[t],plotx[t+1],ploty[t+1],&x_out,&y_out,&r_out,speed,speed);
00430         CalMotorOut(x_out,y_out,r_out);
00431         //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);
00432 
00433         base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),4095);  //m1~m4に代入
00434         //debug_printf("t=%d (0)=%f (1)=%f (2)=%f (3)=%f\n\r",t,GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3));
00435 
00436         if(((plotx[t+1] - now_x)*(plotx[t+1] - plotx[t]) + (ploty[t+1] - now_y)*(ploty[t+1] - ploty[t])) < 0)t++;
00437 
00438         MaxonControl(m1,m2,m3,m4);  //出力
00439         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);
00440 
00441         if(t == (90/theta))break;
00442         if(id1_value[0] != 1)break;
00443     }
00444 }
00445 
00446 void gogo_straight(double u,double v,                //直線運動プログラム
00447                    double x1_point,double y1_point,
00448                    double x2_point,double y2_point,
00449                    double speed1,double speed2,
00450                    double q_p,double q_d,
00451                    double r_p,double r_d,
00452                    double r_out_max,
00453                    double target_angle)
00454 //引数:出発地点の座標(x,y)、目標地点の座標(x,y)、初速度(speed1)、目標速度(speed2)//speed1=speed2 のとき等速運動
00455 {
00456     //-----PathFollowingのパラメーター設定-----//
00457     q_setPDparam(q_p,q_d);  //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数
00458     r_setPDparam(r_p,r_d);  //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数
00459     set_r_out(r_out_max);  //旋回時の最大出力値設定関数
00460     set_target_angle(target_angle);  //機体目標角度設定関数
00461 
00462     while (1) {
00463 
00464         calc_xy(target_angle,u,v);
00465 
00466         XYRmotorout(x1_point,y1_point,x2_point,y2_point,&x_out,&y_out,&r_out,speed1,speed2);
00467         //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);
00468 
00469         CalMotorOut(x_out,y_out,r_out);
00470         //printf("out1=%lf, out2=%lf, out3=%lf, out4=%lf\n",GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3));
00471 
00472         base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),4095);
00473         //printf("m1=%d, m2=%d, m3=%d, m4=%d\r\n",m_1,m_2,m_3,m_4);
00474 
00475         MaxonControl(m1,m2,m3,m4);
00476         debug_printf("m1=%d m2=%d m3=%d m4=%d x=%f y=%f angle=%f\n\r",m1,m2,m3,m4,now_x,now_y,now_angle);
00477 
00478         if(((x2_point - now_x)*(x2_point - x1_point) + (y2_point - now_y)*(y2_point - y1_point)) < 0)break;
00479         if(id1_value[0] != 1)break;
00480     }
00481 }
00482 
00483 void pos_correction(double tgt_x, double tgt_y, double tgt_angle, double u, double v)   //位置補正(使用前にMaxonControl(0,0,0,0)を入れる)
00484 {
00485 
00486     double r, R=10;  // r:一回補正が入るごとの機体の位置と目標位置の距離(ズレ) R:補正終了とみなす目標位置からの機体の位置のズレ
00487     double out;
00488 
00489     calc_xy(tgt_angle, u, v);
00490 
00491     while(1) { //機体の位置を目標領域(目標座標+許容誤差)に収める
00492         gogo_straight(u,v,now_x,now_y,tgt_x,tgt_y,200,50,5,0.1,10,0.1,500,tgt_angle);
00493         MaxonControl(0,0,0,0);
00494 
00495         calc_xy(tgt_angle, u, v);
00496 
00497         r=hypot(now_x - tgt_x, now_y - tgt_y);
00498 
00499         if(r < R) break;
00500         if(id1_value[0] != 1)break;
00501     }
00502 
00503     while(1) {
00504 
00505         calc_gyro();
00506 
00507         out = 10 * (tgt_angle - now_angle);
00508 
00509         if(out > 300) {  //0~179°のときは時計回りに回転
00510             MaxonControl(300,300,300,300);
00511         } else if(out < -300) {
00512             MaxonControl(-300,-300,-300,-300);
00513         } else if(out <= 300 && out > -300) {
00514             MaxonControl(out,out,out,out);
00515         }
00516 
00517         if(tgt_angle - 0.5 < now_angle && now_angle < tgt_angle + 0.5) break;  //目標角度からの許容誤差内に機体の角度が収まった時、補正終了
00518         if(id1_value[0] != 1)break;
00519     }
00520     MaxonControl(0,0,0,0);
00521 }