2月25日
Dependencies: uw_28015 mbed ros_lib_kinetic move4wheel2 EC CruizCore_R6093U CruizCore_R1370P
movement/movement.cpp@0:44f9a43e4ab2, 2020-02-25 (annotated)
- Committer:
- yuki0701
- Date:
- Tue Feb 25 01:20:43 2020 +0000
- Revision:
- 0:44f9a43e4ab2
a;
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
yuki0701 | 0:44f9a43e4ab2 | 1 | #include "EC.h" |
yuki0701 | 0:44f9a43e4ab2 | 2 | #include "R1370P.h" |
yuki0701 | 0:44f9a43e4ab2 | 3 | #include "move4wheel.h" |
yuki0701 | 0:44f9a43e4ab2 | 4 | #include "mbed.h" |
yuki0701 | 0:44f9a43e4ab2 | 5 | #include "math.h" |
yuki0701 | 0:44f9a43e4ab2 | 6 | #include "PathFollowing.h" |
yuki0701 | 0:44f9a43e4ab2 | 7 | #include "movement.h" |
yuki0701 | 0:44f9a43e4ab2 | 8 | #include "manual.h" |
yuki0701 | 0:44f9a43e4ab2 | 9 | #include "can.h" |
yuki0701 | 0:44f9a43e4ab2 | 10 | #include "R6093U.h" |
yuki0701 | 0:44f9a43e4ab2 | 11 | #include "uw.h" |
yuki0701 | 0:44f9a43e4ab2 | 12 | |
yuki0701 | 0:44f9a43e4ab2 | 13 | #define PI 3.141592 |
yuki0701 | 0:44f9a43e4ab2 | 14 | |
yuki0701 | 0:44f9a43e4ab2 | 15 | char can_ashileddata[2]= {0}; |
yuki0701 | 0:44f9a43e4ab2 | 16 | char can_ashileddata2[8]= {0}; |
yuki0701 | 0:44f9a43e4ab2 | 17 | char can_num[1]= {0}; |
yuki0701 | 0:44f9a43e4ab2 | 18 | double info_x, info_y, info_r; |
yuki0701 | 0:44f9a43e4ab2 | 19 | |
yuki0701 | 0:44f9a43e4ab2 | 20 | //char can_ashileddata3[2]= {0}; |
yuki0701 | 0:44f9a43e4ab2 | 21 | //char can_ashileddata4[2]= {0}; |
yuki0701 | 0:44f9a43e4ab2 | 22 | //char can_ashileddata5[2]= {0}; |
yuki0701 | 0:44f9a43e4ab2 | 23 | |
yuki0701 | 0:44f9a43e4ab2 | 24 | int can_ashileddata0_0,can_ashileddata0_1,can_ashileddata0_2,can_ashileddata0_3; |
yuki0701 | 0:44f9a43e4ab2 | 25 | |
yuki0701 | 0:44f9a43e4ab2 | 26 | Ec EC2(p16,p15,NC,2048,0.05); |
yuki0701 | 0:44f9a43e4ab2 | 27 | Ec EC1(p18,p17,NC,2048,0.05); |
yuki0701 | 0:44f9a43e4ab2 | 28 | |
yuki0701 | 0:44f9a43e4ab2 | 29 | |
yuki0701 | 0:44f9a43e4ab2 | 30 | Uw uw1(p28); |
yuki0701 | 0:44f9a43e4ab2 | 31 | Uw uw4(p27); |
yuki0701 | 0:44f9a43e4ab2 | 32 | |
yuki0701 | 0:44f9a43e4ab2 | 33 | |
yuki0701 | 0:44f9a43e4ab2 | 34 | Ticker ec_ticker; //ec角速度計算用ticker |
yuki0701 | 0:44f9a43e4ab2 | 35 | Ticker uw_ticker; //uw値取得用ticker |
yuki0701 | 0:44f9a43e4ab2 | 36 | |
yuki0701 | 0:44f9a43e4ab2 | 37 | //R1370P gyro(p9,p10); |
yuki0701 | 0:44f9a43e4ab2 | 38 | |
yuki0701 | 0:44f9a43e4ab2 | 39 | R6093U gyro(p9,p10); |
yuki0701 | 0:44f9a43e4ab2 | 40 | |
yuki0701 | 0:44f9a43e4ab2 | 41 | double new_dist1=0,new_dist2=0; |
yuki0701 | 0:44f9a43e4ab2 | 42 | double old_dist1=0,old_dist2=0; |
yuki0701 | 0:44f9a43e4ab2 | 43 | double d_dist1=0,d_dist2=0; //座標計算用関数 |
yuki0701 | 0:44f9a43e4ab2 | 44 | double d_x,d_y; |
yuki0701 | 0:44f9a43e4ab2 | 45 | //現在地X,y座標、現在角度については、PathFollowingでnow_x,now_y,now_angleを定義済 |
yuki0701 | 0:44f9a43e4ab2 | 46 | double start_x=0,start_y=0; //スタート位置 |
yuki0701 | 0:44f9a43e4ab2 | 47 | double x_out,y_out,r_out; //出力値 |
yuki0701 | 0:44f9a43e4ab2 | 48 | |
yuki0701 | 0:44f9a43e4ab2 | 49 | int16_t m1=0, m2=0, m3=0, m4=0; //int16bit = int2byte |
yuki0701 | 0:44f9a43e4ab2 | 50 | |
yuki0701 | 0:44f9a43e4ab2 | 51 | double xy_type,pm_typeX,pm_typeY,x_base,y_base; |
yuki0701 | 0:44f9a43e4ab2 | 52 | |
yuki0701 | 0:44f9a43e4ab2 | 53 | int flag; |
yuki0701 | 0:44f9a43e4ab2 | 54 | double angle_base = 0; |
yuki0701 | 0:44f9a43e4ab2 | 55 | |
yuki0701 | 0:44f9a43e4ab2 | 56 | int RL_mode; |
yuki0701 | 0:44f9a43e4ab2 | 57 | |
yuki0701 | 0:44f9a43e4ab2 | 58 | int uw_flag1 = 0,uw_flag2 = 0,uw_flag3 = 0,uw_flag4 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 59 | |
yuki0701 | 0:44f9a43e4ab2 | 60 | ///////////////////機体情報をメンバとする構造体"robo_data"と構造体型変数info(←この変数に各センサーにより求めた機体情報(機体位置/機体角度)を格納する)の宣言///////////////// |
yuki0701 | 0:44f9a43e4ab2 | 61 | |
yuki0701 | 0:44f9a43e4ab2 | 62 | /*「info.(機体情報の種類).(使用センサーの種類)」に各情報を格納する |
yuki0701 | 0:44f9a43e4ab2 | 63 | *状況に応じて、どのセンサーにより算出した情報を信用するかを選択し、その都度now_angle,now_x,now_yに代入する。(何種類かのセンサーの情報を混ぜて使用することも可能) |
yuki0701 | 0:44f9a43e4ab2 | 64 | *(ex) |
yuki0701 | 0:44f9a43e4ab2 | 65 | *info.nowX.enc → エンコーダにより算出した機体位置のx座標 |
yuki0701 | 0:44f9a43e4ab2 | 66 | *info.nowY.usw → 超音波センサーにより求めた機体位置のy座標 |
yuki0701 | 0:44f9a43e4ab2 | 67 | */ |
yuki0701 | 0:44f9a43e4ab2 | 68 | |
yuki0701 | 0:44f9a43e4ab2 | 69 | typedef struct { //使用センサーの種類 |
yuki0701 | 0:44f9a43e4ab2 | 70 | double usw; //超音波センサー |
yuki0701 | 0:44f9a43e4ab2 | 71 | double enc; //エンコーダ |
yuki0701 | 0:44f9a43e4ab2 | 72 | double gyro; //ジャイロ |
yuki0701 | 0:44f9a43e4ab2 | 73 | //double line;//ラインセンサー |
yuki0701 | 0:44f9a43e4ab2 | 74 | } robo_sensor; |
yuki0701 | 0:44f9a43e4ab2 | 75 | |
yuki0701 | 0:44f9a43e4ab2 | 76 | typedef struct { //機体情報の種類 |
yuki0701 | 0:44f9a43e4ab2 | 77 | robo_sensor angle; //←機体角度は超音波センサーやラインセンサーからも算出可能なので一応格納先を用意したが、ジャイロの値を完全に信用してもいいかも |
yuki0701 | 0:44f9a43e4ab2 | 78 | robo_sensor nowX; |
yuki0701 | 0:44f9a43e4ab2 | 79 | robo_sensor nowY; |
yuki0701 | 0:44f9a43e4ab2 | 80 | } robo_data; |
yuki0701 | 0:44f9a43e4ab2 | 81 | |
yuki0701 | 0:44f9a43e4ab2 | 82 | robo_data info= {{0,0,0},{0,0,0},{0,0,0}}; //全てのデータを0に初期化 |
yuki0701 | 0:44f9a43e4ab2 | 83 | |
yuki0701 | 0:44f9a43e4ab2 | 84 | //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// |
yuki0701 | 0:44f9a43e4ab2 | 85 | |
yuki0701 | 0:44f9a43e4ab2 | 86 | void UserLoopSetting_sensor() |
yuki0701 | 0:44f9a43e4ab2 | 87 | { |
yuki0701 | 0:44f9a43e4ab2 | 88 | |
yuki0701 | 0:44f9a43e4ab2 | 89 | gyro.initialize(); |
yuki0701 | 0:44f9a43e4ab2 | 90 | ec_ticker.attach(&calOmega,0.02); //0.05秒間隔で角速度を計算 |
yuki0701 | 0:44f9a43e4ab2 | 91 | uw_ticker.attach(&cal_uw,0.05); |
yuki0701 | 0:44f9a43e4ab2 | 92 | EC1.setDiameter_mm(70); |
yuki0701 | 0:44f9a43e4ab2 | 93 | EC2.setDiameter_mm(70); //測定輪半径//後で測定 |
yuki0701 | 0:44f9a43e4ab2 | 94 | //info.nowX.enc = 457; //初期位置の設定 |
yuki0701 | 0:44f9a43e4ab2 | 95 | //info.nowY.enc = 457; |
yuki0701 | 0:44f9a43e4ab2 | 96 | info.nowX.enc = 0; //初期位置の設定 |
yuki0701 | 0:44f9a43e4ab2 | 97 | info.nowY.enc = 0; |
yuki0701 | 0:44f9a43e4ab2 | 98 | angle_base = -90; |
yuki0701 | 0:44f9a43e4ab2 | 99 | } |
yuki0701 | 0:44f9a43e4ab2 | 100 | |
yuki0701 | 0:44f9a43e4ab2 | 101 | void UserLoopSetting_enc_right() |
yuki0701 | 0:44f9a43e4ab2 | 102 | { |
yuki0701 | 0:44f9a43e4ab2 | 103 | info.nowX.enc = 3112; //エンコーダの初期位置の設定(右側フィールド) |
yuki0701 | 0:44f9a43e4ab2 | 104 | info.nowY.enc = 3500; |
yuki0701 | 0:44f9a43e4ab2 | 105 | RL_mode = 0; |
yuki0701 | 0:44f9a43e4ab2 | 106 | } |
yuki0701 | 0:44f9a43e4ab2 | 107 | |
yuki0701 | 0:44f9a43e4ab2 | 108 | void UserLoopSetting_enc_left() |
yuki0701 | 0:44f9a43e4ab2 | 109 | { |
yuki0701 | 0:44f9a43e4ab2 | 110 | info.nowX.enc = -3112; //エンコーダの初期位置の設定(左側フィールド) |
yuki0701 | 0:44f9a43e4ab2 | 111 | info.nowY.enc = 3500; |
yuki0701 | 0:44f9a43e4ab2 | 112 | RL_mode = 1; |
yuki0701 | 0:44f9a43e4ab2 | 113 | } |
yuki0701 | 0:44f9a43e4ab2 | 114 | |
yuki0701 | 0:44f9a43e4ab2 | 115 | void calOmega() //角速度計算関数 |
yuki0701 | 0:44f9a43e4ab2 | 116 | { |
yuki0701 | 0:44f9a43e4ab2 | 117 | EC1.CalOmega(); |
yuki0701 | 0:44f9a43e4ab2 | 118 | EC2.CalOmega(); |
yuki0701 | 0:44f9a43e4ab2 | 119 | calc_xy_enc(); |
yuki0701 | 0:44f9a43e4ab2 | 120 | |
yuki0701 | 0:44f9a43e4ab2 | 121 | //usw_data1 = 10 * uw1.get_dist(); |
yuki0701 | 0:44f9a43e4ab2 | 122 | ////usw_data2 = 10 * uw2.get_dist(); |
yuki0701 | 0:44f9a43e4ab2 | 123 | //usw_data3 = 10 * uw3.get_dist(); |
yuki0701 | 0:44f9a43e4ab2 | 124 | ////usw_data4 = 10 * uw4.get_dist(); |
yuki0701 | 0:44f9a43e4ab2 | 125 | } |
yuki0701 | 0:44f9a43e4ab2 | 126 | |
yuki0701 | 0:44f9a43e4ab2 | 127 | void cal_uw() //uw値取得用 |
yuki0701 | 0:44f9a43e4ab2 | 128 | { |
yuki0701 | 0:44f9a43e4ab2 | 129 | if(uw_flag1 == 1) { |
yuki0701 | 0:44f9a43e4ab2 | 130 | usw_data1 = 10 * uw1.get_dist(); |
yuki0701 | 0:44f9a43e4ab2 | 131 | //printf("uw1 = %f\n\r",usw_data1); |
yuki0701 | 0:44f9a43e4ab2 | 132 | } |
yuki0701 | 0:44f9a43e4ab2 | 133 | if(uw_flag2 == 1) { |
yuki0701 | 0:44f9a43e4ab2 | 134 | //usw_data2 = 10 * uw2.get_dist(); |
yuki0701 | 0:44f9a43e4ab2 | 135 | } |
yuki0701 | 0:44f9a43e4ab2 | 136 | if(uw_flag3 == 1) { |
yuki0701 | 0:44f9a43e4ab2 | 137 | //usw_data3 = 10 * uw3.get_dist(); |
yuki0701 | 0:44f9a43e4ab2 | 138 | } |
yuki0701 | 0:44f9a43e4ab2 | 139 | if(uw_flag4 == 1) { |
yuki0701 | 0:44f9a43e4ab2 | 140 | usw_data4 = 10 * uw4.get_dist(); |
yuki0701 | 0:44f9a43e4ab2 | 141 | //printf("uw4 = %f\n\r",usw_data4); |
yuki0701 | 0:44f9a43e4ab2 | 142 | } |
yuki0701 | 0:44f9a43e4ab2 | 143 | } |
yuki0701 | 0:44f9a43e4ab2 | 144 | |
yuki0701 | 0:44f9a43e4ab2 | 145 | void output(double FL,double BL,double BR,double FR) |
yuki0701 | 0:44f9a43e4ab2 | 146 | { |
yuki0701 | 0:44f9a43e4ab2 | 147 | m1=FL; |
yuki0701 | 0:44f9a43e4ab2 | 148 | m2=BL; |
yuki0701 | 0:44f9a43e4ab2 | 149 | m3=BR; |
yuki0701 | 0:44f9a43e4ab2 | 150 | m4=FR; |
yuki0701 | 0:44f9a43e4ab2 | 151 | } |
yuki0701 | 0:44f9a43e4ab2 | 152 | |
yuki0701 | 0:44f9a43e4ab2 | 153 | void base(double FL,double BL,double BR,double FR,double Max) |
yuki0701 | 0:44f9a43e4ab2 | 154 | //いろんな加算をしても最大OR最小がMaxになるような補正//絶対値が一番でかいやつで除算 |
yuki0701 | 0:44f9a43e4ab2 | 155 | //DCモーターならMax=1、マクソンは-4095~4095だからMax=4095にする |
yuki0701 | 0:44f9a43e4ab2 | 156 | { |
yuki0701 | 0:44f9a43e4ab2 | 157 | if(fabs(FL)>=Max||fabs(BL)>=Max||fabs(BR)>=Max||fabs(FR)>=Max) { |
yuki0701 | 0:44f9a43e4ab2 | 158 | |
yuki0701 | 0:44f9a43e4ab2 | 159 | if (fabs(FL)>=fabs(BL)&&fabs(FL)>=fabs(BR)&&fabs(FL)>=fabs(FR))output(Max*FL/fabs(FL),Max*BL/fabs(FL),Max*BR/fabs(FL),Max*FR/fabs(FL)); |
yuki0701 | 0:44f9a43e4ab2 | 160 | else if(fabs(BL)>=fabs(FL)&&fabs(BL)>=fabs(BR)&&fabs(BL)>=fabs(FR))output(Max*FL/fabs(BL),Max*BL/fabs(BL),Max*BR/fabs(BL),Max*FR/fabs(BL)); |
yuki0701 | 0:44f9a43e4ab2 | 161 | else if(fabs(BR)>=fabs(FL)&&fabs(BR)>=fabs(BL)&&fabs(BR)>=fabs(FR))output(Max*FL/fabs(BR),Max*BL/fabs(BR),Max*BR/fabs(BR),Max*FR/fabs(BR)); |
yuki0701 | 0:44f9a43e4ab2 | 162 | else output(Max*FL/fabs(FR),Max*BL/fabs(FR),Max*BR/fabs(FR),Max*FR/fabs(FR)); |
yuki0701 | 0:44f9a43e4ab2 | 163 | } else { |
yuki0701 | 0:44f9a43e4ab2 | 164 | output(FL,BL,BR,FR); |
yuki0701 | 0:44f9a43e4ab2 | 165 | } |
yuki0701 | 0:44f9a43e4ab2 | 166 | } |
yuki0701 | 0:44f9a43e4ab2 | 167 | |
yuki0701 | 0:44f9a43e4ab2 | 168 | void ashi_led() |
yuki0701 | 0:44f9a43e4ab2 | 169 | { |
yuki0701 | 0:44f9a43e4ab2 | 170 | if(now_angle > -1 && now_angle < 1) { |
yuki0701 | 0:44f9a43e4ab2 | 171 | can_ashileddata0_0 = 1; |
yuki0701 | 0:44f9a43e4ab2 | 172 | } else { |
yuki0701 | 0:44f9a43e4ab2 | 173 | can_ashileddata0_0 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 174 | } |
yuki0701 | 0:44f9a43e4ab2 | 175 | |
yuki0701 | 0:44f9a43e4ab2 | 176 | if(now_angle > 350) { |
yuki0701 | 0:44f9a43e4ab2 | 177 | can_ashileddata0_1 = 1; |
yuki0701 | 0:44f9a43e4ab2 | 178 | } else { |
yuki0701 | 0:44f9a43e4ab2 | 179 | can_ashileddata0_1 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 180 | } |
yuki0701 | 0:44f9a43e4ab2 | 181 | |
yuki0701 | 0:44f9a43e4ab2 | 182 | if(RL_mode == 0) { |
yuki0701 | 0:44f9a43e4ab2 | 183 | if(now_x > 3110 && now_x < 3114) { |
yuki0701 | 0:44f9a43e4ab2 | 184 | can_ashileddata0_2 = 1; |
yuki0701 | 0:44f9a43e4ab2 | 185 | } else { |
yuki0701 | 0:44f9a43e4ab2 | 186 | can_ashileddata0_2 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 187 | } |
yuki0701 | 0:44f9a43e4ab2 | 188 | |
yuki0701 | 0:44f9a43e4ab2 | 189 | if(now_y > 3498 && now_y < 3502) { |
yuki0701 | 0:44f9a43e4ab2 | 190 | can_ashileddata0_3 = 1; |
yuki0701 | 0:44f9a43e4ab2 | 191 | } else { |
yuki0701 | 0:44f9a43e4ab2 | 192 | can_ashileddata0_3 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 193 | } |
yuki0701 | 0:44f9a43e4ab2 | 194 | } else if(RL_mode == 1) { |
yuki0701 | 0:44f9a43e4ab2 | 195 | if(now_x > -3114 && now_x < -3110) { |
yuki0701 | 0:44f9a43e4ab2 | 196 | can_ashileddata0_2 = 1; |
yuki0701 | 0:44f9a43e4ab2 | 197 | } else { |
yuki0701 | 0:44f9a43e4ab2 | 198 | can_ashileddata0_2 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 199 | } |
yuki0701 | 0:44f9a43e4ab2 | 200 | |
yuki0701 | 0:44f9a43e4ab2 | 201 | if(now_y > 3498 && now_y < 3502) { |
yuki0701 | 0:44f9a43e4ab2 | 202 | can_ashileddata0_3 = 1; |
yuki0701 | 0:44f9a43e4ab2 | 203 | } else { |
yuki0701 | 0:44f9a43e4ab2 | 204 | can_ashileddata0_3 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 205 | } |
yuki0701 | 0:44f9a43e4ab2 | 206 | } |
yuki0701 | 0:44f9a43e4ab2 | 207 | |
yuki0701 | 0:44f9a43e4ab2 | 208 | can_ashileddata[0] = (can_ashileddata0_0<<7 | can_ashileddata0_1<<6 | can_ashileddata0_2<<5 | can_ashileddata0_3<<4); |
yuki0701 | 0:44f9a43e4ab2 | 209 | } |
yuki0701 | 0:44f9a43e4ab2 | 210 | |
yuki0701 | 0:44f9a43e4ab2 | 211 | void calc_gyro() |
yuki0701 | 0:44f9a43e4ab2 | 212 | { |
yuki0701 | 0:44f9a43e4ab2 | 213 | //now_angle=gyro.getAngle(); //ジャイロの値読み込み |
yuki0701 | 0:44f9a43e4ab2 | 214 | now_angle = -gyro.getZ_Angle() + angle_base; |
yuki0701 | 0:44f9a43e4ab2 | 215 | } |
yuki0701 | 0:44f9a43e4ab2 | 216 | |
yuki0701 | 0:44f9a43e4ab2 | 217 | void print_gyro() |
yuki0701 | 0:44f9a43e4ab2 | 218 | { |
yuki0701 | 0:44f9a43e4ab2 | 219 | while(1) { |
yuki0701 | 0:44f9a43e4ab2 | 220 | //printf("now_gyro = %f\n\r",-gyro.getAngle()); |
yuki0701 | 0:44f9a43e4ab2 | 221 | } |
yuki0701 | 0:44f9a43e4ab2 | 222 | |
yuki0701 | 0:44f9a43e4ab2 | 223 | } |
yuki0701 | 0:44f9a43e4ab2 | 224 | |
yuki0701 | 0:44f9a43e4ab2 | 225 | void calc_xy_enc() //エンコーダ&ジャイロによる座標計算 |
yuki0701 | 0:44f9a43e4ab2 | 226 | { |
yuki0701 | 0:44f9a43e4ab2 | 227 | old_angle=now_angle; |
yuki0701 | 0:44f9a43e4ab2 | 228 | //now_angle=gyro.getAngle(); //ジャイロの値読み込み |
yuki0701 | 0:44f9a43e4ab2 | 229 | now_angle = -gyro.getZ_Angle() + angle_base; |
yuki0701 | 0:44f9a43e4ab2 | 230 | adj_angle=(now_angle+old_angle)/2; |
yuki0701 | 0:44f9a43e4ab2 | 231 | |
yuki0701 | 0:44f9a43e4ab2 | 232 | new_dist1=EC1.getDistance_mm(); |
yuki0701 | 0:44f9a43e4ab2 | 233 | new_dist2=EC2.getDistance_mm(); |
yuki0701 | 0:44f9a43e4ab2 | 234 | d_dist1=new_dist1-old_dist1; |
yuki0701 | 0:44f9a43e4ab2 | 235 | d_dist2=new_dist2-old_dist2; |
yuki0701 | 0:44f9a43e4ab2 | 236 | old_dist1=new_dist1; |
yuki0701 | 0:44f9a43e4ab2 | 237 | old_dist2=new_dist2; //微小時間当たりのエンコーダ読み込み |
yuki0701 | 0:44f9a43e4ab2 | 238 | |
yuki0701 | 0:44f9a43e4ab2 | 239 | d_x=d_dist2*sin(adj_angle*PI/180)-d_dist1*cos(adj_angle*PI/180); |
yuki0701 | 0:44f9a43e4ab2 | 240 | d_y=d_dist2*cos(adj_angle*PI/180)+d_dist1*sin(adj_angle*PI/180); //微小時間毎の座標変化 |
yuki0701 | 0:44f9a43e4ab2 | 241 | info.nowX.enc = info.nowX.enc + d_x; |
yuki0701 | 0:44f9a43e4ab2 | 242 | info.nowY.enc = info.nowY.enc - d_y; //微小時間毎に座標に加算 |
yuki0701 | 0:44f9a43e4ab2 | 243 | } |
yuki0701 | 0:44f9a43e4ab2 | 244 | |
yuki0701 | 0:44f9a43e4ab2 | 245 | |
yuki0701 | 0:44f9a43e4ab2 | 246 | void set_cond(int t, int px, double bx, int py, double by) //超音波センサーを使用するときの条件設定関数 |
yuki0701 | 0:44f9a43e4ab2 | 247 | { |
yuki0701 | 0:44f9a43e4ab2 | 248 | //引数の詳細は関数"calc_xy_usw"参照 |
yuki0701 | 0:44f9a43e4ab2 | 249 | |
yuki0701 | 0:44f9a43e4ab2 | 250 | xy_type = t; |
yuki0701 | 0:44f9a43e4ab2 | 251 | |
yuki0701 | 0:44f9a43e4ab2 | 252 | pm_typeX = px; |
yuki0701 | 0:44f9a43e4ab2 | 253 | x_base = bx; |
yuki0701 | 0:44f9a43e4ab2 | 254 | |
yuki0701 | 0:44f9a43e4ab2 | 255 | pm_typeY = py; |
yuki0701 | 0:44f9a43e4ab2 | 256 | y_base = by; |
yuki0701 | 0:44f9a43e4ab2 | 257 | } |
yuki0701 | 0:44f9a43e4ab2 | 258 | |
yuki0701 | 0:44f9a43e4ab2 | 259 | void calc_xy_usw(double tgt_angle) //超音波センサーによる座標計算(機体が旋回する場合はこの方法による座標計算は出来ない) |
yuki0701 | 0:44f9a43e4ab2 | 260 | { |
yuki0701 | 0:44f9a43e4ab2 | 261 | //tgt_angle:機体の目標角度(運動初期角度と同じ/今大会では0,90,180のみ) |
yuki0701 | 0:44f9a43e4ab2 | 262 | //xy_type:(0:Y軸平行の壁を読む/1:X軸平行の壁を読む/2:X,Y軸平行の壁を共に読む) |
yuki0701 | 0:44f9a43e4ab2 | 263 | //pm_typeX,pm_typeY:(0:各軸正方向側の壁を読む/1:各軸負方向側の壁を読む) |
yuki0701 | 0:44f9a43e4ab2 | 264 | //x_base,y_base:超音波センサーで読む壁の座標(y軸並行の壁のx座標/x軸平行の壁のy座標) |
yuki0701 | 0:44f9a43e4ab2 | 265 | |
yuki0701 | 0:44f9a43e4ab2 | 266 | double R1=414.5,R2=414.5,R3=414.5,R4=414.5; //機体の中心から各超音波センサーが付いている面までの距離 |
yuki0701 | 0:44f9a43e4ab2 | 267 | double D1=-237.5,D2=237.5,D3=237.5,D4=-237.5; //各超音波センサーが付いている面の中心から各超音波センサーまでの距離(時計回りを正とする) |
yuki0701 | 0:44f9a43e4ab2 | 268 | |
yuki0701 | 0:44f9a43e4ab2 | 269 | // now_angle=gyro.getAngle(); //ジャイロの値読み込み |
yuki0701 | 0:44f9a43e4ab2 | 270 | now_angle = -gyro.getZ_Angle() + angle_base ; |
yuki0701 | 0:44f9a43e4ab2 | 271 | |
yuki0701 | 0:44f9a43e4ab2 | 272 | if(tgt_angle > -45 && tgt_angle < 45) { |
yuki0701 | 0:44f9a43e4ab2 | 273 | if((xy_type==0 || xy_type==2) && pm_typeX==0) { |
yuki0701 | 0:44f9a43e4ab2 | 274 | |
yuki0701 | 0:44f9a43e4ab2 | 275 | info.nowX.usw = x_base - (usw_data4 + R4*cos(now_angle*PI/180) + D4*sin(now_angle*PI/180)); |
yuki0701 | 0:44f9a43e4ab2 | 276 | uw_flag4 = 1; |
yuki0701 | 0:44f9a43e4ab2 | 277 | |
yuki0701 | 0:44f9a43e4ab2 | 278 | } else if((xy_type==0 || xy_type==2) && pm_typeX==1) { |
yuki0701 | 0:44f9a43e4ab2 | 279 | |
yuki0701 | 0:44f9a43e4ab2 | 280 | info.nowX.usw = x_base + (usw_data3 + R3*cos(now_angle*PI/180) + D3*sin(now_angle*PI/180)); |
yuki0701 | 0:44f9a43e4ab2 | 281 | uw_flag3 = 1; |
yuki0701 | 0:44f9a43e4ab2 | 282 | |
yuki0701 | 0:44f9a43e4ab2 | 283 | } |
yuki0701 | 0:44f9a43e4ab2 | 284 | if((xy_type==1 || xy_type==2) && pm_typeY==0) { |
yuki0701 | 0:44f9a43e4ab2 | 285 | |
yuki0701 | 0:44f9a43e4ab2 | 286 | info.nowY.usw = y_base - (usw_data2 + R2*cos(now_angle*PI/180) + D2*sin(now_angle*PI/180)); |
yuki0701 | 0:44f9a43e4ab2 | 287 | uw_flag2 = 1; |
yuki0701 | 0:44f9a43e4ab2 | 288 | |
yuki0701 | 0:44f9a43e4ab2 | 289 | } else if((xy_type==1 || xy_type==2) && pm_typeY==1) { |
yuki0701 | 0:44f9a43e4ab2 | 290 | |
yuki0701 | 0:44f9a43e4ab2 | 291 | info.nowY.usw = y_base + (usw_data1 + R1*cos(now_angle*PI/180) + D1*sin(now_angle*PI/180)); |
yuki0701 | 0:44f9a43e4ab2 | 292 | uw_flag1 = 1; |
yuki0701 | 0:44f9a43e4ab2 | 293 | |
yuki0701 | 0:44f9a43e4ab2 | 294 | } |
yuki0701 | 0:44f9a43e4ab2 | 295 | |
yuki0701 | 0:44f9a43e4ab2 | 296 | } else if(tgt_angle > 45 && tgt_angle < 135) { |
yuki0701 | 0:44f9a43e4ab2 | 297 | if((xy_type==0 || xy_type==2) && pm_typeX==0) { |
yuki0701 | 0:44f9a43e4ab2 | 298 | |
yuki0701 | 0:44f9a43e4ab2 | 299 | info.nowX.usw = x_base - (usw_data1 + R1*cos((now_angle-tgt_angle)*PI/180) + D1*sin((now_angle-tgt_angle)*PI/180)); |
yuki0701 | 0:44f9a43e4ab2 | 300 | uw_flag1 = 1; |
yuki0701 | 0:44f9a43e4ab2 | 301 | |
yuki0701 | 0:44f9a43e4ab2 | 302 | } else if((xy_type==0 || xy_type==2) && pm_typeX==1) { |
yuki0701 | 0:44f9a43e4ab2 | 303 | |
yuki0701 | 0:44f9a43e4ab2 | 304 | info.nowX.usw = x_base + (usw_data2 + R2*cos((now_angle-tgt_angle)*PI/180) + D2*sin((now_angle-tgt_angle)*PI/180)); |
yuki0701 | 0:44f9a43e4ab2 | 305 | uw_flag2 = 1; |
yuki0701 | 0:44f9a43e4ab2 | 306 | |
yuki0701 | 0:44f9a43e4ab2 | 307 | } |
yuki0701 | 0:44f9a43e4ab2 | 308 | if((xy_type==1 || xy_type==2) && pm_typeY==0) { |
yuki0701 | 0:44f9a43e4ab2 | 309 | |
yuki0701 | 0:44f9a43e4ab2 | 310 | info.nowY.usw = y_base - (usw_data4 + R4*cos((now_angle-tgt_angle)*PI/180) + D4*sin((now_angle-tgt_angle)*PI/180)); |
yuki0701 | 0:44f9a43e4ab2 | 311 | uw_flag4 = 1; |
yuki0701 | 0:44f9a43e4ab2 | 312 | |
yuki0701 | 0:44f9a43e4ab2 | 313 | } else if((xy_type==1 || xy_type==2) && pm_typeY==1) { |
yuki0701 | 0:44f9a43e4ab2 | 314 | |
yuki0701 | 0:44f9a43e4ab2 | 315 | info.nowY.usw = y_base + (usw_data3 + R3*cos((now_angle-tgt_angle)*PI/180) + D3*sin((now_angle-tgt_angle)*PI/180)); |
yuki0701 | 0:44f9a43e4ab2 | 316 | uw_flag3 = 1; |
yuki0701 | 0:44f9a43e4ab2 | 317 | |
yuki0701 | 0:44f9a43e4ab2 | 318 | } |
yuki0701 | 0:44f9a43e4ab2 | 319 | |
yuki0701 | 0:44f9a43e4ab2 | 320 | } else if((tgt_angle > 135 && tgt_angle < 225) || (tgt_angle > -225 && tgt_angle < -135)) { |
yuki0701 | 0:44f9a43e4ab2 | 321 | if((xy_type==0 || xy_type==2) && pm_typeX==0) { |
yuki0701 | 0:44f9a43e4ab2 | 322 | |
yuki0701 | 0:44f9a43e4ab2 | 323 | info.nowX.usw = x_base - (usw_data3 + R3*cos((now_angle-tgt_angle)*PI/180) + D3*sin((now_angle-tgt_angle)*PI/180)); |
yuki0701 | 0:44f9a43e4ab2 | 324 | uw_flag3 = 1; |
yuki0701 | 0:44f9a43e4ab2 | 325 | |
yuki0701 | 0:44f9a43e4ab2 | 326 | } else if((xy_type==0 || xy_type==2) && pm_typeX==1) { |
yuki0701 | 0:44f9a43e4ab2 | 327 | |
yuki0701 | 0:44f9a43e4ab2 | 328 | info.nowX.usw = x_base + (usw_data4 + R4*cos((now_angle-tgt_angle)*PI/180) + D4*sin((now_angle-tgt_angle)*PI/180)); |
yuki0701 | 0:44f9a43e4ab2 | 329 | uw_flag4 = 1; |
yuki0701 | 0:44f9a43e4ab2 | 330 | |
yuki0701 | 0:44f9a43e4ab2 | 331 | } |
yuki0701 | 0:44f9a43e4ab2 | 332 | if((xy_type==1 || xy_type==2) && pm_typeY==0) { |
yuki0701 | 0:44f9a43e4ab2 | 333 | |
yuki0701 | 0:44f9a43e4ab2 | 334 | info.nowY.usw = y_base - (usw_data1+ R1*cos((now_angle-tgt_angle)*PI/180) + D1*sin((now_angle-tgt_angle)*PI/180)); |
yuki0701 | 0:44f9a43e4ab2 | 335 | uw_flag1 = 1; |
yuki0701 | 0:44f9a43e4ab2 | 336 | |
yuki0701 | 0:44f9a43e4ab2 | 337 | } else if((xy_type==1 || xy_type==2) && pm_typeY==1) { |
yuki0701 | 0:44f9a43e4ab2 | 338 | |
yuki0701 | 0:44f9a43e4ab2 | 339 | info.nowY.usw = y_base + (usw_data2 + R2*cos((now_angle-tgt_angle)*PI/180) + D2*sin((now_angle-tgt_angle)*PI/180)); |
yuki0701 | 0:44f9a43e4ab2 | 340 | uw_flag2 = 1; |
yuki0701 | 0:44f9a43e4ab2 | 341 | |
yuki0701 | 0:44f9a43e4ab2 | 342 | } |
yuki0701 | 0:44f9a43e4ab2 | 343 | } else if(tgt_angle > -135 && tgt_angle < -45) { |
yuki0701 | 0:44f9a43e4ab2 | 344 | if((xy_type==0 || xy_type==2) && pm_typeX==0) { |
yuki0701 | 0:44f9a43e4ab2 | 345 | |
yuki0701 | 0:44f9a43e4ab2 | 346 | info.nowX.usw = x_base - (usw_data2 + R2*cos((now_angle-tgt_angle)*PI/180) + D2*sin((now_angle-tgt_angle)*PI/180)); |
yuki0701 | 0:44f9a43e4ab2 | 347 | uw_flag2 = 1; |
yuki0701 | 0:44f9a43e4ab2 | 348 | |
yuki0701 | 0:44f9a43e4ab2 | 349 | } else if((xy_type==0 || xy_type==2) && pm_typeX==1) { |
yuki0701 | 0:44f9a43e4ab2 | 350 | |
yuki0701 | 0:44f9a43e4ab2 | 351 | info.nowX.usw = x_base + (usw_data1 + R1*cos((now_angle-tgt_angle)*PI/180) + D1*sin((now_angle-tgt_angle)*PI/180)); |
yuki0701 | 0:44f9a43e4ab2 | 352 | uw_flag1 = 1; |
yuki0701 | 0:44f9a43e4ab2 | 353 | |
yuki0701 | 0:44f9a43e4ab2 | 354 | } |
yuki0701 | 0:44f9a43e4ab2 | 355 | if((xy_type==1 || xy_type==2) && pm_typeY==0) { |
yuki0701 | 0:44f9a43e4ab2 | 356 | |
yuki0701 | 0:44f9a43e4ab2 | 357 | info.nowY.usw = y_base - (usw_data3 + R3*cos((now_angle-tgt_angle)*PI/180) + D3*sin((now_angle-tgt_angle)*PI/180)); |
yuki0701 | 0:44f9a43e4ab2 | 358 | uw_flag3 = 1; |
yuki0701 | 0:44f9a43e4ab2 | 359 | |
yuki0701 | 0:44f9a43e4ab2 | 360 | } else if((xy_type==1 || xy_type==2) && pm_typeY==1) { |
yuki0701 | 0:44f9a43e4ab2 | 361 | |
yuki0701 | 0:44f9a43e4ab2 | 362 | info.nowY.usw = y_base + (usw_data4 + R4*cos((now_angle-tgt_angle)*PI/180) + D4*sin((now_angle-tgt_angle)*PI/180)); |
yuki0701 | 0:44f9a43e4ab2 | 363 | uw_flag4 = 1; |
yuki0701 | 0:44f9a43e4ab2 | 364 | |
yuki0701 | 0:44f9a43e4ab2 | 365 | } |
yuki0701 | 0:44f9a43e4ab2 | 366 | } |
yuki0701 | 0:44f9a43e4ab2 | 367 | } |
yuki0701 | 0:44f9a43e4ab2 | 368 | |
yuki0701 | 0:44f9a43e4ab2 | 369 | void uwflag_reset() |
yuki0701 | 0:44f9a43e4ab2 | 370 | { |
yuki0701 | 0:44f9a43e4ab2 | 371 | uw_flag1 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 372 | uw_flag2 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 373 | uw_flag3 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 374 | uw_flag4 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 375 | } |
yuki0701 | 0:44f9a43e4ab2 | 376 | |
yuki0701 | 0:44f9a43e4ab2 | 377 | void uwflag_change(int u1,int u2, int u3, int u4) |
yuki0701 | 0:44f9a43e4ab2 | 378 | { |
yuki0701 | 0:44f9a43e4ab2 | 379 | uw_flag1 = u1; |
yuki0701 | 0:44f9a43e4ab2 | 380 | uw_flag2 = u2; |
yuki0701 | 0:44f9a43e4ab2 | 381 | uw_flag3 = u3; |
yuki0701 | 0:44f9a43e4ab2 | 382 | uw_flag4 = u4; |
yuki0701 | 0:44f9a43e4ab2 | 383 | } |
yuki0701 | 0:44f9a43e4ab2 | 384 | |
yuki0701 | 0:44f9a43e4ab2 | 385 | |
yuki0701 | 0:44f9a43e4ab2 | 386 | void calc_xy(double target_angle, double u,double v) |
yuki0701 | 0:44f9a43e4ab2 | 387 | { |
yuki0701 | 0:44f9a43e4ab2 | 388 | //エンコーダにより求めた機体の座標と超音波センサーにより求めた機体の座標を(エンコーダ : 超音波 = u : 1-u / v : 1-v)の割合で混ぜて now_x,now_y に代入する |
yuki0701 | 0:44f9a43e4ab2 | 389 | |
yuki0701 | 0:44f9a43e4ab2 | 390 | calc_xy_enc(); |
yuki0701 | 0:44f9a43e4ab2 | 391 | //usw_data1 = 10 * uw1.get_dist(); |
yuki0701 | 0:44f9a43e4ab2 | 392 | ///usw_data2 = 10 * uw2.get_dist(); |
yuki0701 | 0:44f9a43e4ab2 | 393 | //usw_data3 = 10 * uw3.get_dist(); |
yuki0701 | 0:44f9a43e4ab2 | 394 | ///usw_data4 = 10 * uw4.get_dist(); |
yuki0701 | 0:44f9a43e4ab2 | 395 | |
yuki0701 | 0:44f9a43e4ab2 | 396 | //printf("uw2 = %f, uw4 = %f\n\r",usw_data2,usw_data4); |
yuki0701 | 0:44f9a43e4ab2 | 397 | |
yuki0701 | 0:44f9a43e4ab2 | 398 | if(u != 1 || v != 1) { |
yuki0701 | 0:44f9a43e4ab2 | 399 | calc_xy_usw(target_angle); //エンコーダの値しか使用しない場合は超音波センサーによる座標計算は行わずに計算量を減らす。 |
yuki0701 | 0:44f9a43e4ab2 | 400 | } |
yuki0701 | 0:44f9a43e4ab2 | 401 | |
yuki0701 | 0:44f9a43e4ab2 | 402 | now_x = u * info.nowX.enc + (1-u) * info.nowX.usw; |
yuki0701 | 0:44f9a43e4ab2 | 403 | now_y = v * info.nowY.enc + (1-v) * info.nowY.usw; |
yuki0701 | 0:44f9a43e4ab2 | 404 | |
yuki0701 | 0:44f9a43e4ab2 | 405 | /*if(now_x >-1 && now_x <1 && now_y >-1 && now_y <1){ //スタート時の0合わせ用 |
yuki0701 | 0:44f9a43e4ab2 | 406 | ec_led = 1; |
yuki0701 | 0:44f9a43e4ab2 | 407 | }else{ |
yuki0701 | 0:44f9a43e4ab2 | 408 | ec_led = 0; |
yuki0701 | 0:44f9a43e4ab2 | 409 | } |
yuki0701 | 0:44f9a43e4ab2 | 410 | |
yuki0701 | 0:44f9a43e4ab2 | 411 | if(now_angle >-0.5 && now_angle <0.5){ |
yuki0701 | 0:44f9a43e4ab2 | 412 | gyro_led = 1; |
yuki0701 | 0:44f9a43e4ab2 | 413 | }else{ |
yuki0701 | 0:44f9a43e4ab2 | 414 | gyro_led = 0; |
yuki0701 | 0:44f9a43e4ab2 | 415 | }*/ |
yuki0701 | 0:44f9a43e4ab2 | 416 | } |
yuki0701 | 0:44f9a43e4ab2 | 417 | |
yuki0701 | 0:44f9a43e4ab2 | 418 | void copy_xyr_usw(){ |
yuki0701 | 0:44f9a43e4ab2 | 419 | calc_xy_enc(); |
yuki0701 | 0:44f9a43e4ab2 | 420 | now_angle = -gyro.getZ_Angle() + angle_base; |
yuki0701 | 0:44f9a43e4ab2 | 421 | |
yuki0701 | 0:44f9a43e4ab2 | 422 | info_x = info.nowX.enc; |
yuki0701 | 0:44f9a43e4ab2 | 423 | info_y = info.nowY.enc; |
yuki0701 | 0:44f9a43e4ab2 | 424 | info_r = now_angle; |
yuki0701 | 0:44f9a43e4ab2 | 425 | |
yuki0701 | 0:44f9a43e4ab2 | 426 | usw_data1 = 10 * uw1.get_dist(); |
yuki0701 | 0:44f9a43e4ab2 | 427 | usw_data2 = 2000; //10 * uw2.get_dist(); |
yuki0701 | 0:44f9a43e4ab2 | 428 | usw_data3 = 3000; //10 * uw3.get_dist(); |
yuki0701 | 0:44f9a43e4ab2 | 429 | usw_data4 = 10 * uw4.get_dist(); |
yuki0701 | 0:44f9a43e4ab2 | 430 | } |
yuki0701 | 0:44f9a43e4ab2 | 431 | |
yuki0701 | 0:44f9a43e4ab2 | 432 | void enc_correction(int x_select,int y_select) //エンコーダの座標を超音波センサの座標で上書き |
yuki0701 | 0:44f9a43e4ab2 | 433 | { |
yuki0701 | 0:44f9a43e4ab2 | 434 | //x_select,y_select → (0:上書きしない/1:上書きする) |
yuki0701 | 0:44f9a43e4ab2 | 435 | |
yuki0701 | 0:44f9a43e4ab2 | 436 | if(x_select == 1) { |
yuki0701 | 0:44f9a43e4ab2 | 437 | info.nowX.enc = info.nowX.usw; |
yuki0701 | 0:44f9a43e4ab2 | 438 | } |
yuki0701 | 0:44f9a43e4ab2 | 439 | if(y_select == 1) { |
yuki0701 | 0:44f9a43e4ab2 | 440 | info.nowY.enc = info.nowY.usw; |
yuki0701 | 0:44f9a43e4ab2 | 441 | } |
yuki0701 | 0:44f9a43e4ab2 | 442 | |
yuki0701 | 0:44f9a43e4ab2 | 443 | } |
yuki0701 | 0:44f9a43e4ab2 | 444 | |
yuki0701 | 0:44f9a43e4ab2 | 445 | void enc_correction2(int x_plot1, int y_plot2) //引数の座標でエンコーダの座標を修正 |
yuki0701 | 0:44f9a43e4ab2 | 446 | { |
yuki0701 | 0:44f9a43e4ab2 | 447 | info.nowX.enc = x_plot1; |
yuki0701 | 0:44f9a43e4ab2 | 448 | info.nowY.enc = y_plot2; |
yuki0701 | 0:44f9a43e4ab2 | 449 | } |
yuki0701 | 0:44f9a43e4ab2 | 450 | |
yuki0701 | 0:44f9a43e4ab2 | 451 | //ここからそれぞれのプログラム///////////////////////////////////////////////////////////////////////////////////////////////////////////////// |
yuki0701 | 0:44f9a43e4ab2 | 452 | //now_x(現在のx座標),now_y(現在のy座標),now_angle(機体角度(ラジアンではない)(0~360や-180~180とは限らない))(反時計回りが正) |
yuki0701 | 0:44f9a43e4ab2 | 453 | //ジャイロの出力は角度だが三角関数はラジアンとして計算する |
yuki0701 | 0:44f9a43e4ab2 | 454 | //通常の移動+座標のずれ補正+機体の角度補正(+必要に応じさらに別補正) |
yuki0701 | 0:44f9a43e4ab2 | 455 | //ジャイロの仕様上、角度補正をするときに計算式内で角度はそのままよりsinをとったほうがいいかもね |
yuki0701 | 0:44f9a43e4ab2 | 456 | |
yuki0701 | 0:44f9a43e4ab2 | 457 | void purecurve(int type,double u,double v, //正面を変えずに円弧or楕円を描いて曲がる |
yuki0701 | 0:44f9a43e4ab2 | 458 | double point_x1,double point_y1, |
yuki0701 | 0:44f9a43e4ab2 | 459 | double point_x2,double point_y2, |
yuki0701 | 0:44f9a43e4ab2 | 460 | int theta, |
yuki0701 | 0:44f9a43e4ab2 | 461 | double speed, |
yuki0701 | 0:44f9a43e4ab2 | 462 | double q_p,double q_d, |
yuki0701 | 0:44f9a43e4ab2 | 463 | double r_p,double r_d, |
yuki0701 | 0:44f9a43e4ab2 | 464 | double r_out_max, |
yuki0701 | 0:44f9a43e4ab2 | 465 | double target_angle, double v_base, double q_out_max) |
yuki0701 | 0:44f9a43e4ab2 | 466 | //type:動きの種類(8パターン) point_x1,point_y1=出発地点の座標 point_x2,point_x2=目標地点の座標 theta=plotの間隔(0~90°) speed=速度 |
yuki0701 | 0:44f9a43e4ab2 | 467 | { |
yuki0701 | 0:44f9a43e4ab2 | 468 | //-----PathFollowingのパラメーター設定-----// |
yuki0701 | 0:44f9a43e4ab2 | 469 | q_setPDparam(q_p,q_d); //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数 |
yuki0701 | 0:44f9a43e4ab2 | 470 | r_setPDparam(r_p,r_d); //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数 |
yuki0701 | 0:44f9a43e4ab2 | 471 | set_r_out(r_out_max); //旋回時の最大出力値設定関数 |
yuki0701 | 0:44f9a43e4ab2 | 472 | set_q_out(q_out_max); |
yuki0701 | 0:44f9a43e4ab2 | 473 | set_target_angle(target_angle); //機体目標角度設定関数 |
yuki0701 | 0:44f9a43e4ab2 | 474 | |
yuki0701 | 0:44f9a43e4ab2 | 475 | int s; |
yuki0701 | 0:44f9a43e4ab2 | 476 | int t = 0; |
yuki0701 | 0:44f9a43e4ab2 | 477 | double X,Y;//X=楕円の中心座標、Y=楕円の中心座標 |
yuki0701 | 0:44f9a43e4ab2 | 478 | double a,b; //a=楕円のx軸方向の幅の半分,b=楕円のy軸方向の幅の半分 |
yuki0701 | 0:44f9a43e4ab2 | 479 | double plotx[(90/theta)+1]; //楕円にとるplotのx座標 |
yuki0701 | 0:44f9a43e4ab2 | 480 | double ploty[(90/theta)+1]; |
yuki0701 | 0:44f9a43e4ab2 | 481 | |
yuki0701 | 0:44f9a43e4ab2 | 482 | double x_out,y_out,r_out; |
yuki0701 | 0:44f9a43e4ab2 | 483 | |
yuki0701 | 0:44f9a43e4ab2 | 484 | a=fabs(point_x1-point_x2); |
yuki0701 | 0:44f9a43e4ab2 | 485 | b=fabs(point_y1-point_y2); |
yuki0701 | 0:44f9a43e4ab2 | 486 | |
yuki0701 | 0:44f9a43e4ab2 | 487 | switch(type) { |
yuki0701 | 0:44f9a43e4ab2 | 488 | |
yuki0701 | 0:44f9a43e4ab2 | 489 | case 1://→↑移動 |
yuki0701 | 0:44f9a43e4ab2 | 490 | X=point_x1; |
yuki0701 | 0:44f9a43e4ab2 | 491 | Y=point_y2; |
yuki0701 | 0:44f9a43e4ab2 | 492 | |
yuki0701 | 0:44f9a43e4ab2 | 493 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 0:44f9a43e4ab2 | 494 | plotx[s] = X + a * cos(-PI/2 + s * (PI*theta/180)); |
yuki0701 | 0:44f9a43e4ab2 | 495 | ploty[s] = Y + b * sin(-PI/2 + s * (PI*theta/180)); |
yuki0701 | 0:44f9a43e4ab2 | 496 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 0:44f9a43e4ab2 | 497 | } |
yuki0701 | 0:44f9a43e4ab2 | 498 | break; |
yuki0701 | 0:44f9a43e4ab2 | 499 | |
yuki0701 | 0:44f9a43e4ab2 | 500 | case 2://↑→移動 |
yuki0701 | 0:44f9a43e4ab2 | 501 | X=point_x2; |
yuki0701 | 0:44f9a43e4ab2 | 502 | Y=point_y1; |
yuki0701 | 0:44f9a43e4ab2 | 503 | |
yuki0701 | 0:44f9a43e4ab2 | 504 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 0:44f9a43e4ab2 | 505 | plotx[s] = X + a * cos(PI - s * (PI*theta/180)); |
yuki0701 | 0:44f9a43e4ab2 | 506 | ploty[s] = Y + b * sin(PI - s * (PI*theta/180)); |
yuki0701 | 0:44f9a43e4ab2 | 507 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 0:44f9a43e4ab2 | 508 | } |
yuki0701 | 0:44f9a43e4ab2 | 509 | break; |
yuki0701 | 0:44f9a43e4ab2 | 510 | |
yuki0701 | 0:44f9a43e4ab2 | 511 | case 3://↑←移動 |
yuki0701 | 0:44f9a43e4ab2 | 512 | X=point_x2; |
yuki0701 | 0:44f9a43e4ab2 | 513 | Y=point_y1; |
yuki0701 | 0:44f9a43e4ab2 | 514 | |
yuki0701 | 0:44f9a43e4ab2 | 515 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 0:44f9a43e4ab2 | 516 | plotx[s] = X + a * cos(s * (PI*theta/180)); |
yuki0701 | 0:44f9a43e4ab2 | 517 | ploty[s] = Y + b * sin(s * (PI*theta/180)); |
yuki0701 | 0:44f9a43e4ab2 | 518 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 0:44f9a43e4ab2 | 519 | } |
yuki0701 | 0:44f9a43e4ab2 | 520 | break; |
yuki0701 | 0:44f9a43e4ab2 | 521 | |
yuki0701 | 0:44f9a43e4ab2 | 522 | case 4://←↑移動 |
yuki0701 | 0:44f9a43e4ab2 | 523 | X=point_x1; |
yuki0701 | 0:44f9a43e4ab2 | 524 | Y=point_y2; |
yuki0701 | 0:44f9a43e4ab2 | 525 | |
yuki0701 | 0:44f9a43e4ab2 | 526 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 0:44f9a43e4ab2 | 527 | plotx[s] = X + a * cos(-PI/2 - s * (PI*theta/180)); |
yuki0701 | 0:44f9a43e4ab2 | 528 | ploty[s] = Y + b * sin(-PI/2 - s * (PI*theta/180)); |
yuki0701 | 0:44f9a43e4ab2 | 529 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 0:44f9a43e4ab2 | 530 | } |
yuki0701 | 0:44f9a43e4ab2 | 531 | break; |
yuki0701 | 0:44f9a43e4ab2 | 532 | |
yuki0701 | 0:44f9a43e4ab2 | 533 | case 5://←↓移動 |
yuki0701 | 0:44f9a43e4ab2 | 534 | X=point_x1; |
yuki0701 | 0:44f9a43e4ab2 | 535 | Y=point_y2; |
yuki0701 | 0:44f9a43e4ab2 | 536 | |
yuki0701 | 0:44f9a43e4ab2 | 537 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 0:44f9a43e4ab2 | 538 | plotx[s] = X + a * cos(PI/2 + s * (PI*theta/180)); |
yuki0701 | 0:44f9a43e4ab2 | 539 | ploty[s] = Y + b * sin(PI/2 + s * (PI*theta/180)); |
yuki0701 | 0:44f9a43e4ab2 | 540 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 0:44f9a43e4ab2 | 541 | } |
yuki0701 | 0:44f9a43e4ab2 | 542 | break; |
yuki0701 | 0:44f9a43e4ab2 | 543 | |
yuki0701 | 0:44f9a43e4ab2 | 544 | case 6://↓←移動 |
yuki0701 | 0:44f9a43e4ab2 | 545 | X=point_x2; |
yuki0701 | 0:44f9a43e4ab2 | 546 | Y=point_y1; |
yuki0701 | 0:44f9a43e4ab2 | 547 | |
yuki0701 | 0:44f9a43e4ab2 | 548 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 0:44f9a43e4ab2 | 549 | plotx[s] = X + a * cos(-s * (PI*theta/180)); |
yuki0701 | 0:44f9a43e4ab2 | 550 | ploty[s] = Y + b * sin(-s * (PI*theta/180)); |
yuki0701 | 0:44f9a43e4ab2 | 551 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 0:44f9a43e4ab2 | 552 | } |
yuki0701 | 0:44f9a43e4ab2 | 553 | break; |
yuki0701 | 0:44f9a43e4ab2 | 554 | |
yuki0701 | 0:44f9a43e4ab2 | 555 | case 7://↓→移動 |
yuki0701 | 0:44f9a43e4ab2 | 556 | X=point_x2; |
yuki0701 | 0:44f9a43e4ab2 | 557 | Y=point_y1; |
yuki0701 | 0:44f9a43e4ab2 | 558 | |
yuki0701 | 0:44f9a43e4ab2 | 559 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 0:44f9a43e4ab2 | 560 | plotx[s] = X + a * cos(PI + s * (PI*theta/180)); |
yuki0701 | 0:44f9a43e4ab2 | 561 | ploty[s] = Y + b * sin(PI + s * (PI*theta/180)); |
yuki0701 | 0:44f9a43e4ab2 | 562 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 0:44f9a43e4ab2 | 563 | } |
yuki0701 | 0:44f9a43e4ab2 | 564 | break; |
yuki0701 | 0:44f9a43e4ab2 | 565 | |
yuki0701 | 0:44f9a43e4ab2 | 566 | case 8://→↓移動 |
yuki0701 | 0:44f9a43e4ab2 | 567 | X=point_x1; |
yuki0701 | 0:44f9a43e4ab2 | 568 | Y=point_y2; |
yuki0701 | 0:44f9a43e4ab2 | 569 | |
yuki0701 | 0:44f9a43e4ab2 | 570 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 0:44f9a43e4ab2 | 571 | plotx[s] = X + a * cos(PI/2 - s * (PI*theta/180)); |
yuki0701 | 0:44f9a43e4ab2 | 572 | ploty[s] = Y + b * sin(PI/2 - s * (PI*theta/180)); |
yuki0701 | 0:44f9a43e4ab2 | 573 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 0:44f9a43e4ab2 | 574 | } |
yuki0701 | 0:44f9a43e4ab2 | 575 | break; |
yuki0701 | 0:44f9a43e4ab2 | 576 | } |
yuki0701 | 0:44f9a43e4ab2 | 577 | |
yuki0701 | 0:44f9a43e4ab2 | 578 | while(1) { |
yuki0701 | 0:44f9a43e4ab2 | 579 | |
yuki0701 | 0:44f9a43e4ab2 | 580 | if(id1_value[0] != 1)break; |
yuki0701 | 0:44f9a43e4ab2 | 581 | if(id1_value[6] != flag)break; |
yuki0701 | 0:44f9a43e4ab2 | 582 | |
yuki0701 | 0:44f9a43e4ab2 | 583 | calc_xy(target_angle,u,v); |
yuki0701 | 0:44f9a43e4ab2 | 584 | |
yuki0701 | 0:44f9a43e4ab2 | 585 | XYRmotorout(plotx[t],ploty[t],plotx[t+1],ploty[t+1],&x_out,&y_out,&r_out,speed,speed); |
yuki0701 | 0:44f9a43e4ab2 | 586 | CalMotorOut(x_out,y_out,r_out); |
yuki0701 | 0:44f9a43e4ab2 | 587 | //debug_printf("t=%d now_x=%f now_y=%f x_out=%f y_out=%f\n\r",t,now_x,now_y,x_out,y_out); |
yuki0701 | 0:44f9a43e4ab2 | 588 | |
yuki0701 | 0:44f9a43e4ab2 | 589 | base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),v_base); //m1~m4に代入 |
yuki0701 | 0:44f9a43e4ab2 | 590 | //debug_printf("t=%d (0)=%f (1)=%f (2)=%f (3)=%f\n\r",t,GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3)); |
yuki0701 | 0:44f9a43e4ab2 | 591 | |
yuki0701 | 0:44f9a43e4ab2 | 592 | if(((plotx[t+1] - now_x)*(plotx[t+1] - plotx[t]) + (ploty[t+1] - now_y)*(ploty[t+1] - ploty[t])) < 0)t++; |
yuki0701 | 0:44f9a43e4ab2 | 593 | |
yuki0701 | 0:44f9a43e4ab2 | 594 | // MaxonControl(m1,m2,m3,m4); //出力 |
yuki0701 | 0:44f9a43e4ab2 | 595 | // debug_printf("t=%d m1=%d m2=%d m3=%d m4=%d x=%f y=%f angle=%f\n\r",t,m1,m2,m3,m4,now_x,now_y,now_angle); |
yuki0701 | 0:44f9a43e4ab2 | 596 | |
yuki0701 | 0:44f9a43e4ab2 | 597 | if(t == (90/theta))break; |
yuki0701 | 0:44f9a43e4ab2 | 598 | } |
yuki0701 | 0:44f9a43e4ab2 | 599 | } |
yuki0701 | 0:44f9a43e4ab2 | 600 | |
yuki0701 | 0:44f9a43e4ab2 | 601 | void gogo_straight(double u,double v, //直線運動プログラム |
yuki0701 | 0:44f9a43e4ab2 | 602 | double x1_point,double y1_point, |
yuki0701 | 0:44f9a43e4ab2 | 603 | double x2_point,double y2_point, |
yuki0701 | 0:44f9a43e4ab2 | 604 | double speed1,double speed2, |
yuki0701 | 0:44f9a43e4ab2 | 605 | double q_p,double q_d, |
yuki0701 | 0:44f9a43e4ab2 | 606 | double r_p,double r_d, |
yuki0701 | 0:44f9a43e4ab2 | 607 | double r_out_max, |
yuki0701 | 0:44f9a43e4ab2 | 608 | double target_angle,double v_base, double q_out_max) |
yuki0701 | 0:44f9a43e4ab2 | 609 | //引数:出発地点の座標(x,y)、目標地点の座標(x,y)、初速度(speed1)、目標速度(speed2)//speed1=speed2 のとき等速運動 |
yuki0701 | 0:44f9a43e4ab2 | 610 | { |
yuki0701 | 0:44f9a43e4ab2 | 611 | //-----PathFollowingのパラメーター設定-----// |
yuki0701 | 0:44f9a43e4ab2 | 612 | q_setPDparam(q_p,q_d); //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数 |
yuki0701 | 0:44f9a43e4ab2 | 613 | r_setPDparam(r_p,r_d); //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数 |
yuki0701 | 0:44f9a43e4ab2 | 614 | set_r_out(r_out_max); //旋回時の最大出力値設定関数 |
yuki0701 | 0:44f9a43e4ab2 | 615 | set_q_out(q_out_max); |
yuki0701 | 0:44f9a43e4ab2 | 616 | set_target_angle(target_angle); //機体目標角度設定関数 |
yuki0701 | 0:44f9a43e4ab2 | 617 | |
yuki0701 | 0:44f9a43e4ab2 | 618 | while (1) { |
yuki0701 | 0:44f9a43e4ab2 | 619 | |
yuki0701 | 0:44f9a43e4ab2 | 620 | if(id1_value[0] != 1)break; |
yuki0701 | 0:44f9a43e4ab2 | 621 | if(id1_value[6] != flag)break; |
yuki0701 | 0:44f9a43e4ab2 | 622 | |
yuki0701 | 0:44f9a43e4ab2 | 623 | calc_xy(target_angle,u,v); |
yuki0701 | 0:44f9a43e4ab2 | 624 | |
yuki0701 | 0:44f9a43e4ab2 | 625 | XYRmotorout(x1_point,y1_point,x2_point,y2_point,&x_out,&y_out,&r_out,speed1,speed2); |
yuki0701 | 0:44f9a43e4ab2 | 626 | //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); |
yuki0701 | 0:44f9a43e4ab2 | 627 | |
yuki0701 | 0:44f9a43e4ab2 | 628 | CalMotorOut(x_out,y_out,r_out); |
yuki0701 | 0:44f9a43e4ab2 | 629 | //printf("out1=%lf, out2=%lf, out3=%lf, out4=%lf\n",GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3)); |
yuki0701 | 0:44f9a43e4ab2 | 630 | |
yuki0701 | 0:44f9a43e4ab2 | 631 | base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),v_base); |
yuki0701 | 0:44f9a43e4ab2 | 632 | //printf("m1=%d, m2=%d, m3=%d, m4=%d\r\n",m_1,m_2,m_3,m_4); |
yuki0701 | 0:44f9a43e4ab2 | 633 | |
yuki0701 | 0:44f9a43e4ab2 | 634 | // MaxonControl(m1,m2,m3,m4); |
yuki0701 | 0:44f9a43e4ab2 | 635 | // 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); |
yuki0701 | 0:44f9a43e4ab2 | 636 | 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); |
yuki0701 | 0:44f9a43e4ab2 | 637 | //printf("usw2 = %f usw4 = %f x=%f y=%f angle=%f\n\r",usw_data2,usw_data4,now_x,now_y,now_angle); |
yuki0701 | 0:44f9a43e4ab2 | 638 | |
yuki0701 | 0:44f9a43e4ab2 | 639 | if(((x2_point - now_x)*(x2_point - x1_point) + (y2_point - now_y)*(y2_point - y1_point)) < 0)break; |
yuki0701 | 0:44f9a43e4ab2 | 640 | } |
yuki0701 | 0:44f9a43e4ab2 | 641 | } |
yuki0701 | 0:44f9a43e4ab2 | 642 | |
yuki0701 | 0:44f9a43e4ab2 | 643 | |
yuki0701 | 0:44f9a43e4ab2 | 644 | |
yuki0701 | 0:44f9a43e4ab2 | 645 | double spline_base(int i, int k, double t, int nv[]) //スプライン基底関数を求める関数 |
yuki0701 | 0:44f9a43e4ab2 | 646 | { |
yuki0701 | 0:44f9a43e4ab2 | 647 | // i:0~(制御点の個数-1) |
yuki0701 | 0:44f9a43e4ab2 | 648 | // k:スプライト曲線の次元 |
yuki0701 | 0:44f9a43e4ab2 | 649 | // t:0~(ノットベクトルの最大値) |
yuki0701 | 0:44f9a43e4ab2 | 650 | // nv[]:ノットベクトル |
yuki0701 | 0:44f9a43e4ab2 | 651 | double w1 = 0.0, w2 = 0.0; |
yuki0701 | 0:44f9a43e4ab2 | 652 | if (k == 1) { |
yuki0701 | 0:44f9a43e4ab2 | 653 | if (t > nv[i] && t <= nv[i + 1]) |
yuki0701 | 0:44f9a43e4ab2 | 654 | return 1.0; |
yuki0701 | 0:44f9a43e4ab2 | 655 | else |
yuki0701 | 0:44f9a43e4ab2 | 656 | return 0.0; |
yuki0701 | 0:44f9a43e4ab2 | 657 | } else { |
yuki0701 | 0:44f9a43e4ab2 | 658 | if ((nv[i + k] - nv[i + 1]) != 0) { |
yuki0701 | 0:44f9a43e4ab2 | 659 | w1 = ((nv[i + k] - t) / (nv[i + k] - nv[i + 1])) * spline_base(i + 1, k - 1, t, nv); |
yuki0701 | 0:44f9a43e4ab2 | 660 | //printf("%f\n\r",w1); |
yuki0701 | 0:44f9a43e4ab2 | 661 | } |
yuki0701 | 0:44f9a43e4ab2 | 662 | if ((nv[i + k - 1] - nv[i]) != 0) { |
yuki0701 | 0:44f9a43e4ab2 | 663 | w2 = ((t - nv[i]) / (nv[i + k - 1] - nv[i])) * spline_base(i, k - 1, t, nv); |
yuki0701 | 0:44f9a43e4ab2 | 664 | //printf("%f\n\r",w2); |
yuki0701 | 0:44f9a43e4ab2 | 665 | } |
yuki0701 | 0:44f9a43e4ab2 | 666 | return (w1 + w2); |
yuki0701 | 0:44f9a43e4ab2 | 667 | } |
yuki0701 | 0:44f9a43e4ab2 | 668 | } |
yuki0701 | 0:44f9a43e4ab2 | 669 | |
yuki0701 | 0:44f9a43e4ab2 | 670 | |
yuki0701 | 0:44f9a43e4ab2 | 671 | void spline_move(double u, double v, |
yuki0701 | 0:44f9a43e4ab2 | 672 | double st_x,double st_y,double end_x,double end_y, |
yuki0701 | 0:44f9a43e4ab2 | 673 | double cont1_x,double cont1_y,double cont2_x,double cont2_y, |
yuki0701 | 0:44f9a43e4ab2 | 674 | double st_speed, double end_speed, |
yuki0701 | 0:44f9a43e4ab2 | 675 | double q_p,double q_d, |
yuki0701 | 0:44f9a43e4ab2 | 676 | double r_p,double r_d, |
yuki0701 | 0:44f9a43e4ab2 | 677 | double r_out_max, |
yuki0701 | 0:44f9a43e4ab2 | 678 | double target_angle, double v_base, double q_out_max, int num) |
yuki0701 | 0:44f9a43e4ab2 | 679 | { |
yuki0701 | 0:44f9a43e4ab2 | 680 | double dx, dy, dr; |
yuki0701 | 0:44f9a43e4ab2 | 681 | int nt[] = {0, 0, 0, 1, 2, 2, 2}; //ノットベクトル |
yuki0701 | 0:44f9a43e4ab2 | 682 | //dr = (end_angle - st_angle) / num; |
yuki0701 | 0:44f9a43e4ab2 | 683 | int ds = (end_speed - st_speed) / num; |
yuki0701 | 0:44f9a43e4ab2 | 684 | |
yuki0701 | 0:44f9a43e4ab2 | 685 | //-----PathFollowingのパラメーター設定-----// |
yuki0701 | 0:44f9a43e4ab2 | 686 | q_setPDparam(q_p,q_d); //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数 |
yuki0701 | 0:44f9a43e4ab2 | 687 | r_setPDparam(r_p,r_d); //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数 |
yuki0701 | 0:44f9a43e4ab2 | 688 | set_r_out(r_out_max); //旋回時の最大出力値設定関数 |
yuki0701 | 0:44f9a43e4ab2 | 689 | set_q_out(q_out_max); |
yuki0701 | 0:44f9a43e4ab2 | 690 | set_target_angle(target_angle); //機体目標角度設定関数 |
yuki0701 | 0:44f9a43e4ab2 | 691 | |
yuki0701 | 0:44f9a43e4ab2 | 692 | double plotx[num + 1]; //楕円にとるplotのx座標 |
yuki0701 | 0:44f9a43e4ab2 | 693 | double ploty[num + 1]; |
yuki0701 | 0:44f9a43e4ab2 | 694 | double value_t; |
yuki0701 | 0:44f9a43e4ab2 | 695 | int i, j; |
yuki0701 | 0:44f9a43e4ab2 | 696 | int t = 0; |
yuki0701 | 0:44f9a43e4ab2 | 697 | // for(i = 0; i < 7; i++){ |
yuki0701 | 0:44f9a43e4ab2 | 698 | // printf("not_V = %d\n\r",nt[i]); |
yuki0701 | 0:44f9a43e4ab2 | 699 | // } |
yuki0701 | 0:44f9a43e4ab2 | 700 | for (i = 0; i < num + 1; i++) { |
yuki0701 | 0:44f9a43e4ab2 | 701 | plotx[i] = 0.0; |
yuki0701 | 0:44f9a43e4ab2 | 702 | ploty[i] = 0.0; |
yuki0701 | 0:44f9a43e4ab2 | 703 | } |
yuki0701 | 0:44f9a43e4ab2 | 704 | printf("{\n"); |
yuki0701 | 0:44f9a43e4ab2 | 705 | for (i = 0; i < num + 1; i++) { |
yuki0701 | 0:44f9a43e4ab2 | 706 | value_t = (double)2 * i / num; |
yuki0701 | 0:44f9a43e4ab2 | 707 | for (j = 0; j < 4; j++) { |
yuki0701 | 0:44f9a43e4ab2 | 708 | if (j == 0) { |
yuki0701 | 0:44f9a43e4ab2 | 709 | plotx[i] += st_x * spline_base(j, 3, value_t, nt); |
yuki0701 | 0:44f9a43e4ab2 | 710 | ploty[i] += st_y * spline_base(j, 3, value_t, nt); |
yuki0701 | 0:44f9a43e4ab2 | 711 | } else if (j == 1) { |
yuki0701 | 0:44f9a43e4ab2 | 712 | plotx[i] += cont1_x * spline_base(j, 3, value_t, nt); |
yuki0701 | 0:44f9a43e4ab2 | 713 | ploty[i] += cont1_y * spline_base(j, 3, value_t, nt); |
yuki0701 | 0:44f9a43e4ab2 | 714 | } else if (j == 2) { |
yuki0701 | 0:44f9a43e4ab2 | 715 | plotx[i] += cont2_x * spline_base(j, 3, value_t, nt); |
yuki0701 | 0:44f9a43e4ab2 | 716 | ploty[i] += cont2_y * spline_base(j, 3, value_t, nt); |
yuki0701 | 0:44f9a43e4ab2 | 717 | } else if (j == 3) { |
yuki0701 | 0:44f9a43e4ab2 | 718 | plotx[i] += end_x * spline_base(j, 3, value_t, nt); |
yuki0701 | 0:44f9a43e4ab2 | 719 | ploty[i] += end_y * spline_base(j, 3, value_t, nt); |
yuki0701 | 0:44f9a43e4ab2 | 720 | } |
yuki0701 | 0:44f9a43e4ab2 | 721 | } |
yuki0701 | 0:44f9a43e4ab2 | 722 | //printf("plot_x = %f, plot_y = %f\n\r", plotx[i], ploty[i]); |
yuki0701 | 0:44f9a43e4ab2 | 723 | } |
yuki0701 | 0:44f9a43e4ab2 | 724 | while(1) { |
yuki0701 | 0:44f9a43e4ab2 | 725 | |
yuki0701 | 0:44f9a43e4ab2 | 726 | if(id1_value[0] != 1)break; |
yuki0701 | 0:44f9a43e4ab2 | 727 | if(id1_value[6] != flag)break; |
yuki0701 | 0:44f9a43e4ab2 | 728 | |
yuki0701 | 0:44f9a43e4ab2 | 729 | calc_xy(target_angle,u,v); |
yuki0701 | 0:44f9a43e4ab2 | 730 | |
yuki0701 | 0:44f9a43e4ab2 | 731 | 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)); |
yuki0701 | 0:44f9a43e4ab2 | 732 | CalMotorOut(x_out,y_out,r_out); |
yuki0701 | 0:44f9a43e4ab2 | 733 | //debug_printf("t=%d now_x=%f now_y=%f x_out=%f y_out=%f\n\r",t,now_x,now_y,x_out,y_out); |
yuki0701 | 0:44f9a43e4ab2 | 734 | |
yuki0701 | 0:44f9a43e4ab2 | 735 | base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),v_base); //m1~m4に代入 |
yuki0701 | 0:44f9a43e4ab2 | 736 | //debug_printf("t=%d (0)=%f (1)=%f (2)=%f (3)=%f\n\r",t,GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3)); |
yuki0701 | 0:44f9a43e4ab2 | 737 | |
yuki0701 | 0:44f9a43e4ab2 | 738 | if(((plotx[t+1] - now_x)*(plotx[t+1] - plotx[t]) + (ploty[t+1] - now_y)*(ploty[t+1] - ploty[t])) < 0)t++; |
yuki0701 | 0:44f9a43e4ab2 | 739 | |
yuki0701 | 0:44f9a43e4ab2 | 740 | // MaxonControl(m1,m2,m3,m4); //出力 |
yuki0701 | 0:44f9a43e4ab2 | 741 | // debug_printf("t=%d m1=%d m2=%d m3=%d m4=%d x=%f y=%f angle=%f\n\r",t,m1,m2,m3,m4,now_x,now_y,now_angle); |
yuki0701 | 0:44f9a43e4ab2 | 742 | 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); |
yuki0701 | 0:44f9a43e4ab2 | 743 | |
yuki0701 | 0:44f9a43e4ab2 | 744 | if(t == num)break; |
yuki0701 | 0:44f9a43e4ab2 | 745 | } |
yuki0701 | 0:44f9a43e4ab2 | 746 | |
yuki0701 | 0:44f9a43e4ab2 | 747 | } |
yuki0701 | 0:44f9a43e4ab2 | 748 | |
yuki0701 | 0:44f9a43e4ab2 | 749 | |
yuki0701 | 0:44f9a43e4ab2 | 750 | |
yuki0701 | 0:44f9a43e4ab2 | 751 | |
yuki0701 | 0:44f9a43e4ab2 | 752 | /*void pos_correction(double tgt_x, double tgt_y, double tgt_angle, double u, double v) //位置補正(使用前にMaxonControl(0,0,0,0)を入れる) |
yuki0701 | 0:44f9a43e4ab2 | 753 | { |
yuki0701 | 0:44f9a43e4ab2 | 754 | |
yuki0701 | 0:44f9a43e4ab2 | 755 | double r, R=10; // r:一回補正が入るごとの機体の位置と目標位置の距離(ズレ) R:補正終了とみなす目標位置からの機体の位置のズレ |
yuki0701 | 0:44f9a43e4ab2 | 756 | double out; |
yuki0701 | 0:44f9a43e4ab2 | 757 | |
yuki0701 | 0:44f9a43e4ab2 | 758 | calc_xy(tgt_angle, u, v); |
yuki0701 | 0:44f9a43e4ab2 | 759 | |
yuki0701 | 0:44f9a43e4ab2 | 760 | while(1) { //機体の位置を目標領域(目標座標+許容誤差)に収める |
yuki0701 | 0:44f9a43e4ab2 | 761 | gogo_straight(u,v,now_x,now_y,tgt_x,tgt_y,200,50,5,0.1,10,0.1,500,tgt_angle); |
yuki0701 | 0:44f9a43e4ab2 | 762 | MaxonControl(0,0,0,0); |
yuki0701 | 0:44f9a43e4ab2 | 763 | |
yuki0701 | 0:44f9a43e4ab2 | 764 | calc_xy(tgt_angle, u, v); |
yuki0701 | 0:44f9a43e4ab2 | 765 | |
yuki0701 | 0:44f9a43e4ab2 | 766 | r=hypot(now_x - tgt_x, now_y - tgt_y); |
yuki0701 | 0:44f9a43e4ab2 | 767 | |
yuki0701 | 0:44f9a43e4ab2 | 768 | if(r < R) break; |
yuki0701 | 0:44f9a43e4ab2 | 769 | if(id1_value[0] != 1)break; |
yuki0701 | 0:44f9a43e4ab2 | 770 | } |
yuki0701 | 0:44f9a43e4ab2 | 771 | |
yuki0701 | 0:44f9a43e4ab2 | 772 | while(1) { |
yuki0701 | 0:44f9a43e4ab2 | 773 | |
yuki0701 | 0:44f9a43e4ab2 | 774 | calc_gyro(); |
yuki0701 | 0:44f9a43e4ab2 | 775 | |
yuki0701 | 0:44f9a43e4ab2 | 776 | out = 10 * (tgt_angle - now_angle); |
yuki0701 | 0:44f9a43e4ab2 | 777 | |
yuki0701 | 0:44f9a43e4ab2 | 778 | if(out > 300) { //0~179°のときは時計回りに回転 |
yuki0701 | 0:44f9a43e4ab2 | 779 | MaxonControl(300,300,300,300); |
yuki0701 | 0:44f9a43e4ab2 | 780 | } else if(out < -300) { |
yuki0701 | 0:44f9a43e4ab2 | 781 | MaxonControl(-300,-300,-300,-300); |
yuki0701 | 0:44f9a43e4ab2 | 782 | } else if(out <= 300 && out > -300) { |
yuki0701 | 0:44f9a43e4ab2 | 783 | MaxonControl(out,out,out,out); |
yuki0701 | 0:44f9a43e4ab2 | 784 | } |
yuki0701 | 0:44f9a43e4ab2 | 785 | |
yuki0701 | 0:44f9a43e4ab2 | 786 | if(tgt_angle - 0.5 < now_angle && now_angle < tgt_angle + 0.5) break; //目標角度からの許容誤差内に機体の角度が収まった時、補正終了 |
yuki0701 | 0:44f9a43e4ab2 | 787 | if(id1_value[0] != 1)break; |
yuki0701 | 0:44f9a43e4ab2 | 788 | } |
yuki0701 | 0:44f9a43e4ab2 | 789 | MaxonControl(0,0,0,0); |
yuki0701 | 0:44f9a43e4ab2 | 790 | }*/ |
yuki0701 | 0:44f9a43e4ab2 | 791 | |
yuki0701 | 0:44f9a43e4ab2 | 792 | void pos_correction(double tgt_x, double tgt_y, double tgt_angle, double u, double v, double v_base) //改良版 位置補正(使用前にMaxonControl(0,0,0,0)を入れる) |
yuki0701 | 0:44f9a43e4ab2 | 793 | { |
yuki0701 | 0:44f9a43e4ab2 | 794 | //距離に比例させて補正初速度を増加させる。(最大速度を設定しそれ以上は出ないようにする) |
yuki0701 | 0:44f9a43e4ab2 | 795 | |
yuki0701 | 0:44f9a43e4ab2 | 796 | double first_speed, first_speed50 = 10, last_speed = 10, Max_speed = 500, speed5 = 20; |
yuki0701 | 0:44f9a43e4ab2 | 797 | double r, R=25; // r:一回補正が入るごとの機体の位置と目標位置の距離(ズレ) R:補正終了とみなす目標位置からの機体の位置のズレ |
yuki0701 | 0:44f9a43e4ab2 | 798 | double out; |
yuki0701 | 0:44f9a43e4ab2 | 799 | |
yuki0701 | 0:44f9a43e4ab2 | 800 | calc_xy(tgt_angle, u, v); |
yuki0701 | 0:44f9a43e4ab2 | 801 | |
yuki0701 | 0:44f9a43e4ab2 | 802 | //r = hypot(now_x - tgt_x, now_y - tgt_y); |
yuki0701 | 0:44f9a43e4ab2 | 803 | |
yuki0701 | 0:44f9a43e4ab2 | 804 | while(1) { //機体の位置を目標領域(目標座標+許容誤差)に収める |
yuki0701 | 0:44f9a43e4ab2 | 805 | //printf("col\n\n\n"); |
yuki0701 | 0:44f9a43e4ab2 | 806 | if(id1_value[0] != 1)break; |
yuki0701 | 0:44f9a43e4ab2 | 807 | if(id1_value[6] != flag)break; |
yuki0701 | 0:44f9a43e4ab2 | 808 | |
yuki0701 | 0:44f9a43e4ab2 | 809 | //first_speed = first_speed50 * r / 50; |
yuki0701 | 0:44f9a43e4ab2 | 810 | |
yuki0701 | 0:44f9a43e4ab2 | 811 | /*if(first_speed > Max_speed){ |
yuki0701 | 0:44f9a43e4ab2 | 812 | 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); |
yuki0701 | 0:44f9a43e4ab2 | 813 | }else{ |
yuki0701 | 0:44f9a43e4ab2 | 814 | 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); |
yuki0701 | 0:44f9a43e4ab2 | 815 | }*/ |
yuki0701 | 0:44f9a43e4ab2 | 816 | |
yuki0701 | 0:44f9a43e4ab2 | 817 | //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); |
yuki0701 | 0:44f9a43e4ab2 | 818 | |
yuki0701 | 0:44f9a43e4ab2 | 819 | int diff_sm = hypot(now_x-tgt_x,now_y-tgt_y); |
yuki0701 | 0:44f9a43e4ab2 | 820 | |
yuki0701 | 0:44f9a43e4ab2 | 821 | int f_speed = diff_sm / 5 * (speed5 - last_speed); |
yuki0701 | 0:44f9a43e4ab2 | 822 | 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); |
yuki0701 | 0:44f9a43e4ab2 | 823 | //gogo_straight(1,1,0,0,200,0,50,500,5,0.1,10,0.1,50,0); |
yuki0701 | 0:44f9a43e4ab2 | 824 | //gogo_straight(u,v,now_x,now_y,0,100,first_speed50,last_speed,5,0.1,10,0.1,500,tgt_angle); |
yuki0701 | 0:44f9a43e4ab2 | 825 | |
yuki0701 | 0:44f9a43e4ab2 | 826 | // MaxonControl(0,0,0,0); |
yuki0701 | 0:44f9a43e4ab2 | 827 | m1 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 828 | m2 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 829 | m3 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 830 | m4 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 831 | |
yuki0701 | 0:44f9a43e4ab2 | 832 | calc_xy(tgt_angle, u, v); |
yuki0701 | 0:44f9a43e4ab2 | 833 | |
yuki0701 | 0:44f9a43e4ab2 | 834 | r=hypot(now_x - tgt_x, now_y - tgt_y); |
yuki0701 | 0:44f9a43e4ab2 | 835 | |
yuki0701 | 0:44f9a43e4ab2 | 836 | if(r < R) break; |
yuki0701 | 0:44f9a43e4ab2 | 837 | } |
yuki0701 | 0:44f9a43e4ab2 | 838 | |
yuki0701 | 0:44f9a43e4ab2 | 839 | while(1) { |
yuki0701 | 0:44f9a43e4ab2 | 840 | |
yuki0701 | 0:44f9a43e4ab2 | 841 | if(id1_value[0] != 1)break; |
yuki0701 | 0:44f9a43e4ab2 | 842 | if(id1_value[6] != flag)break; |
yuki0701 | 0:44f9a43e4ab2 | 843 | |
yuki0701 | 0:44f9a43e4ab2 | 844 | //calc_gyro(); |
yuki0701 | 0:44f9a43e4ab2 | 845 | // now_angle=gyro.getAngle(); |
yuki0701 | 0:44f9a43e4ab2 | 846 | now_angle = -gyro.getZ_Angle() + angle_base; |
yuki0701 | 0:44f9a43e4ab2 | 847 | if(tgt_angle - 1 < now_angle && now_angle < tgt_angle + 1) break; //目標角度からの許容誤差内に機体の角度が収まった時、補正終了 |
yuki0701 | 0:44f9a43e4ab2 | 848 | else if(now_angle > tgt_angle + 1)out = 5 * (tgt_angle - now_angle + 1); |
yuki0701 | 0:44f9a43e4ab2 | 849 | else if(tgt_angle - 1 > now_angle)out = 5 * (tgt_angle - now_angle - 1); |
yuki0701 | 0:44f9a43e4ab2 | 850 | |
yuki0701 | 0:44f9a43e4ab2 | 851 | printf("angle = %f out = %f\n\r",now_angle,out); |
yuki0701 | 0:44f9a43e4ab2 | 852 | |
yuki0701 | 0:44f9a43e4ab2 | 853 | if(out > 100) { //0~179°のときは時計回りに回転 |
yuki0701 | 0:44f9a43e4ab2 | 854 | // MaxonControl(-300,-300,-300,-300); |
yuki0701 | 0:44f9a43e4ab2 | 855 | m1 = -100; |
yuki0701 | 0:44f9a43e4ab2 | 856 | m2 = -100; |
yuki0701 | 0:44f9a43e4ab2 | 857 | m3 = -100; |
yuki0701 | 0:44f9a43e4ab2 | 858 | m4 = -100; |
yuki0701 | 0:44f9a43e4ab2 | 859 | |
yuki0701 | 0:44f9a43e4ab2 | 860 | } else if(out < -100) { |
yuki0701 | 0:44f9a43e4ab2 | 861 | // MaxonControl(300,300,300,300); |
yuki0701 | 0:44f9a43e4ab2 | 862 | m1 = 100; |
yuki0701 | 0:44f9a43e4ab2 | 863 | m2 = 100; |
yuki0701 | 0:44f9a43e4ab2 | 864 | m3 = 100; |
yuki0701 | 0:44f9a43e4ab2 | 865 | m4 = 100; |
yuki0701 | 0:44f9a43e4ab2 | 866 | } else if(out <= 100 && out > -100) { |
yuki0701 | 0:44f9a43e4ab2 | 867 | // MaxonControl(-out,-out,-out,-out); |
yuki0701 | 0:44f9a43e4ab2 | 868 | m1 = -out; |
yuki0701 | 0:44f9a43e4ab2 | 869 | m2 = -out; |
yuki0701 | 0:44f9a43e4ab2 | 870 | m3 = -out; |
yuki0701 | 0:44f9a43e4ab2 | 871 | m4 = -out; |
yuki0701 | 0:44f9a43e4ab2 | 872 | } |
yuki0701 | 0:44f9a43e4ab2 | 873 | |
yuki0701 | 0:44f9a43e4ab2 | 874 | /* if(out > 100) { //0~179°のときは時計回りに回転 |
yuki0701 | 0:44f9a43e4ab2 | 875 | // MaxonControl(-300,-300,-300,-300); |
yuki0701 | 0:44f9a43e4ab2 | 876 | m1 = 9900; |
yuki0701 | 0:44f9a43e4ab2 | 877 | m2 = 9900; |
yuki0701 | 0:44f9a43e4ab2 | 878 | m3 = 9900; |
yuki0701 | 0:44f9a43e4ab2 | 879 | m4 = 9900; |
yuki0701 | 0:44f9a43e4ab2 | 880 | |
yuki0701 | 0:44f9a43e4ab2 | 881 | } else if(out < -100) { |
yuki0701 | 0:44f9a43e4ab2 | 882 | // MaxonControl(300,300,300,300); |
yuki0701 | 0:44f9a43e4ab2 | 883 | m1 = 10100; |
yuki0701 | 0:44f9a43e4ab2 | 884 | m2 = 10100; |
yuki0701 | 0:44f9a43e4ab2 | 885 | m3 = 10100; |
yuki0701 | 0:44f9a43e4ab2 | 886 | m4 = 10100; |
yuki0701 | 0:44f9a43e4ab2 | 887 | } else if(out <= 100 && out > -100) { |
yuki0701 | 0:44f9a43e4ab2 | 888 | // MaxonControl(-out,-out,-out,-out); |
yuki0701 | 0:44f9a43e4ab2 | 889 | m1 = -out + 10000; |
yuki0701 | 0:44f9a43e4ab2 | 890 | m2 = -out + 10000; |
yuki0701 | 0:44f9a43e4ab2 | 891 | m3 = -out + 10000; |
yuki0701 | 0:44f9a43e4ab2 | 892 | m4 = -out + 10000; |
yuki0701 | 0:44f9a43e4ab2 | 893 | }*/ |
yuki0701 | 0:44f9a43e4ab2 | 894 | |
yuki0701 | 0:44f9a43e4ab2 | 895 | } |
yuki0701 | 0:44f9a43e4ab2 | 896 | // MaxonControl(0,0,0,0); |
yuki0701 | 0:44f9a43e4ab2 | 897 | m1 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 898 | m2 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 899 | m3 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 900 | m4 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 901 | } |
yuki0701 | 0:44f9a43e4ab2 | 902 | |
yuki0701 | 0:44f9a43e4ab2 | 903 | void mt_stop() |
yuki0701 | 0:44f9a43e4ab2 | 904 | { |
yuki0701 | 0:44f9a43e4ab2 | 905 | m1 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 906 | m2 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 907 | m3 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 908 | m4 = 0; |
yuki0701 | 0:44f9a43e4ab2 | 909 | printf("motor stop\n\r"); |
yuki0701 | 0:44f9a43e4ab2 | 910 | } |
yuki0701 | 0:44f9a43e4ab2 | 911 | |
yuki0701 | 0:44f9a43e4ab2 | 912 | void mt_check(double out, int dr) |
yuki0701 | 0:44f9a43e4ab2 | 913 | { |
yuki0701 | 0:44f9a43e4ab2 | 914 | // dr→ 1:x+ 2:x- 3:y+ 4:y- |
yuki0701 | 0:44f9a43e4ab2 | 915 | while(1) { |
yuki0701 | 0:44f9a43e4ab2 | 916 | if(dr == 1) { |
yuki0701 | 0:44f9a43e4ab2 | 917 | m1 = out; |
yuki0701 | 0:44f9a43e4ab2 | 918 | m2 = -out; |
yuki0701 | 0:44f9a43e4ab2 | 919 | m3 = -out; |
yuki0701 | 0:44f9a43e4ab2 | 920 | m4 = out; |
yuki0701 | 0:44f9a43e4ab2 | 921 | } else if(dr == 2) { |
yuki0701 | 0:44f9a43e4ab2 | 922 | m1 = -out; |
yuki0701 | 0:44f9a43e4ab2 | 923 | m2 = out; |
yuki0701 | 0:44f9a43e4ab2 | 924 | m3 = out; |
yuki0701 | 0:44f9a43e4ab2 | 925 | m4 = -out; |
yuki0701 | 0:44f9a43e4ab2 | 926 | } else if(dr == 3) { |
yuki0701 | 0:44f9a43e4ab2 | 927 | m1 = out; |
yuki0701 | 0:44f9a43e4ab2 | 928 | m2 = out; |
yuki0701 | 0:44f9a43e4ab2 | 929 | m3 = -out; |
yuki0701 | 0:44f9a43e4ab2 | 930 | m4 = -out; |
yuki0701 | 0:44f9a43e4ab2 | 931 | } else if(dr == 4) { |
yuki0701 | 0:44f9a43e4ab2 | 932 | m1 = -out; |
yuki0701 | 0:44f9a43e4ab2 | 933 | m2 = -out; |
yuki0701 | 0:44f9a43e4ab2 | 934 | m3 = out; |
yuki0701 | 0:44f9a43e4ab2 | 935 | m4 = out; |
yuki0701 | 0:44f9a43e4ab2 | 936 | } |
yuki0701 | 0:44f9a43e4ab2 | 937 | |
yuki0701 | 0:44f9a43e4ab2 | 938 | printf("motor check out = %f\n\r",out); |
yuki0701 | 0:44f9a43e4ab2 | 939 | } |
yuki0701 | 0:44f9a43e4ab2 | 940 | } |