2月25日

Dependencies:   uw_28015 mbed ros_lib_kinetic move4wheel2 EC CruizCore_R6093U CruizCore_R1370P

Files at this revision

API Documentation at this revision

Comitter:
yuki0701
Date:
Tue Feb 25 01:20:43 2020 +0000
Commit message:
a;

Changed in this revision

CruizCore_R1370P.lib Show annotated file Show diff for this revision Revisions of this file
CruizCore_R6093U.lib Show annotated file Show diff for this revision Revisions of this file
EC.lib Show annotated file Show diff for this revision Revisions of this file
can/can.cpp Show annotated file Show diff for this revision Revisions of this file
can/can.h Show annotated file Show diff for this revision Revisions of this file
main.cpp Show annotated file Show diff for this revision Revisions of this file
manual/manual.cpp Show annotated file Show diff for this revision Revisions of this file
manual/manual.h Show annotated file Show diff for this revision Revisions of this file
mbed.bld Show annotated file Show diff for this revision Revisions of this file
move4wheel.lib Show annotated file Show diff for this revision Revisions of this file
movement/movement.cpp Show annotated file Show diff for this revision Revisions of this file
movement/movement.h Show annotated file Show diff for this revision Revisions of this file
pathfollowing/PathFollowing.cpp Show annotated file Show diff for this revision Revisions of this file
pathfollowing/PathFollowing.h Show annotated file Show diff for this revision Revisions of this file
ros_lib_kinetic.lib Show annotated file Show diff for this revision Revisions of this file
uw_28015.lib Show annotated file Show diff for this revision Revisions of this file
diff -r 000000000000 -r 44f9a43e4ab2 CruizCore_R1370P.lib
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/CruizCore_R1370P.lib	Tue Feb 25 01:20:43 2020 +0000
@@ -0,0 +1,1 @@
+http://os.mbed.com/teams/ROBOSTEP_LIBRARY/code/CruizCore_R1370P/#b034f6d0b378
diff -r 000000000000 -r 44f9a43e4ab2 CruizCore_R6093U.lib
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/CruizCore_R6093U.lib	Tue Feb 25 01:20:43 2020 +0000
@@ -0,0 +1,1 @@
+https://os.mbed.com/teams/2019-11/code/CruizCore_R6093U/#56f68dbbd195
diff -r 000000000000 -r 44f9a43e4ab2 EC.lib
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/EC.lib	Tue Feb 25 01:20:43 2020 +0000
@@ -0,0 +1,1 @@
+https://os.mbed.com/teams/2019-11/code/EC/#bb5068ea1444
diff -r 000000000000 -r 44f9a43e4ab2 can/can.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/can/can.cpp	Tue Feb 25 01:20:43 2020 +0000
@@ -0,0 +1,86 @@
+#include "mbed.h"
+#include "PathFollowing.h"
+#include "movement.h"
+#include "manual.h"
+#include "can.h"
+
+CAN can1(p30,p29);
+Ticker can_ticker;  //can用ticker
+
+DigitalOut cansend_led(LED1);  //cansend -> on
+DigitalOut canread_led(LED2);  //canread -> on
+
+int t1_r=0, T1=0; //動作番号(受け取った値、送信する値(int型))
+int k = 0;
+
+void can_readsend()
+{
+    CANMessage msg;
+    if(can1.read(msg)) {
+        //printf(" CAN success\n\r");
+        if(msg.id == 2) {
+            t1_r = msg.data[0];
+            //printf("main T1 = %d  t1_r = %d\n\r",T1,t1_r);
+        }
+
+    } else {
+        canread_led = 0;
+        //printf("fale\n\r");
+    }
+ /*   if(k > 100){
+           printf("T1 in can_read = %d\n\r",T1);
+           k = 0;
+    }
+    k++;*/
+    can_num[0] = T1;  //動作番号(id節約のため、can_ashileddata[]と一緒に送る)
+    //can_num[0] = 1;
+    
+    can_ashileddata2[0] = m1 >> 8;
+    can_ashileddata2[1] = m1 &255;
+
+    can_ashileddata2[2] = m2 >> 8;
+    can_ashileddata2[3] = m2 &255;
+
+    can_ashileddata2[4] = m3 >> 8;
+    can_ashileddata2[5] = m3 &255;
+
+    can_ashileddata2[6] = m4 >> 8;
+    can_ashileddata2[7] = m4 &255;
+    
+     
+    if(can1.write(CANMessage(1,can_num,1))) {
+        cansend_led = 1;
+    }
+
+    if(can1.write(CANMessage(4,can_ashileddata2,8))) {  //IDを4にして送信
+        //printf("success : %d \n\r",m1);
+        cansend_led = 1;
+    }
+
+    if(t1_r > T1) {
+        T1 = t1_r;
+    }
+    
+}
+
+void can_start()
+{
+
+    while(1) {
+
+        CANMessage msg;
+
+//        debug_printf("wait\n\r");
+        printf("wait\n\r");
+        wait(0.1);
+        if(can1.read(msg)) {
+            break;
+        }
+    }
+}
+
+void UserLoopSetting_can()
+{
+    can1.frequency(1000000);
+    can_ticker.attach(&can_readsend,0.01);  //遅かったら早める
+}
\ No newline at end of file
diff -r 000000000000 -r 44f9a43e4ab2 can/can.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/can/can.h	Tue Feb 25 01:20:43 2020 +0000
@@ -0,0 +1,13 @@
+#ifndef HARUROBO2019_CAN
+#define HARUROBO2019_CAN
+
+extern int T1;
+extern int t1_r;
+
+void can_readsend();
+
+void can_start();
+
+void UserLoopSetting_can();
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 44f9a43e4ab2 main.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/main.cpp	Tue Feb 25 01:20:43 2020 +0000
@@ -0,0 +1,68 @@
+#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 <ros.h>
+#include <geometry_msgs/Point.h>
+#include <geometry_msgs/Pose.h>
+
+ros::NodeHandle nh;
+geometry_msgs::Point posi_xyr;
+geometry_msgs::Quaternion usw_4info;
+
+ros::Publisher pub_xyr("/mbed_main1",&posi_xyr);
+ros::Publisher pub_usw("/mbed_main2",&usw_4info);
+
+Ticker cm_pc;
+#define PI 3.141592
+
+void cm_to_pc(){
+    
+    copy_xyr_usw();
+    
+    posi_xyr.x = info_x;
+    posi_xyr.y = info_y;
+    posi_xyr.z = info_r;
+    
+    usw_4info.x = usw_data1;
+    usw_4info.y = usw_data2;
+    usw_4info.z = usw_data3;
+    usw_4info.w = usw_data4;
+    
+    pub_xyr.publish(&posi_xyr);
+    pub_usw.publish(&usw_4info);
+}
+
+
+//-----mbed led------------------//点灯条件-----------------------//参照場所------------------------------//
+//DigitalOut cansend_led(LED1);  //cansend -> on                //can.cpp
+//DigitalOut canread_led(LED2);  //canread -> on                //can.cpp
+//DigitalOut debug_led(LED3);    //maxon debug programme -> on  //maxonsetting.cpp
+
+//////////////////////////////////////////////////////////////以下main文/////////////////////////////////////////////////////////////////
+
+int main()
+{
+    nh.getHardware()->setBaud(115200);
+    nh.initNode();
+    nh.advertise(pub_xyr);
+    nh.advertise(pub_usw);
+    
+    cm_pc.attach(&cm_to_pc,0.01);
+
+    UserLoopSetting_sensor();
+    
+    while(1) {
+
+        nh.spinOnce();
+        wait(0.01);
+
+    }
+
+}
\ No newline at end of file
diff -r 000000000000 -r 44f9a43e4ab2 manual/manual.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/manual/manual.cpp	Tue Feb 25 01:20:43 2020 +0000
@@ -0,0 +1,68 @@
+#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"
+
+#define PI 3.141592
+
+int id1_value[7]= {0};
+
+//-----手動用の変数宣言--------------------------------------------------------------------------//
+int stick_theta;  //ジョイスティックの角度
+int manual_xout,manual_yout;  //フィールド座標系のx,y方向の速度
+int manual_realxout,manual_realyout;  //機体座標系のx,y方向の速度
+int manual_rout;  //旋回速度
+
+void CalManualOut(int v,int r_out)  //vはθ方向の速度、r_outは旋回速度(正の値)
+//PS3ジョイスティックの x=127.5 かつ y>127.5 の直線を0°としてθをとる
+{
+    stick_theta = (short)((id1_value[1]<<8) | id1_value[2]);
+    //debug_printf("stick = %d\n\r",stick_theta);
+
+    //ジョイスティック方向の速度をフィールド座標系の速度に変換
+    manual_xout = v * sin(PI*stick_theta/180);
+    manual_yout = -v * cos(PI*stick_theta/180);
+
+    //フィールド座標系の速度を機体座標系の速度に変換
+    manual_realxout = manual_xout * cos(PI*now_angle/180) + manual_yout * sin(PI*now_angle/180);
+    manual_realyout = -manual_xout * sin(PI*now_angle/180) + manual_yout * cos(PI*now_angle/180);
+
+    if(id1_value[4] == 1) { //旋回速度を代入
+        manual_rout = 0;
+    } else if(id1_value[4] == 2) {
+        manual_rout = r_out;
+    } else if(id1_value[4] == 3) {
+        manual_rout = -r_out;
+    }
+
+
+}
+
+void ManualOut(int slow_v, int slow_r, int fast_v, int fast_r)
+{
+
+    calc_gyro();
+
+    if(id1_value[3]==1) { //BOTTONR1押したら減速
+        CalManualOut(slow_v,slow_r);
+    } else {
+        CalManualOut(fast_v,fast_r);
+    }
+
+    if(id1_value[5] == 1) { //ニュートラルポジションなら出力0
+        output(0,0,0,0);
+        base(manual_rout,manual_rout,manual_rout,manual_rout,4095);
+    } else {
+        CalMotorOut(manual_realxout,manual_realyout,0);
+        base(GetMotorOut(0)+manual_rout,GetMotorOut(1)+manual_rout,GetMotorOut(2)+manual_rout,GetMotorOut(3)+manual_rout,4095);
+    }
+
+    //MaxonControl(m1,m2,m3,m4);
+//    debug_printf("m1=%d m2=%d m3=%d m4=%d now_angle=%f\n\r",m1,m2,m3,m4,now_angle);
+    printf("m1=%d m2=%d m3=%d m4=%d now_angle=%f\n\r",m1,m2,m3,m4,now_angle);
+}
\ No newline at end of file
diff -r 000000000000 -r 44f9a43e4ab2 manual/manual.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/manual/manual.h	Tue Feb 25 01:20:43 2020 +0000
@@ -0,0 +1,10 @@
+#ifndef HARUROBO2019_MANUAL
+#define HARUROBO2019_MANUAL
+
+extern int id1_value[7];
+
+void CalManualOut(int v,int r_out);
+
+void ManualOut(int slow_v, int slow_r, int fast_v, int fast_r);
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 44f9a43e4ab2 mbed.bld
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/mbed.bld	Tue Feb 25 01:20:43 2020 +0000
@@ -0,0 +1,1 @@
+https://os.mbed.com/users/mbed_official/code/mbed/builds/3a7713b1edbc
\ No newline at end of file
diff -r 000000000000 -r 44f9a43e4ab2 move4wheel.lib
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/move4wheel.lib	Tue Feb 25 01:20:43 2020 +0000
@@ -0,0 +1,1 @@
+https://os.mbed.com/teams/F3RC4/code/move4wheel2/#fefdbba20795
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
diff -r 000000000000 -r 44f9a43e4ab2 movement/movement.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/movement/movement.h	Tue Feb 25 01:20:43 2020 +0000
@@ -0,0 +1,88 @@
+#ifndef HARUROBO2019_MOVEMENT
+#define HARUROBO2019_MOVEMENT
+
+extern char can_ashileddata[2];
+extern char can_ashileddata2[8];
+extern char can_num[1];
+extern double info_x, info_y, info_r;
+//extern char can_ashileddata3[2];
+//extern char can_ashileddata4[2];
+//extern char can_ashileddata5[2];
+
+void print_gyro();
+
+extern int16_t m1,m2,m3,m4;
+
+extern int flag;
+
+void UserLoopSetting_sensor();
+
+void UserLoopSetting_enc_right();
+
+void UserLoopSetting_enc_left();
+
+void calOmega();
+
+void cal_uw();
+
+void output(double FL,double BL,double BR,double FR);
+
+void base(double FL,double BL,double BR,double FR,double Max);
+
+void ashi_led();
+
+void calc_gyro();
+
+void calc_xy_enc();
+
+void set_cond(int t, int px, double bx, int py, double by);
+
+void calc_xy_usw(double tgt_angle);
+
+void uwflag_reset();
+
+void uwflag_change(int u1,int u2, int u3, int u4);
+
+void calc_xy(double tgt_angle, double u, double v);
+
+void copy_xyr_usw();
+
+void enc_correction(int x_select,int y_select);
+
+void enc_correction2(int x_plot1, int y_plot2);
+
+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);
+
+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);
+
+double spline_base(int i, int k, double t, int nv[]);
+
+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);
+
+void pos_correction(double tgt_x, double tgt_y, double tgt_angle, double u, double v, double v_base);
+
+void mt_stop();
+
+void mt_check(double out, int dr);
+#endif
\ No newline at end of file
diff -r 000000000000 -r 44f9a43e4ab2 pathfollowing/PathFollowing.cpp
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/pathfollowing/PathFollowing.cpp	Tue Feb 25 01:20:43 2020 +0000
@@ -0,0 +1,154 @@
+#include "PathFollowing.h"
+#include "mbed.h"
+#include "math.h"
+
+double p_out,r_out_max, q_out_max;
+double Kvq_p,Kvq_d,Kvr_p,Kvr_d;
+double diff_old,diffangle,diffangle_old;
+double out_dutyQ,out_dutyR;
+double now_angle,target_angle,old_angle,adj_angle;
+double now_timeQ,old_timeQ,now_timeR,old_timeR;
+double now_x, now_y;
+double diff_st,diff_tgt,diff_st_tgt,p_param;
+double usw_data1,usw_data2,usw_data3,usw_data4;
+
+Timer timer;
+
+//初期座標:A, 目標座標:B、機体位置:C、点Cから直線ABに下ろした垂線の足:H
+void XYRmotorout(double plot_x1, double plot_y1, double plot_x2, double plot_y2, double *ad_x_out, double *ad_y_out, double *ad_r_out, double speed1, double speed2 )  //プログラム使用時、now_x,now_yはグローバル変数として定義する必要あり
+//plot_x1,plot_y1:出発地点の座標
+//plot_x2,plot_y2:目標地点の座標
+//speed1:初期速度
+//speed2:目標速度
+{
+    double Vector_P[2] = {(plot_x2 - plot_x1), (plot_y2 - plot_y1)}; //ベクトルAB
+    double A_Vector_P = hypot(Vector_P[0], Vector_P[1]); //ベクトルABの大きさ(hypot(a,b)で√(a^2+b^2)を計算できる <math.h>))
+    double UnitVector_P[2] = {Vector_P[0]/A_Vector_P, Vector_P[1]/A_Vector_P}; //ベクトルABの単位ベクトル
+    double UnitVector_Q[2] = {UnitVector_P[1], -UnitVector_P[0]}; //ベクトルCHの単位ベクトル
+    double Vector_R[2] = {(now_x - plot_x1), (now_y - plot_y1)}; //ベクトルAC
+    double diff = UnitVector_P[0]*Vector_R[1] - UnitVector_P[1]*Vector_R[0]; //機体位置と直線ABの距離(外積を用いて計算)
+
+    //double VectorOut_P[2]= {0}; //ベクトルABに平行方向の出力をx軸方向、y軸方向の出力に分解
+
+///////////////////<XYRmotorout関数内>以下、ベクトルABに垂直な方向の誤差を埋めるPD制御(ベクトルABに垂直方向の出力を求め、x軸方向、y軸方向の出力に分解)//////////////////////
+
+    timer.start();
+    now_timeQ=timer.read();
+    out_dutyQ=Kvq_p*diff+Kvq_d*(diff-diff_old)/(now_timeQ-old_timeQ); //ベクトルABに垂直方向の出力を決定
+    diff_old=diff;
+
+    if(out_dutyQ>q_out_max)out_dutyQ=q_out_max;
+    if(out_dutyQ<-q_out_max)out_dutyQ=-q_out_max;
+
+    old_timeQ=now_timeQ;
+
+    double VectorOut_Q[2] = {out_dutyQ*UnitVector_Q[0], out_dutyQ*UnitVector_Q[1]}; //ベクトルABに垂直方向の出力をx軸方向、y軸方向の出力に分解
+
+///////////////////////////////<XYRmotorout関数内>以下、機体角度と目標角度の誤差を埋めるPD制御(旋回のための出力値を決定)//////////////////////////////////
+
+    now_timeR=timer.read();
+    diffangle=target_angle-now_angle;
+    out_dutyR=-(Kvr_p*diffangle+Kvr_d*(diffangle-diffangle_old)/(now_timeR-old_timeR));
+    diffangle_old=diffangle;
+
+    if(out_dutyR>r_out_max)out_dutyR=r_out_max;
+    if(out_dutyR<-r_out_max)out_dutyR=-r_out_max;
+
+    old_timeR=now_timeR;
+
+//////////////////////////<XYRmotorout関数内>以下、x軸方向、y軸方向、旋回の出力をそれぞれad_x_out,ad_y_out,ad_r_outの指すアドレスに書き込む/////////////////////////////
+////////////////////////////////////////////その際、x軸方向、y軸方向の出力はフィールドの座標系から機体の座標系に変換する。///////////////////////////////////////////////
+
+    diff_st = hypot(now_x-plot_x1,now_y-plot_y1); //出発座標と機体の位置の距離
+    diff_tgt = hypot(now_x - plot_x2, now_y - plot_y2); //機体の位置と目標座標の距離
+    diff_st_tgt = hypot(plot_x1-plot_x2,plot_y1-plot_y2); //出発座標と目標座標の距離
+
+    if(speed1 == speed2) { //等速移動
+
+        double VectorOut_P[2] = {speed1*UnitVector_P[0], speed1*UnitVector_P[1]};
+
+        *ad_x_out = (VectorOut_P[0]+VectorOut_Q[0])*cos(-now_angle*3.141592/180)-(VectorOut_P[1]+VectorOut_Q[1])*sin(-now_angle*3.141592/180);
+        *ad_y_out = (VectorOut_P[0]+VectorOut_Q[0])*sin(-now_angle*3.141592/180)+(VectorOut_P[1]+VectorOut_Q[1])*cos(-now_angle*3.141592/180);
+        *ad_r_out = out_dutyR;
+
+    } else if(speed2 == 0) { //減速移動(目標速度が0)→ベクトルABに垂直な方向の出力にもP制御をかける。
+
+        double VectorOut_P[2] = {speed1*UnitVector_P[0], speed1*UnitVector_P[1]};
+
+        if(diff_tgt > diff_st_tgt) {
+            diff_tgt = diff_st_tgt;
+        }
+
+        p_param=(diff_tgt/diff_st_tgt);
+
+        *ad_x_out = p_param*((VectorOut_P[0]+VectorOut_Q[0])*cos(-now_angle*3.141592/180)-(VectorOut_P[1]+VectorOut_Q[1])*sin(-now_angle*3.141592/180));
+        *ad_y_out = p_param*((VectorOut_P[0]+VectorOut_Q[0])*sin(-now_angle*3.141592/180)+(VectorOut_P[1]+VectorOut_Q[1])*cos(-now_angle*3.141592/180));
+        *ad_r_out = out_dutyR;
+
+    } else if(speed1 > speed2) { //減速移動(目標速度が0でない)
+
+        if(diff_tgt > diff_st_tgt) {
+            diff_tgt = diff_st_tgt;
+        }
+
+        p_param=(diff_tgt/diff_st_tgt);
+
+        double speed3 = speed2 + (speed1-speed2)*p_param;
+
+        double VectorOut_P[2] = {speed3*UnitVector_P[0], speed3*UnitVector_P[1]};
+
+        *ad_x_out = (VectorOut_P[0]+VectorOut_Q[0])*cos(-now_angle*3.141592/180)-(VectorOut_P[1]+VectorOut_Q[1])*sin(-now_angle*3.141592/180);
+        *ad_y_out = (VectorOut_P[0]+VectorOut_Q[0])*sin(-now_angle*3.141592/180)+(VectorOut_P[1]+VectorOut_Q[1])*cos(-now_angle*3.141592/180);
+        *ad_r_out = out_dutyR;
+
+    } else if(speed1 < speed2) { //加速移動(speed1)
+
+        if(diff_st > diff_st_tgt) {
+            diff_st = diff_st_tgt;
+        }
+
+        p_param=(diff_st/diff_st_tgt);
+
+        double speed4 = speed1 + (speed2-speed1)*p_param;
+
+        double VectorOut_P[2] = {speed4*UnitVector_P[0], speed4*UnitVector_P[1]};
+
+        *ad_x_out = (VectorOut_P[0]+VectorOut_Q[0])*cos(-now_angle*3.141592/180)-(VectorOut_P[1]+VectorOut_Q[1])*sin(-now_angle*3.141592/180);
+        *ad_y_out = (VectorOut_P[0]+VectorOut_Q[0])*sin(-now_angle*3.141592/180)+(VectorOut_P[1]+VectorOut_Q[1])*cos(-now_angle*3.141592/180);
+        *ad_r_out = out_dutyR;
+    }
+}
+
+////////////////////////////////////////////////////////////<XYRmotorout関数は以上>////////////////////////////////////////////////////////////////
+
+
+/*void set_p_out(double p)  //ベクトルABに平行方向の出力値設定関数
+{
+    p_out = p;
+}*/
+
+void q_setPDparam(double q_p,double q_d)  //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数
+{
+    Kvq_p=q_p;
+    Kvq_d=q_d;
+}
+
+void r_setPDparam(double r_p,double r_d)  //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数
+{
+    Kvr_p=r_p;
+    Kvr_d=r_d;
+}
+
+void set_r_out(double r)  //旋回時の最大出力値設定関数
+{
+    r_out_max = r;
+}
+
+void set_q_out(double q){
+    q_out_max = q;   
+}
+
+void set_target_angle(double t)  //機体の目標角度設定関数
+{
+    target_angle = t;
+}
diff -r 000000000000 -r 44f9a43e4ab2 pathfollowing/PathFollowing.h
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/pathfollowing/PathFollowing.h	Tue Feb 25 01:20:43 2020 +0000
@@ -0,0 +1,36 @@
+#ifndef HARUROBO2019_PATHFOLLOWING
+#define HARUROBO2019_PATHFOLLOWING
+
+extern double now_x,now_y,now_angle,old_angle,adj_angle;  //main.cppにこれらの値の読み込みを書くこと
+extern double now_timeQ,now_timeR;
+extern double usw_data1,usw_data2,usw_data3,usw_data4;
+
+void XYRmotorout(double plot_x1, double plot_y1, double plot_x2, double plot_y2, double *ad_x_out, double *ad_y_out, double *ad_r_out,double speed1,double speed2);
+//出発地点、目標地点の座標から機体のx軸方向、y軸方向、旋回の出力を算出する関数
+/*
+ *1.main分内でx_out,y_out,r_outをdouble型で定義
+ *2.XYRmotorout関数使用時は、num番目のx、y座標、num+1番目のx,y座標に加え、
+  x_out,y_out,r_outのアドレス(&x_out,&y_out,&r_out)を渡す→(XYRmotorout(座標×4つ,&x_out,&y_out,&r_out))
+*/
+
+//次の関数のパラメーターを定義すること
+
+//void set_p_out(double p);
+//ベクトルABに平行方向の出力値設定関数
+
+void q_setPDparam(double q_p,double q_d);
+//ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数
+
+void r_setPDparam(double r_p,double r_d);
+//機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数
+
+void set_r_out(double r);
+//旋回時の最大出力値設定関数
+
+void set_q_out(double q);
+//経路に垂直な方向の出力の最大値設定関数
+
+void set_target_angle(double t);
+//機体目標角度設定関数
+
+#endif
\ No newline at end of file
diff -r 000000000000 -r 44f9a43e4ab2 ros_lib_kinetic.lib
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/ros_lib_kinetic.lib	Tue Feb 25 01:20:43 2020 +0000
@@ -0,0 +1,1 @@
+https://os.mbed.com/users/garyservin/code/ros_lib_kinetic/#a849bf78d77f
diff -r 000000000000 -r 44f9a43e4ab2 uw_28015.lib
--- /dev/null	Thu Jan 01 00:00:00 1970 +0000
+++ b/uw_28015.lib	Tue Feb 25 01:20:43 2020 +0000
@@ -0,0 +1,1 @@
+https://os.mbed.com/users/yuki0701/code/uw_28015/#c5ad8660c8fd