2月25日

Dependencies:   uw_28015 mbed ros_lib_kinetic move4wheel2 EC CruizCore_R6093U CruizCore_R1370P

Revision:
0:44f9a43e4ab2
diff -r 000000000000 -r 44f9a43e4ab2 movement/movement.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/movement/movement.cpp	Tue Feb 25 01:20:43 2020 +0000
@@ -0,0 +1,940 @@
+#include "EC.h"
+#include "R1370P.h"
+#include "move4wheel.h"
+#include "mbed.h"
+#include "math.h"
+#include "PathFollowing.h"
+#include "movement.h"
+#include "manual.h"
+#include "can.h"
+#include "R6093U.h"
+#include "uw.h"
+
+#define PI 3.141592
+
+char can_ashileddata[2]= {0};
+char can_ashileddata2[8]= {0};
+char can_num[1]= {0};
+double info_x, info_y, info_r;
+
+//char can_ashileddata3[2]= {0};
+//char can_ashileddata4[2]= {0};
+//char can_ashileddata5[2]= {0};
+
+int can_ashileddata0_0,can_ashileddata0_1,can_ashileddata0_2,can_ashileddata0_3;
+
+Ec EC2(p16,p15,NC,2048,0.05);
+Ec EC1(p18,p17,NC,2048,0.05);
+
+
+Uw uw1(p28);
+Uw uw4(p27);
+
+
+Ticker ec_ticker;  //ec角速度計算用ticker
+Ticker uw_ticker;  //uw値取得用ticker
+
+//R1370P gyro(p9,p10);
+
+R6093U gyro(p9,p10);
+
+double new_dist1=0,new_dist2=0;
+double old_dist1=0,old_dist2=0;
+double d_dist1=0,d_dist2=0;  //座標計算用関数
+double d_x,d_y;
+//現在地X,y座標、現在角度については、PathFollowingでnow_x,now_y,now_angleを定義済
+double start_x=0,start_y=0;  //スタート位置
+double x_out,y_out,r_out;  //出力値
+
+int16_t m1=0, m2=0, m3=0, m4=0;  //int16bit = int2byte
+
+double xy_type,pm_typeX,pm_typeY,x_base,y_base;
+
+int flag;
+double angle_base = 0;
+
+int RL_mode;
+
+int uw_flag1 = 0,uw_flag2 = 0,uw_flag3 = 0,uw_flag4 = 0;
+
+///////////////////機体情報をメンバとする構造体"robo_data"と構造体型変数info(←この変数に各センサーにより求めた機体情報(機体位置/機体角度)を格納する)の宣言/////////////////
+
+/*「info.(機体情報の種類).(使用センサーの種類)」に各情報を格納する
+ *状況に応じて、どのセンサーにより算出した情報を信用するかを選択し、その都度now_angle,now_x,now_yに代入する。(何種類かのセンサーの情報を混ぜて使用することも可能)
+ *(ex)
+ *info.nowX.enc → エンコーダにより算出した機体位置のx座標
+ *info.nowY.usw → 超音波センサーにより求めた機体位置のy座標
+*/
+
+typedef struct { //使用センサーの種類
+    double usw;  //超音波センサー
+    double enc;  //エンコーダ
+    double gyro; //ジャイロ
+    //double line;//ラインセンサー
+} robo_sensor;
+
+typedef struct { //機体情報の種類
+    robo_sensor angle; //←機体角度は超音波センサーやラインセンサーからも算出可能なので一応格納先を用意したが、ジャイロの値を完全に信用してもいいかも
+    robo_sensor nowX;
+    robo_sensor nowY;
+} robo_data;
+
+robo_data info= {{0,0,0},{0,0,0},{0,0,0}}; //全てのデータを0に初期化
+
+////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+
+void UserLoopSetting_sensor()
+{
+
+    gyro.initialize();
+    ec_ticker.attach(&calOmega,0.02);  //0.05秒間隔で角速度を計算
+    uw_ticker.attach(&cal_uw,0.05);
+    EC1.setDiameter_mm(70);
+    EC2.setDiameter_mm(70);  //測定輪半径//後で測定
+    //info.nowX.enc = 457; //初期位置の設定
+    //info.nowY.enc = 457;
+    info.nowX.enc = 0; //初期位置の設定
+    info.nowY.enc = 0;
+    angle_base = -90;
+}
+
+void UserLoopSetting_enc_right()
+{
+    info.nowX.enc = 3112; //エンコーダの初期位置の設定(右側フィールド)
+    info.nowY.enc = 3500;
+    RL_mode = 0;
+}
+
+void UserLoopSetting_enc_left()
+{
+    info.nowX.enc = -3112; //エンコーダの初期位置の設定(左側フィールド)
+    info.nowY.enc = 3500;
+    RL_mode = 1;
+}
+
+void calOmega()  //角速度計算関数
+{
+    EC1.CalOmega();
+    EC2.CalOmega();
+    calc_xy_enc();
+
+    //usw_data1 = 10 * uw1.get_dist();
+    ////usw_data2 = 10 * uw2.get_dist();
+    //usw_data3 = 10 * uw3.get_dist();
+    ////usw_data4 = 10 * uw4.get_dist();
+}
+
+void cal_uw()   //uw値取得用
+{
+    if(uw_flag1 == 1) {
+        usw_data1 = 10 * uw1.get_dist();
+        //printf("uw1 = %f\n\r",usw_data1);
+    }
+    if(uw_flag2 == 1) {
+        //usw_data2 = 10 * uw2.get_dist();
+    }
+    if(uw_flag3 == 1) {
+        //usw_data3 = 10 * uw3.get_dist();
+    }
+    if(uw_flag4 == 1) {
+        usw_data4 = 10 * uw4.get_dist();
+        //printf("uw4 = %f\n\r",usw_data4);
+    }
+}
+
+void output(double FL,double BL,double BR,double FR)
+{
+    m1=FL;
+    m2=BL;
+    m3=BR;
+    m4=FR;
+}
+
+void base(double FL,double BL,double BR,double FR,double Max)
+//いろんな加算をしても最大OR最小がMaxになるような補正//絶対値が一番でかいやつで除算
+//DCモーターならMax=1、マクソンは-4095~4095だからMax=4095にする
+{
+    if(fabs(FL)>=Max||fabs(BL)>=Max||fabs(BR)>=Max||fabs(FR)>=Max) {
+
+        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));
+        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));
+        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));
+        else                                                               output(Max*FL/fabs(FR),Max*BL/fabs(FR),Max*BR/fabs(FR),Max*FR/fabs(FR));
+    } else {
+        output(FL,BL,BR,FR);
+    }
+}
+
+void ashi_led()
+{
+    if(now_angle > -1 && now_angle < 1) {
+        can_ashileddata0_0 = 1;
+    } else {
+        can_ashileddata0_0 = 0;
+    }
+
+    if(now_angle > 350) {
+        can_ashileddata0_1 = 1;
+    } else {
+        can_ashileddata0_1 = 0;
+    }
+
+    if(RL_mode == 0) {
+        if(now_x > 3110 && now_x < 3114) {
+            can_ashileddata0_2 = 1;
+        } else {
+            can_ashileddata0_2 = 0;
+        }
+
+        if(now_y > 3498 && now_y < 3502) {
+            can_ashileddata0_3 = 1;
+        } else {
+            can_ashileddata0_3 = 0;
+        }
+    } else if(RL_mode == 1) {
+        if(now_x > -3114 && now_x < -3110) {
+            can_ashileddata0_2 = 1;
+        } else {
+            can_ashileddata0_2 = 0;
+        }
+
+        if(now_y > 3498 && now_y < 3502) {
+            can_ashileddata0_3 = 1;
+        } else {
+            can_ashileddata0_3 = 0;
+        }
+    }
+
+    can_ashileddata[0] = (can_ashileddata0_0<<7 | can_ashileddata0_1<<6 | can_ashileddata0_2<<5 | can_ashileddata0_3<<4);
+}
+
+void calc_gyro()
+{
+    //now_angle=gyro.getAngle();  //ジャイロの値読み込み
+    now_angle = -gyro.getZ_Angle() + angle_base;
+}
+
+void print_gyro()
+{
+    while(1) {
+        //printf("now_gyro = %f\n\r",-gyro.getAngle());
+    }
+
+}
+
+void calc_xy_enc()  //エンコーダ&ジャイロによる座標計算
+{
+    old_angle=now_angle;
+    //now_angle=gyro.getAngle();  //ジャイロの値読み込み
+    now_angle = -gyro.getZ_Angle() + angle_base;
+    adj_angle=(now_angle+old_angle)/2;
+
+    new_dist1=EC1.getDistance_mm();
+    new_dist2=EC2.getDistance_mm();
+    d_dist1=new_dist1-old_dist1;
+    d_dist2=new_dist2-old_dist2;
+    old_dist1=new_dist1;
+    old_dist2=new_dist2;  //微小時間当たりのエンコーダ読み込み
+
+    d_x=d_dist2*sin(adj_angle*PI/180)-d_dist1*cos(adj_angle*PI/180);
+    d_y=d_dist2*cos(adj_angle*PI/180)+d_dist1*sin(adj_angle*PI/180);  //微小時間毎の座標変化
+    info.nowX.enc = info.nowX.enc + d_x;
+    info.nowY.enc = info.nowY.enc - d_y;  //微小時間毎に座標に加算
+}
+
+
+void set_cond(int t, int px, double bx, int py, double by)   //超音波センサーを使用するときの条件設定関数
+{
+//引数の詳細は関数"calc_xy_usw"参照
+
+    xy_type = t;
+
+    pm_typeX = px;
+    x_base = bx;
+
+    pm_typeY = py;
+    y_base = by;
+}
+
+void calc_xy_usw(double tgt_angle)   //超音波センサーによる座標計算(機体が旋回する場合はこの方法による座標計算は出来ない)
+{
+//tgt_angle:機体の目標角度(運動初期角度と同じ/今大会では0,90,180のみ)
+//xy_type:(0:Y軸平行の壁を読む/1:X軸平行の壁を読む/2:X,Y軸平行の壁を共に読む)
+//pm_typeX,pm_typeY:(0:各軸正方向側の壁を読む/1:各軸負方向側の壁を読む)
+//x_base,y_base:超音波センサーで読む壁の座標(y軸並行の壁のx座標/x軸平行の壁のy座標)
+
+    double R1=414.5,R2=414.5,R3=414.5,R4=414.5; //機体の中心から各超音波センサーが付いている面までの距離
+    double D1=-237.5,D2=237.5,D3=237.5,D4=-237.5; //各超音波センサーが付いている面の中心から各超音波センサーまでの距離(時計回りを正とする)
+
+//    now_angle=gyro.getAngle();  //ジャイロの値読み込み
+    now_angle = -gyro.getZ_Angle() + angle_base ;
+
+    if(tgt_angle > -45 && tgt_angle < 45) {
+        if((xy_type==0 || xy_type==2) && pm_typeX==0) {
+
+            info.nowX.usw = x_base - (usw_data4 + R4*cos(now_angle*PI/180) + D4*sin(now_angle*PI/180));
+            uw_flag4 = 1;
+
+        } else if((xy_type==0 || xy_type==2) && pm_typeX==1) {
+
+            info.nowX.usw = x_base + (usw_data3 + R3*cos(now_angle*PI/180) + D3*sin(now_angle*PI/180));
+            uw_flag3 = 1;
+
+        }
+        if((xy_type==1 || xy_type==2) && pm_typeY==0) {
+
+            info.nowY.usw = y_base - (usw_data2 + R2*cos(now_angle*PI/180) + D2*sin(now_angle*PI/180));
+            uw_flag2 = 1;
+
+        } else if((xy_type==1 || xy_type==2) && pm_typeY==1) {
+
+            info.nowY.usw = y_base + (usw_data1 + R1*cos(now_angle*PI/180) + D1*sin(now_angle*PI/180));
+            uw_flag1 = 1;
+
+        }
+
+    } else if(tgt_angle > 45 && tgt_angle < 135) {
+        if((xy_type==0 || xy_type==2) && pm_typeX==0) {
+
+            info.nowX.usw = x_base - (usw_data1 + R1*cos((now_angle-tgt_angle)*PI/180) + D1*sin((now_angle-tgt_angle)*PI/180));
+            uw_flag1 = 1;
+
+        } else if((xy_type==0 || xy_type==2) && pm_typeX==1) {
+
+            info.nowX.usw = x_base + (usw_data2 + R2*cos((now_angle-tgt_angle)*PI/180) + D2*sin((now_angle-tgt_angle)*PI/180));
+            uw_flag2 = 1;
+
+        }
+        if((xy_type==1 || xy_type==2) && pm_typeY==0) {
+
+            info.nowY.usw = y_base - (usw_data4 + R4*cos((now_angle-tgt_angle)*PI/180) + D4*sin((now_angle-tgt_angle)*PI/180));
+            uw_flag4 = 1;
+
+        } else if((xy_type==1 || xy_type==2) && pm_typeY==1) {
+
+            info.nowY.usw = y_base + (usw_data3 + R3*cos((now_angle-tgt_angle)*PI/180) + D3*sin((now_angle-tgt_angle)*PI/180));
+            uw_flag3 = 1;
+
+        }
+
+    } else if((tgt_angle > 135 && tgt_angle < 225) || (tgt_angle > -225 && tgt_angle < -135)) {
+        if((xy_type==0 || xy_type==2) && pm_typeX==0) {
+
+            info.nowX.usw = x_base - (usw_data3 + R3*cos((now_angle-tgt_angle)*PI/180) + D3*sin((now_angle-tgt_angle)*PI/180));
+            uw_flag3 = 1;
+
+        } else if((xy_type==0 || xy_type==2) && pm_typeX==1) {
+
+            info.nowX.usw = x_base + (usw_data4 + R4*cos((now_angle-tgt_angle)*PI/180) + D4*sin((now_angle-tgt_angle)*PI/180));
+            uw_flag4 = 1;
+
+        }
+        if((xy_type==1 || xy_type==2) && pm_typeY==0) {
+
+            info.nowY.usw = y_base - (usw_data1+ R1*cos((now_angle-tgt_angle)*PI/180) + D1*sin((now_angle-tgt_angle)*PI/180));
+            uw_flag1 = 1;
+
+        } else if((xy_type==1 || xy_type==2) && pm_typeY==1) {
+
+            info.nowY.usw = y_base + (usw_data2 + R2*cos((now_angle-tgt_angle)*PI/180) + D2*sin((now_angle-tgt_angle)*PI/180));
+            uw_flag2 = 1;
+
+        }
+    } else if(tgt_angle > -135 && tgt_angle < -45) {
+        if((xy_type==0 || xy_type==2) && pm_typeX==0) {
+
+            info.nowX.usw = x_base - (usw_data2 + R2*cos((now_angle-tgt_angle)*PI/180) + D2*sin((now_angle-tgt_angle)*PI/180));
+            uw_flag2 = 1;
+
+        } else if((xy_type==0 || xy_type==2) && pm_typeX==1) {
+
+            info.nowX.usw = x_base + (usw_data1 + R1*cos((now_angle-tgt_angle)*PI/180) + D1*sin((now_angle-tgt_angle)*PI/180));
+            uw_flag1 = 1;
+
+        }
+        if((xy_type==1 || xy_type==2) && pm_typeY==0) {
+
+            info.nowY.usw = y_base - (usw_data3 + R3*cos((now_angle-tgt_angle)*PI/180) + D3*sin((now_angle-tgt_angle)*PI/180));
+            uw_flag3 = 1;
+
+        } else if((xy_type==1 || xy_type==2) && pm_typeY==1) {
+
+            info.nowY.usw = y_base + (usw_data4 + R4*cos((now_angle-tgt_angle)*PI/180) + D4*sin((now_angle-tgt_angle)*PI/180));
+            uw_flag4 = 1;
+
+        }
+    }
+}
+
+void uwflag_reset()
+{
+    uw_flag1 = 0;
+    uw_flag2 = 0;
+    uw_flag3 = 0;
+    uw_flag4 = 0;
+}
+
+void uwflag_change(int u1,int u2, int u3, int u4)
+{
+    uw_flag1 = u1;
+    uw_flag2 = u2;
+    uw_flag3 = u3;
+    uw_flag4 = u4;
+}
+
+
+void calc_xy(double target_angle, double u,double v)
+{
+//エンコーダにより求めた機体の座標と超音波センサーにより求めた機体の座標を(エンコーダ : 超音波 = u : 1-u / v : 1-v)の割合で混ぜて now_x,now_y に代入する
+
+    calc_xy_enc();
+    //usw_data1 = 10 * uw1.get_dist();
+    ///usw_data2 = 10 * uw2.get_dist();
+    //usw_data3 = 10 * uw3.get_dist();
+    ///usw_data4 = 10 * uw4.get_dist();
+
+    //printf("uw2 = %f,  uw4 = %f\n\r",usw_data2,usw_data4);
+
+    if(u != 1 || v != 1) {
+        calc_xy_usw(target_angle);  //エンコーダの値しか使用しない場合は超音波センサーによる座標計算は行わずに計算量を減らす。
+    }
+
+    now_x = u * info.nowX.enc + (1-u) * info.nowX.usw;
+    now_y = v * info.nowY.enc + (1-v) * info.nowY.usw;
+
+    /*if(now_x >-1 && now_x <1 && now_y >-1 && now_y <1){  //スタート時の0合わせ用
+        ec_led = 1;
+    }else{
+        ec_led = 0;
+    }
+
+    if(now_angle >-0.5 && now_angle <0.5){
+        gyro_led = 1;
+    }else{
+        gyro_led = 0;
+    }*/
+}
+
+void copy_xyr_usw(){
+    calc_xy_enc();
+    now_angle = -gyro.getZ_Angle() + angle_base;
+    
+    info_x = info.nowX.enc;
+    info_y = info.nowY.enc;
+    info_r = now_angle;
+    
+    usw_data1 = 10 * uw1.get_dist();
+    usw_data2 = 2000; //10 * uw2.get_dist();
+    usw_data3 = 3000; //10 * uw3.get_dist();
+    usw_data4 = 10 * uw4.get_dist();
+}
+
+void enc_correction(int x_select,int y_select)  //エンコーダの座標を超音波センサの座標で上書き
+{
+//x_select,y_select → (0:上書きしない/1:上書きする)
+
+    if(x_select == 1) {
+        info.nowX.enc = info.nowX.usw;
+    }
+    if(y_select == 1) {
+        info.nowY.enc = info.nowY.usw;
+    }
+
+}
+
+void enc_correction2(int x_plot1, int y_plot2) //引数の座標でエンコーダの座標を修正
+{
+    info.nowX.enc = x_plot1;
+    info.nowY.enc = y_plot2;
+}
+
+//ここからそれぞれのプログラム/////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+//now_x(現在のx座標),now_y(現在のy座標),now_angle(機体角度(ラジアンではない)(0~360や-180~180とは限らない))(反時計回りが正)
+//ジャイロの出力は角度だが三角関数はラジアンとして計算する
+//通常の移動+座標のずれ補正+機体の角度補正(+必要に応じさらに別補正)
+//ジャイロの仕様上、角度補正をするときに計算式内で角度はそのままよりsinをとったほうがいいかもね
+
+void purecurve(int type,double u,double v,       //正面を変えずに円弧or楕円を描いて曲がる
+               double point_x1,double point_y1,
+               double point_x2,double point_y2,
+               int theta,
+               double speed,
+               double q_p,double q_d,
+               double r_p,double r_d,
+               double r_out_max,
+               double target_angle, double v_base, double q_out_max)
+//type:動きの種類(8パターン) point_x1,point_y1=出発地点の座標 point_x2,point_x2=目標地点の座標 theta=plotの間隔(0~90°) speed=速度
+{
+    //-----PathFollowingのパラメーター設定-----//
+    q_setPDparam(q_p,q_d);  //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数
+    r_setPDparam(r_p,r_d);  //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数
+    set_r_out(r_out_max);  //旋回時の最大出力値設定関数
+    set_q_out(q_out_max);
+    set_target_angle(target_angle);  //機体目標角度設定関数
+
+    int s;
+    int t = 0;
+    double X,Y;//X=楕円の中心座標、Y=楕円の中心座標
+    double a,b; //a=楕円のx軸方向の幅の半分,b=楕円のy軸方向の幅の半分
+    double plotx[(90/theta)+1];  //楕円にとるplotのx座標
+    double ploty[(90/theta)+1];
+
+    double x_out,y_out,r_out;
+
+    a=fabs(point_x1-point_x2);
+    b=fabs(point_y1-point_y2);
+
+    switch(type) {
+
+        case 1://→↑移動
+            X=point_x1;
+            Y=point_y2;
+
+            for(s=0; s<((90/theta)+1); s++) {
+                plotx[s] = X + a * cos(-PI/2 + s * (PI*theta/180));
+                ploty[s] = Y + b * sin(-PI/2 + s * (PI*theta/180));
+                //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
+            }
+            break;
+
+        case 2://↑→移動
+            X=point_x2;
+            Y=point_y1;
+
+            for(s=0; s<((90/theta)+1); s++) {
+                plotx[s] = X + a * cos(PI - s * (PI*theta/180));
+                ploty[s] = Y + b * sin(PI - s * (PI*theta/180));
+                //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
+            }
+            break;
+
+        case 3://↑←移動
+            X=point_x2;
+            Y=point_y1;
+
+            for(s=0; s<((90/theta)+1); s++) {
+                plotx[s] = X + a * cos(s * (PI*theta/180));
+                ploty[s] = Y + b * sin(s * (PI*theta/180));
+                //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
+            }
+            break;
+
+        case 4://←↑移動
+            X=point_x1;
+            Y=point_y2;
+
+            for(s=0; s<((90/theta)+1); s++) {
+                plotx[s] = X + a * cos(-PI/2 - s * (PI*theta/180));
+                ploty[s] = Y + b * sin(-PI/2 - s * (PI*theta/180));
+                //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
+            }
+            break;
+
+        case 5://←↓移動
+            X=point_x1;
+            Y=point_y2;
+
+            for(s=0; s<((90/theta)+1); s++) {
+                plotx[s] = X + a * cos(PI/2 + s * (PI*theta/180));
+                ploty[s] = Y + b * sin(PI/2 + s * (PI*theta/180));
+                //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
+            }
+            break;
+
+        case 6://↓←移動
+            X=point_x2;
+            Y=point_y1;
+
+            for(s=0; s<((90/theta)+1); s++) {
+                plotx[s] = X + a * cos(-s * (PI*theta/180));
+                ploty[s] = Y + b * sin(-s * (PI*theta/180));
+                //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
+            }
+            break;
+
+        case 7://↓→移動
+            X=point_x2;
+            Y=point_y1;
+
+            for(s=0; s<((90/theta)+1); s++) {
+                plotx[s] = X + a * cos(PI + s * (PI*theta/180));
+                ploty[s] = Y + b * sin(PI + s * (PI*theta/180));
+                //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
+            }
+            break;
+
+        case 8://→↓移動
+            X=point_x1;
+            Y=point_y2;
+
+            for(s=0; s<((90/theta)+1); s++) {
+                plotx[s] = X + a * cos(PI/2 - s * (PI*theta/180));
+                ploty[s] = Y + b * sin(PI/2 - s * (PI*theta/180));
+                //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
+            }
+            break;
+    }
+
+    while(1) {
+
+        if(id1_value[0] != 1)break;
+        if(id1_value[6] != flag)break;
+
+        calc_xy(target_angle,u,v);
+
+        XYRmotorout(plotx[t],ploty[t],plotx[t+1],ploty[t+1],&x_out,&y_out,&r_out,speed,speed);
+        CalMotorOut(x_out,y_out,r_out);
+        //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);
+
+        base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),v_base);  //m1~m4に代入
+        //debug_printf("t=%d (0)=%f (1)=%f (2)=%f (3)=%f\n\r",t,GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3));
+
+        if(((plotx[t+1] - now_x)*(plotx[t+1] - plotx[t]) + (ploty[t+1] - now_y)*(ploty[t+1] - ploty[t])) < 0)t++;
+
+//        MaxonControl(m1,m2,m3,m4);  //出力
+//        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);
+
+        if(t == (90/theta))break;
+    }
+}
+
+void gogo_straight(double u,double v,                //直線運動プログラム
+                   double x1_point,double y1_point,
+                   double x2_point,double y2_point,
+                   double speed1,double speed2,
+                   double q_p,double q_d,
+                   double r_p,double r_d,
+                   double r_out_max,
+                   double target_angle,double v_base, double q_out_max)
+//引数:出発地点の座標(x,y)、目標地点の座標(x,y)、初速度(speed1)、目標速度(speed2)//speed1=speed2 のとき等速運動
+{
+    //-----PathFollowingのパラメーター設定-----//
+    q_setPDparam(q_p,q_d);  //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数
+    r_setPDparam(r_p,r_d);  //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数
+    set_r_out(r_out_max);  //旋回時の最大出力値設定関数
+    set_q_out(q_out_max);
+    set_target_angle(target_angle);  //機体目標角度設定関数
+
+    while (1) {
+
+        if(id1_value[0] != 1)break;
+        if(id1_value[6] != flag)break;
+
+        calc_xy(target_angle,u,v);
+
+        XYRmotorout(x1_point,y1_point,x2_point,y2_point,&x_out,&y_out,&r_out,speed1,speed2);
+        //printf("n_x = %f, n_y = %f,n_angle = %f, t_x = %f, t_y = %f, t_angle = %f, x_out=%lf, y_out=%lf, r_out=%lf\n\r",now_x,now_y,now_angle,x2_point,y2_point,target_angle,x_out, y_out,r_out);
+
+        CalMotorOut(x_out,y_out,r_out);
+        //printf("out1=%lf, out2=%lf, out3=%lf, out4=%lf\n",GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3));
+
+        base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),v_base);
+        //printf("m1=%d, m2=%d, m3=%d, m4=%d\r\n",m_1,m_2,m_3,m_4);
+
+//        MaxonControl(m1,m2,m3,m4);
+//        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);
+        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);
+        //printf("usw2 = %f  usw4 = %f x=%f y=%f angle=%f\n\r",usw_data2,usw_data4,now_x,now_y,now_angle);
+
+        if(((x2_point - now_x)*(x2_point - x1_point) + (y2_point - now_y)*(y2_point - y1_point)) < 0)break;
+    }
+}
+
+
+
+double spline_base(int i, int k, double t, int nv[]) //スプライン基底関数を求める関数
+{
+    // i:0~(制御点の個数-1)
+    // k:スプライト曲線の次元
+    // t:0~(ノットベクトルの最大値)
+    // nv[]:ノットベクトル
+    double w1 = 0.0, w2 = 0.0;
+    if (k == 1) {
+        if (t > nv[i] && t <= nv[i + 1])
+            return 1.0;
+        else
+            return 0.0;
+    } else {
+        if ((nv[i + k] - nv[i + 1]) != 0) {
+            w1 = ((nv[i + k] - t) / (nv[i + k] - nv[i + 1])) * spline_base(i + 1, k - 1, t, nv);
+            //printf("%f\n\r",w1);
+        }
+        if ((nv[i + k - 1] - nv[i]) != 0) {
+            w2 = ((t - nv[i]) / (nv[i + k - 1] - nv[i])) * spline_base(i, k - 1, t, nv);
+            //printf("%f\n\r",w2);
+        }
+        return (w1 + w2);
+    }
+}
+
+
+void spline_move(double u, double v,
+                 double st_x,double st_y,double end_x,double end_y,
+                 double cont1_x,double cont1_y,double cont2_x,double cont2_y,
+                 double st_speed, double end_speed,
+                 double q_p,double q_d,
+                 double r_p,double r_d,
+                 double r_out_max,
+                 double target_angle, double v_base, double q_out_max, int num)
+{
+    double dx, dy, dr;
+    int nt[] = {0, 0, 0, 1, 2, 2, 2}; //ノットベクトル
+    //dr = (end_angle - st_angle) / num;
+    int ds = (end_speed - st_speed) / num;
+
+    //-----PathFollowingのパラメーター設定-----//
+    q_setPDparam(q_p,q_d);  //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数
+    r_setPDparam(r_p,r_d);  //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数
+    set_r_out(r_out_max);  //旋回時の最大出力値設定関数
+    set_q_out(q_out_max);
+    set_target_angle(target_angle);  //機体目標角度設定関数
+
+    double plotx[num + 1]; //楕円にとるplotのx座標
+    double ploty[num + 1];
+    double value_t;
+    int i, j;
+    int t = 0;
+    // for(i = 0; i < 7; i++){
+    //  printf("not_V = %d\n\r",nt[i]);
+    // }
+    for (i = 0; i < num + 1; i++) {
+        plotx[i] = 0.0;
+        ploty[i] = 0.0;
+    }
+    printf("{\n");
+    for (i = 0; i < num + 1; i++) {
+        value_t = (double)2 * i / num;
+        for (j = 0; j < 4; j++) {
+            if (j == 0) {
+                plotx[i] += st_x * spline_base(j, 3, value_t, nt);
+                ploty[i] += st_y * spline_base(j, 3, value_t, nt);
+            } else if (j == 1) {
+                plotx[i] += cont1_x * spline_base(j, 3, value_t, nt);
+                ploty[i] += cont1_y * spline_base(j, 3, value_t, nt);
+            } else if (j == 2) {
+                plotx[i] += cont2_x * spline_base(j, 3, value_t, nt);
+                ploty[i] += cont2_y * spline_base(j, 3, value_t, nt);
+            } else if (j == 3) {
+                plotx[i] += end_x * spline_base(j, 3, value_t, nt);
+                ploty[i] += end_y * spline_base(j, 3, value_t, nt);
+            }
+        }
+        //printf("plot_x = %f, plot_y = %f\n\r", plotx[i], ploty[i]);
+    }
+    while(1) {
+
+        if(id1_value[0] != 1)break;
+        if(id1_value[6] != flag)break;
+
+        calc_xy(target_angle,u,v);
+
+        XYRmotorout(plotx[t],ploty[t],plotx[t+1],ploty[t+1],&x_out,&y_out,&r_out,st_speed+ds*t,st_speed+ds*(t+1));
+        CalMotorOut(x_out,y_out,r_out);
+        //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);
+
+        base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),v_base);  //m1~m4に代入
+        //debug_printf("t=%d (0)=%f (1)=%f (2)=%f (3)=%f\n\r",t,GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3));
+
+        if(((plotx[t+1] - now_x)*(plotx[t+1] - plotx[t]) + (ploty[t+1] - now_y)*(ploty[t+1] - ploty[t])) < 0)t++;
+
+//        MaxonControl(m1,m2,m3,m4);  //出力
+//        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);
+        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);
+
+        if(t == num)break;
+    }
+
+}
+
+
+
+
+/*void pos_correction(double tgt_x, double tgt_y, double tgt_angle, double u, double v)   //位置補正(使用前にMaxonControl(0,0,0,0)を入れる)
+{
+
+    double r, R=10;  // r:一回補正が入るごとの機体の位置と目標位置の距離(ズレ) R:補正終了とみなす目標位置からの機体の位置のズレ
+    double out;
+
+    calc_xy(tgt_angle, u, v);
+
+    while(1) { //機体の位置を目標領域(目標座標+許容誤差)に収める
+        gogo_straight(u,v,now_x,now_y,tgt_x,tgt_y,200,50,5,0.1,10,0.1,500,tgt_angle);
+        MaxonControl(0,0,0,0);
+
+        calc_xy(tgt_angle, u, v);
+
+        r=hypot(now_x - tgt_x, now_y - tgt_y);
+
+        if(r < R) break;
+        if(id1_value[0] != 1)break;
+    }
+
+    while(1) {
+
+        calc_gyro();
+
+        out = 10 * (tgt_angle - now_angle);
+
+        if(out > 300) {  //0~179°のときは時計回りに回転
+            MaxonControl(300,300,300,300);
+        } else if(out < -300) {
+            MaxonControl(-300,-300,-300,-300);
+        } else if(out <= 300 && out > -300) {
+            MaxonControl(out,out,out,out);
+        }
+
+        if(tgt_angle - 0.5 < now_angle && now_angle < tgt_angle + 0.5) break;  //目標角度からの許容誤差内に機体の角度が収まった時、補正終了
+        if(id1_value[0] != 1)break;
+    }
+    MaxonControl(0,0,0,0);
+}*/
+
+void pos_correction(double tgt_x, double tgt_y, double tgt_angle, double u, double v, double v_base)   //改良版 位置補正(使用前にMaxonControl(0,0,0,0)を入れる)
+{
+//距離に比例させて補正初速度を増加させる。(最大速度を設定しそれ以上は出ないようにする)
+
+    double first_speed, first_speed50 = 10, last_speed = 10, Max_speed = 500, speed5 = 20;
+    double r, R=25;  // r:一回補正が入るごとの機体の位置と目標位置の距離(ズレ) R:補正終了とみなす目標位置からの機体の位置のズレ
+    double out;
+
+    calc_xy(tgt_angle, u, v);
+
+    //r = hypot(now_x - tgt_x, now_y - tgt_y);
+
+    while(1) { //機体の位置を目標領域(目標座標+許容誤差)に収める
+        //printf("col\n\n\n");
+        if(id1_value[0] != 1)break;
+        if(id1_value[6] != flag)break;
+
+        //first_speed = first_speed50 * r / 50;
+
+        /*if(first_speed > Max_speed){
+            gogo_straight(u,v,now_x,now_y,tgt_x,tgt_y,Max_speed,Max_speed,5,0.1,10,0.1,500,tgt_angle, v_base);
+        }else{
+            gogo_straight(u,v,now_x,now_y,tgt_x,tgt_y,first_speed,last_speed,5,0.1,10,0.1,500,tgt_angle);
+        }*/
+
+        //gogo_straight(u,v,now_x,now_y,tgt_x,tgt_y,first_speed50,last_speed,5,0.1,10,0.1,500,tgt_angle);
+
+        int diff_sm = hypot(now_x-tgt_x,now_y-tgt_y);
+
+        int f_speed = diff_sm / 5 * (speed5 - last_speed);
+        gogo_straight(u,v,now_x,now_y,tgt_x,tgt_y,f_speed,last_speed,0.5,0.05,5,0.05,20,tgt_angle, v_base, 70);
+        //gogo_straight(1,1,0,0,200,0,50,500,5,0.1,10,0.1,50,0);
+        //gogo_straight(u,v,now_x,now_y,0,100,first_speed50,last_speed,5,0.1,10,0.1,500,tgt_angle);
+
+//      MaxonControl(0,0,0,0);
+        m1 = 0;
+        m2 = 0;
+        m3 = 0;
+        m4 = 0;
+
+        calc_xy(tgt_angle, u, v);
+
+        r=hypot(now_x - tgt_x, now_y - tgt_y);
+
+        if(r < R) break;
+    }
+
+    while(1) {
+
+        if(id1_value[0] != 1)break;
+        if(id1_value[6] != flag)break;
+
+        //calc_gyro();
+//        now_angle=gyro.getAngle();
+        now_angle = -gyro.getZ_Angle() + angle_base;
+        if(tgt_angle - 1 < now_angle && now_angle < tgt_angle + 1) break;  //目標角度からの許容誤差内に機体の角度が収まった時、補正終了
+        else if(now_angle > tgt_angle + 1)out = 5 * (tgt_angle - now_angle + 1);
+        else if(tgt_angle - 1 > now_angle)out = 5 * (tgt_angle - now_angle - 1);
+
+        printf("angle = %f  out = %f\n\r",now_angle,out);
+
+            if(out > 100) {  //0~179°のときは時計回りに回転
+        //            MaxonControl(-300,-300,-300,-300);
+                m1 = -100;
+                m2 = -100;
+                m3 = -100;
+                m4 = -100;
+
+            } else if(out < -100) {
+        //            MaxonControl(300,300,300,300);
+                m1 = 100;
+                m2 = 100;
+                m3 = 100;
+                m4 = 100;
+            } else if(out <= 100 && out > -100) {
+        //            MaxonControl(-out,-out,-out,-out);
+                m1 = -out;
+                m2 = -out;
+                m3 = -out;
+                m4 = -out;
+            }
+
+/*        if(out > 100) {  //0~179°のときは時計回りに回転
+//            MaxonControl(-300,-300,-300,-300);
+            m1 = 9900;
+            m2 = 9900;
+            m3 = 9900;
+            m4 = 9900;
+
+        } else if(out < -100) {
+//            MaxonControl(300,300,300,300);
+            m1 = 10100;
+            m2 = 10100;
+            m3 = 10100;
+            m4 = 10100;
+        } else if(out <= 100 && out > -100) {
+//            MaxonControl(-out,-out,-out,-out);
+            m1 = -out + 10000;
+            m2 = -out + 10000;
+            m3 = -out + 10000;
+            m4 = -out + 10000;
+        }*/
+
+    }
+//    MaxonControl(0,0,0,0);
+    m1 = 0;
+    m2 = 0;
+    m3 = 0;
+    m4 = 0;
+}
+
+void mt_stop()
+{
+    m1 = 0;
+    m2 = 0;
+    m3 = 0;
+    m4 = 0;
+    printf("motor stop\n\r");
+}
+
+void mt_check(double out, int dr)
+{
+    // dr→ 1:x+  2:x-  3:y+  4:y-
+    while(1) {
+        if(dr == 1) {
+            m1 = out;
+            m2 = -out;
+            m3 = -out;
+            m4 = out;
+        } else if(dr == 2) {
+            m1 = -out;
+            m2 = out;
+            m3 = out;
+            m4 = -out;
+        } else if(dr == 3) {
+            m1 = out;
+            m2 = out;
+            m3 = -out;
+            m4 = -out;
+        } else if(dr == 4) {
+            m1 = -out;
+            m2 = -out;
+            m3 = out;
+            m4 = out;
+        }
+
+        printf("motor check out = %f\n\r",out);
+    }
+}
\ No newline at end of file