harurobo_mbed_undercarriage_sub
PathFollowing.cpp@8:524d86b2073f, 2019-01-11 (annotated)
- Committer:
- yuki0701
- Date:
- Fri Jan 11 08:28:11 2019 +0000
- Revision:
- 8:524d86b2073f
- Parent:
- 7:48af3a9c5bdd
a
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
yuki0701 | 7:48af3a9c5bdd | 1 | #include "PathFollowing.h" |
la00noix | 0:591749f315ac | 2 | #include <mbed.h> |
la00noix | 0:591749f315ac | 3 | #include <math.h> |
yuki0701 | 6:efe1bc381434 | 4 | #include "EC.h" |
yuki0701 | 6:efe1bc381434 | 5 | #include "R1370P.h" |
yuki0701 | 6:efe1bc381434 | 6 | #include "move4wheel.h" |
yuki0701 | 6:efe1bc381434 | 7 | #include <stdarg.h> |
yuki0701 | 6:efe1bc381434 | 8 | #include "Maxon_setting.h" |
yuki0701 | 6:efe1bc381434 | 9 | |
yuki0701 | 6:efe1bc381434 | 10 | #define PI 3.141592 |
yuki0701 | 6:efe1bc381434 | 11 | |
la00noix | 0:591749f315ac | 12 | |
yuki0701 | 1:d438093cb464 | 13 | double p_out,r_out_max; |
la00noix | 0:591749f315ac | 14 | double Kvq_p,Kvq_d,Kvr_p,Kvr_d; |
la00noix | 0:591749f315ac | 15 | double diff_old,diffangle,diffangle_old; |
la00noix | 0:591749f315ac | 16 | double out_dutyQ,out_dutyR; |
la00noix | 0:591749f315ac | 17 | double now_angle,target_angle; |
la00noix | 0:591749f315ac | 18 | double now_timeQ,old_timeQ,now_timeR,old_timeR; |
la00noix | 0:591749f315ac | 19 | double now_x, now_y; |
yuki0701 | 4:69775231687c | 20 | double diff_st,diff_tgt,diff_st_tgt,p_param; |
yuki0701 | 6:efe1bc381434 | 21 | double usw_data1,usw_data2,usw_data3,usw_data4; |
la00noix | 0:591749f315ac | 22 | |
yuki0701 | 1:d438093cb464 | 23 | |
yuki0701 | 6:efe1bc381434 | 24 | Ticker motor_tick; //角速度計算用ticker |
yuki0701 | 6:efe1bc381434 | 25 | //Ticker ticker; //for enc |
la00noix | 0:591749f315ac | 26 | Timer timer; |
la00noix | 0:591749f315ac | 27 | |
yuki0701 | 6:efe1bc381434 | 28 | Ec EC1(p8,p26,NC,500,0.05); |
yuki0701 | 6:efe1bc381434 | 29 | Ec EC2(p21,p22,NC,500,0.05); |
yuki0701 | 6:efe1bc381434 | 30 | R1370P gyro(p28,p27); |
yuki0701 | 6:efe1bc381434 | 31 | |
yuki0701 | 6:efe1bc381434 | 32 | double new_dist1=0,new_dist2=0; |
yuki0701 | 6:efe1bc381434 | 33 | double old_dist1=0,old_dist2=0; |
yuki0701 | 6:efe1bc381434 | 34 | double d_dist1=0,d_dist2=0; //座標計算用関数 |
yuki0701 | 6:efe1bc381434 | 35 | double d_x,d_y; |
yuki0701 | 6:efe1bc381434 | 36 | //現在地X,y座標、現在角度については、PathFollowingでnow_x,now_y,now_angleを定義済 |
yuki0701 | 6:efe1bc381434 | 37 | double start_x=0,start_y=0; //スタート位置 |
yuki0701 | 6:efe1bc381434 | 38 | |
yuki0701 | 6:efe1bc381434 | 39 | double x_out,y_out,r_out; //出力値 |
yuki0701 | 6:efe1bc381434 | 40 | |
yuki0701 | 6:efe1bc381434 | 41 | static int16_t m_1=0, m_2=0, m_3=0, m_4=0; //int16bit = int2byte |
yuki0701 | 6:efe1bc381434 | 42 | |
yuki0701 | 7:48af3a9c5bdd | 43 | double xy_type,pm_typeX,pm_typeY,x_base,y_base; |
yuki0701 | 6:efe1bc381434 | 44 | |
yuki0701 | 6:efe1bc381434 | 45 | |
yuki0701 | 7:48af3a9c5bdd | 46 | ///////////////////機体情報をメンバとする構造体"robo_data"と構造体型変数info(←この変数に各センサーにより求めた機体情報(機体位置/機体角度)を格納する)の宣言///////////////// |
yuki0701 | 7:48af3a9c5bdd | 47 | |
yuki0701 | 7:48af3a9c5bdd | 48 | /*「info.(機体情報の種類).(使用センサーの種類)」に各情報を格納する |
yuki0701 | 7:48af3a9c5bdd | 49 | *状況に応じて、どのセンサーにより算出した情報を信用するかを選択し、その都度now_angle,now_x,now_yに代入する。(何種類かのセンサーの情報を混ぜて使用することも可能) |
yuki0701 | 7:48af3a9c5bdd | 50 | *(ex) |
yuki0701 | 7:48af3a9c5bdd | 51 | *info.nowX.enc → エンコーダにより算出した機体位置のx座標 |
yuki0701 | 7:48af3a9c5bdd | 52 | *info.nowY.usw → 超音波センサーにより求めた機体位置のy座標 |
yuki0701 | 7:48af3a9c5bdd | 53 | */ |
yuki0701 | 7:48af3a9c5bdd | 54 | |
yuki0701 | 7:48af3a9c5bdd | 55 | typedef struct{ //使用センサーの種類 |
yuki0701 | 7:48af3a9c5bdd | 56 | double usw; //超音波センサー |
yuki0701 | 7:48af3a9c5bdd | 57 | double enc; //エンコーダ |
yuki0701 | 7:48af3a9c5bdd | 58 | double gyro; //ジャイロ |
yuki0701 | 7:48af3a9c5bdd | 59 | //double line;//ラインセンサー |
yuki0701 | 7:48af3a9c5bdd | 60 | }robo_sensor; |
yuki0701 | 7:48af3a9c5bdd | 61 | |
yuki0701 | 7:48af3a9c5bdd | 62 | typedef struct{ //機体情報の種類 |
yuki0701 | 7:48af3a9c5bdd | 63 | robo_sensor angle; //←機体角度は超音波センサーやラインセンサーからも算出可能なので一応格納先を用意したが、ジャイロの値を完全に信用してもいいかも |
yuki0701 | 7:48af3a9c5bdd | 64 | robo_sensor nowX; |
yuki0701 | 7:48af3a9c5bdd | 65 | robo_sensor nowY; |
yuki0701 | 7:48af3a9c5bdd | 66 | }robo_data; |
yuki0701 | 7:48af3a9c5bdd | 67 | |
yuki0701 | 7:48af3a9c5bdd | 68 | robo_data info={{0,0,0},{0,0,0},{0,0,0}}; //全てのデータを0に初期化 |
yuki0701 | 7:48af3a9c5bdd | 69 | |
yuki0701 | 7:48af3a9c5bdd | 70 | |
yuki0701 | 7:48af3a9c5bdd | 71 | //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// |
yuki0701 | 7:48af3a9c5bdd | 72 | |
yuki0701 | 6:efe1bc381434 | 73 | |
yuki0701 | 6:efe1bc381434 | 74 | void UserLoopSetting2(){ |
yuki0701 | 6:efe1bc381434 | 75 | |
yuki0701 | 6:efe1bc381434 | 76 | gyro.initialize(); |
yuki0701 | 8:524d86b2073f | 77 | motor_tick.attach(&calOmega,0.05); //0.05秒間隔で角速度を計算 |
yuki0701 | 6:efe1bc381434 | 78 | EC1.setDiameter_mm(48); |
yuki0701 | 6:efe1bc381434 | 79 | EC2.setDiameter_mm(48); //測定輪半径//後で測定 |
yuki0701 | 6:efe1bc381434 | 80 | |
yuki0701 | 6:efe1bc381434 | 81 | } |
yuki0701 | 6:efe1bc381434 | 82 | |
la00noix | 0:591749f315ac | 83 | //初期座標:A, 目標座標:B、機体位置:C、点Cから直線ABに下ろした垂線の足:H |
yuki0701 | 4:69775231687c | 84 | 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はグローバル変数として定義する必要あり |
yuki0701 | 4:69775231687c | 85 | //plot_x1,plot_y1:出発地点の座標 |
yuki0701 | 4:69775231687c | 86 | //plot_x2,plot_y2:目標地点の座標 |
yuki0701 | 4:69775231687c | 87 | //speed1:初期速度 |
yuki0701 | 4:69775231687c | 88 | //speed2:目標速度 |
la00noix | 0:591749f315ac | 89 | { |
la00noix | 0:591749f315ac | 90 | double Vector_P[2] = {(plot_x2 - plot_x1), (plot_y2 - plot_y1)}; //ベクトルAB |
la00noix | 0:591749f315ac | 91 | double A_Vector_P = hypot(Vector_P[0], Vector_P[1]); //ベクトルABの大きさ(hypot(a,b)で√(a^2+b^2)を計算できる <math.h>)) |
la00noix | 0:591749f315ac | 92 | double UnitVector_P[2] = {Vector_P[0]/A_Vector_P, Vector_P[1]/A_Vector_P}; //ベクトルABの単位ベクトル |
la00noix | 0:591749f315ac | 93 | double UnitVector_Q[2] = {UnitVector_P[1], -UnitVector_P[0]}; //ベクトルCHの単位ベクトル |
la00noix | 0:591749f315ac | 94 | double Vector_R[2] = {(now_x - plot_x1), (now_y - plot_y1)}; //ベクトルAC |
la00noix | 0:591749f315ac | 95 | double diff = UnitVector_P[0]*Vector_R[1] - UnitVector_P[1]*Vector_R[0]; //機体位置と直線ABの距離(外積を用いて計算) |
la00noix | 0:591749f315ac | 96 | |
yuki0701 | 4:69775231687c | 97 | |
yuki0701 | 4:69775231687c | 98 | //double VectorOut_P[2]= {0}; //ベクトルABに平行方向の出力をx軸方向、y軸方向の出力に分解*/ |
la00noix | 0:591749f315ac | 99 | |
la00noix | 0:591749f315ac | 100 | ///////////////////<XYRmotorout関数内>以下、ベクトルABに垂直な方向の誤差を埋めるPD制御(ベクトルABに垂直方向の出力を求め、x軸方向、y軸方向の出力に分解)////////////////////// |
la00noix | 0:591749f315ac | 101 | |
la00noix | 0:591749f315ac | 102 | timer.start(); |
la00noix | 0:591749f315ac | 103 | now_timeQ=timer.read(); |
la00noix | 0:591749f315ac | 104 | out_dutyQ=Kvq_p*diff+Kvq_d*(diff-diff_old)/(now_timeQ-old_timeQ); //ベクトルABに垂直方向の出力を決定 |
la00noix | 0:591749f315ac | 105 | diff_old=diff; |
la00noix | 0:591749f315ac | 106 | |
yuki0701 | 2:32362343f091 | 107 | if(out_dutyQ>500)out_dutyQ=500; |
yuki0701 | 2:32362343f091 | 108 | if(out_dutyQ<-500)out_dutyQ=-500; |
la00noix | 0:591749f315ac | 109 | |
la00noix | 0:591749f315ac | 110 | old_timeQ=now_timeQ; |
la00noix | 0:591749f315ac | 111 | |
la00noix | 0:591749f315ac | 112 | double VectorOut_Q[2] = {out_dutyQ*UnitVector_Q[0], out_dutyQ*UnitVector_Q[1]}; //ベクトルABに垂直方向の出力をx軸方向、y軸方向の出力に分解 |
la00noix | 0:591749f315ac | 113 | |
la00noix | 0:591749f315ac | 114 | ///////////////////////////////<XYRmotorout関数内>以下、機体角度と目標角度の誤差を埋めるPD制御(旋回のための出力値を決定)////////////////////////////////// |
la00noix | 0:591749f315ac | 115 | |
la00noix | 0:591749f315ac | 116 | now_timeR=timer.read(); |
la00noix | 0:591749f315ac | 117 | diffangle=target_angle-now_angle; |
yuki0701 | 1:d438093cb464 | 118 | out_dutyR=-(Kvr_p*diffangle+Kvr_d*(diffangle-diffangle_old)/(now_timeR-old_timeR)); |
la00noix | 0:591749f315ac | 119 | diffangle_old=diffangle; |
la00noix | 0:591749f315ac | 120 | |
yuki0701 | 1:d438093cb464 | 121 | if(out_dutyR>r_out_max)out_dutyR=r_out_max; |
yuki0701 | 1:d438093cb464 | 122 | if(out_dutyR<-r_out_max)out_dutyR=-r_out_max; |
la00noix | 0:591749f315ac | 123 | |
la00noix | 0:591749f315ac | 124 | old_timeR=now_timeR; |
la00noix | 0:591749f315ac | 125 | |
la00noix | 0:591749f315ac | 126 | //////////////////////////<XYRmotorout関数内>以下、x軸方向、y軸方向、旋回の出力をそれぞれad_x_out,ad_y_out,ad_r_outの指すアドレスに書き込む///////////////////////////// |
la00noix | 0:591749f315ac | 127 | ////////////////////////////////////////////その際、x軸方向、y軸方向の出力はフィールドの座標系から機体の座標系に変換する。/////////////////////////////////////////////// |
yuki0701 | 4:69775231687c | 128 | |
yuki0701 | 4:69775231687c | 129 | diff_st = hypot(now_x-plot_x1,now_y-plot_y1); //出発座標と機体の位置の距離 |
yuki0701 | 4:69775231687c | 130 | diff_tgt = hypot(now_x - plot_x2, now_y - plot_y2); //機体の位置と目標座標の距離 |
yuki0701 | 4:69775231687c | 131 | diff_st_tgt = hypot(plot_x1-plot_x2,plot_y1-plot_y2); //出発座標と目標座標の距離 |
yuki0701 | 4:69775231687c | 132 | |
yuki0701 | 4:69775231687c | 133 | if(speed1 == speed2) { //等速移動 |
yuki0701 | 4:69775231687c | 134 | |
yuki0701 | 4:69775231687c | 135 | double VectorOut_P[2] = {speed1*UnitVector_P[0], speed1*UnitVector_P[1]}; |
yuki0701 | 4:69775231687c | 136 | |
yuki0701 | 4:69775231687c | 137 | *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); |
yuki0701 | 4:69775231687c | 138 | *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); |
yuki0701 | 4:69775231687c | 139 | *ad_r_out = out_dutyR; |
la00noix | 0:591749f315ac | 140 | |
yuki0701 | 4:69775231687c | 141 | } else if(speed2 == 0) { //減速移動(目標速度が0)→ベクトルABに垂直な方向の出力にもP制御をかける。 |
yuki0701 | 4:69775231687c | 142 | |
yuki0701 | 4:69775231687c | 143 | double VectorOut_P[2] = {speed1*UnitVector_P[0], speed1*UnitVector_P[1]}; |
yuki0701 | 4:69775231687c | 144 | |
yuki0701 | 4:69775231687c | 145 | if(diff_tgt > diff_st_tgt) { |
yuki0701 | 4:69775231687c | 146 | diff_tgt = diff_st_tgt; |
yuki0701 | 4:69775231687c | 147 | } |
yuki0701 | 2:32362343f091 | 148 | |
yuki0701 | 4:69775231687c | 149 | p_param=(diff_tgt/diff_st_tgt); |
yuki0701 | 4:69775231687c | 150 | |
yuki0701 | 4:69775231687c | 151 | *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)); |
yuki0701 | 4:69775231687c | 152 | *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)); |
yuki0701 | 4:69775231687c | 153 | *ad_r_out = out_dutyR; |
yuki0701 | 4:69775231687c | 154 | |
yuki0701 | 4:69775231687c | 155 | } else if(speed1 > speed2) { //減速移動(目標速度が0でない) |
yuki0701 | 2:32362343f091 | 156 | |
yuki0701 | 4:69775231687c | 157 | if(diff_tgt > diff_st_tgt) { |
yuki0701 | 4:69775231687c | 158 | diff_tgt = diff_st_tgt; |
yuki0701 | 4:69775231687c | 159 | } |
yuki0701 | 4:69775231687c | 160 | |
yuki0701 | 4:69775231687c | 161 | p_param=(diff_tgt/diff_st_tgt); |
yuki0701 | 4:69775231687c | 162 | |
yuki0701 | 4:69775231687c | 163 | double speed3 = speed2 + (speed1-speed2)*p_param; |
yuki0701 | 4:69775231687c | 164 | |
yuki0701 | 4:69775231687c | 165 | double VectorOut_P[2] = {speed3*UnitVector_P[0], speed3*UnitVector_P[1]}; |
yuki0701 | 4:69775231687c | 166 | |
yuki0701 | 4:69775231687c | 167 | *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); |
yuki0701 | 4:69775231687c | 168 | *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); |
yuki0701 | 4:69775231687c | 169 | *ad_r_out = out_dutyR; |
yuki0701 | 2:32362343f091 | 170 | |
yuki0701 | 4:69775231687c | 171 | } else if(speed1 < speed2) { //加速移動(speed1) |
yuki0701 | 4:69775231687c | 172 | |
yuki0701 | 4:69775231687c | 173 | if(diff_st > diff_st_tgt) { |
yuki0701 | 4:69775231687c | 174 | diff_st = diff_st_tgt; |
yuki0701 | 4:69775231687c | 175 | } |
yuki0701 | 4:69775231687c | 176 | |
yuki0701 | 4:69775231687c | 177 | p_param=(diff_st/diff_st_tgt); |
yuki0701 | 2:32362343f091 | 178 | |
yuki0701 | 4:69775231687c | 179 | double speed4 = speed1 + (speed2-speed1)*p_param; |
yuki0701 | 4:69775231687c | 180 | |
yuki0701 | 4:69775231687c | 181 | double VectorOut_P[2] = {speed4*UnitVector_P[0], speed4*UnitVector_P[1]}; |
yuki0701 | 4:69775231687c | 182 | |
yuki0701 | 4:69775231687c | 183 | *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); |
yuki0701 | 4:69775231687c | 184 | *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); |
yuki0701 | 4:69775231687c | 185 | *ad_r_out = out_dutyR; |
yuki0701 | 2:32362343f091 | 186 | } |
la00noix | 0:591749f315ac | 187 | } |
la00noix | 0:591749f315ac | 188 | |
la00noix | 0:591749f315ac | 189 | ////////////////////////////////////////////////////////////<XYRmotorout関数は以上>//////////////////////////////////////////////////////////////// |
la00noix | 0:591749f315ac | 190 | |
la00noix | 0:591749f315ac | 191 | |
yuki0701 | 4:69775231687c | 192 | /*void set_p_out(double p) //ベクトルABに平行方向の出力値設定関数 |
la00noix | 0:591749f315ac | 193 | { |
la00noix | 0:591749f315ac | 194 | p_out = p; |
yuki0701 | 4:69775231687c | 195 | }*/ |
la00noix | 0:591749f315ac | 196 | |
la00noix | 0:591749f315ac | 197 | void q_setPDparam(double q_p,double q_d) //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数 |
la00noix | 0:591749f315ac | 198 | { |
la00noix | 0:591749f315ac | 199 | Kvq_p=q_p; |
la00noix | 0:591749f315ac | 200 | Kvq_d=q_d; |
la00noix | 0:591749f315ac | 201 | } |
la00noix | 0:591749f315ac | 202 | |
la00noix | 0:591749f315ac | 203 | void r_setPDparam(double r_p,double r_d) //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数 |
la00noix | 0:591749f315ac | 204 | { |
la00noix | 0:591749f315ac | 205 | Kvr_p=r_p; |
la00noix | 0:591749f315ac | 206 | Kvr_d=r_d; |
la00noix | 0:591749f315ac | 207 | } |
la00noix | 0:591749f315ac | 208 | |
la00noix | 0:591749f315ac | 209 | void set_r_out(double r) //旋回時の最大出力値設定関数 |
la00noix | 0:591749f315ac | 210 | { |
yuki0701 | 1:d438093cb464 | 211 | r_out_max = r; |
la00noix | 0:591749f315ac | 212 | } |
la00noix | 0:591749f315ac | 213 | |
la00noix | 0:591749f315ac | 214 | void set_target_angle(double t) //機体の目標角度設定関数 |
la00noix | 0:591749f315ac | 215 | { |
la00noix | 0:591749f315ac | 216 | target_angle = t; |
la00noix | 0:591749f315ac | 217 | } |
yuki0701 | 6:efe1bc381434 | 218 | |
yuki0701 | 6:efe1bc381434 | 219 | |
yuki0701 | 6:efe1bc381434 | 220 | void UserLoopSetting(); // initialize setting |
yuki0701 | 6:efe1bc381434 | 221 | void DAC_Write(int16_t data, DigitalOut* DAC_cs); |
yuki0701 | 6:efe1bc381434 | 222 | void MotorControl(int16_t val_md1, int16_t val_md2, int16_t val_md3, int16_t val_md4); |
yuki0701 | 6:efe1bc381434 | 223 | |
yuki0701 | 6:efe1bc381434 | 224 | void calOmega() //角速度計算関数 |
yuki0701 | 6:efe1bc381434 | 225 | { |
yuki0701 | 6:efe1bc381434 | 226 | EC1.CalOmega(); |
yuki0701 | 6:efe1bc381434 | 227 | EC2.CalOmega(); |
yuki0701 | 6:efe1bc381434 | 228 | } |
yuki0701 | 6:efe1bc381434 | 229 | |
yuki0701 | 6:efe1bc381434 | 230 | void output(double FL,double BL,double BR,double FR) |
yuki0701 | 6:efe1bc381434 | 231 | { |
yuki0701 | 7:48af3a9c5bdd | 232 | m_1=FL; |
yuki0701 | 7:48af3a9c5bdd | 233 | m_2=BL; |
yuki0701 | 7:48af3a9c5bdd | 234 | m_3=BR; |
yuki0701 | 7:48af3a9c5bdd | 235 | m_4=FR; |
yuki0701 | 6:efe1bc381434 | 236 | } |
yuki0701 | 6:efe1bc381434 | 237 | |
yuki0701 | 6:efe1bc381434 | 238 | void base(double FL,double BL,double BR,double FR,double Max) |
yuki0701 | 6:efe1bc381434 | 239 | //いろんな加算をしても最大OR最小がMaxになるような補正//絶対値が一番でかいやつで除算 |
yuki0701 | 6:efe1bc381434 | 240 | //DCモーターならMax=1、マクソンは-4095~4095だからMax=4095にする |
yuki0701 | 6:efe1bc381434 | 241 | { |
yuki0701 | 6:efe1bc381434 | 242 | if(fabs(FL)>=Max||fabs(BL)>=Max||fabs(BR)>=Max||fabs(FR)>=Max) { |
yuki0701 | 6:efe1bc381434 | 243 | |
yuki0701 | 6:efe1bc381434 | 244 | 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 | 6:efe1bc381434 | 245 | 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 | 6:efe1bc381434 | 246 | 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 | 6:efe1bc381434 | 247 | else output(Max*FL/fabs(FR),Max*BL/fabs(FR),Max*BR/fabs(FR),Max*FR/fabs(FR)); |
yuki0701 | 6:efe1bc381434 | 248 | } else { |
yuki0701 | 6:efe1bc381434 | 249 | output(FL,BL,BR,FR); |
yuki0701 | 6:efe1bc381434 | 250 | } |
yuki0701 | 6:efe1bc381434 | 251 | } |
yuki0701 | 6:efe1bc381434 | 252 | |
yuki0701 | 7:48af3a9c5bdd | 253 | void calc_xy_enc() //エンコーダによる座標計算 |
yuki0701 | 6:efe1bc381434 | 254 | { |
yuki0701 | 6:efe1bc381434 | 255 | now_angle=gyro.getAngle(); //ジャイロの値読み込み |
yuki0701 | 6:efe1bc381434 | 256 | |
yuki0701 | 6:efe1bc381434 | 257 | new_dist1=EC1.getDistance_mm(); |
yuki0701 | 6:efe1bc381434 | 258 | new_dist2=EC2.getDistance_mm(); |
yuki0701 | 6:efe1bc381434 | 259 | d_dist1=new_dist1-old_dist1; |
yuki0701 | 6:efe1bc381434 | 260 | d_dist2=new_dist2-old_dist2; |
yuki0701 | 6:efe1bc381434 | 261 | old_dist1=new_dist1; |
yuki0701 | 6:efe1bc381434 | 262 | old_dist2=new_dist2; //微小時間当たりのエンコーダ読み込み |
yuki0701 | 6:efe1bc381434 | 263 | |
yuki0701 | 6:efe1bc381434 | 264 | d_x=d_dist2*sin(now_angle*PI/180)-d_dist1*cos(now_angle*PI/180); |
yuki0701 | 6:efe1bc381434 | 265 | d_y=d_dist2*cos(now_angle*PI/180)+d_dist1*sin(now_angle*PI/180); //微小時間毎の座標変化 |
yuki0701 | 7:48af3a9c5bdd | 266 | info.nowX.enc = info.nowX.enc + d_x; |
yuki0701 | 7:48af3a9c5bdd | 267 | info.nowY.enc = info.nowY.enc - d_y; //微小時間毎に座標に加算 |
yuki0701 | 7:48af3a9c5bdd | 268 | } |
yuki0701 | 7:48af3a9c5bdd | 269 | |
yuki0701 | 7:48af3a9c5bdd | 270 | void set_cond(int t, int px, double bx, int py, double by){ //超音波センサーを使用するときの条件設定関数 |
yuki0701 | 8:524d86b2073f | 271 | //引数の詳細は関数"calc_xy_usw"参照 |
yuki0701 | 7:48af3a9c5bdd | 272 | |
yuki0701 | 7:48af3a9c5bdd | 273 | xy_type = t; |
yuki0701 | 7:48af3a9c5bdd | 274 | |
yuki0701 | 7:48af3a9c5bdd | 275 | pm_typeX = px; |
yuki0701 | 7:48af3a9c5bdd | 276 | x_base = bx; |
yuki0701 | 7:48af3a9c5bdd | 277 | |
yuki0701 | 7:48af3a9c5bdd | 278 | pm_typeY = py; |
yuki0701 | 7:48af3a9c5bdd | 279 | y_base = by; |
yuki0701 | 7:48af3a9c5bdd | 280 | |
yuki0701 | 7:48af3a9c5bdd | 281 | } |
yuki0701 | 7:48af3a9c5bdd | 282 | |
yuki0701 | 7:48af3a9c5bdd | 283 | |
yuki0701 | 7:48af3a9c5bdd | 284 | void calc_xy_usw(double tgt_angle){ //超音波センサーによる座標計算(機体が旋回する場合はこの方法による座標計算は出来ない) |
yuki0701 | 7:48af3a9c5bdd | 285 | //tgt_angle:機体の目標角度(運動初期角度と同じ/今大会では0,90,180のみ) |
yuki0701 | 7:48af3a9c5bdd | 286 | //xy_type:(0:Y軸平行の壁を読む/1:X軸平行の壁を読む/2:X,Y軸平行の壁を共に読む) |
yuki0701 | 7:48af3a9c5bdd | 287 | //pm_typeX,pm_typeY:(0:各軸正方向側の壁を読む/1:各軸負方向側の壁を読む) |
yuki0701 | 7:48af3a9c5bdd | 288 | //x_base,y_base:超音波センサーで読む壁の座標(y軸並行の壁のx座標/x軸平行の壁のy座標) |
yuki0701 | 7:48af3a9c5bdd | 289 | |
yuki0701 | 7:48af3a9c5bdd | 290 | double R1=240,R2=240,R3=240,R4=240; //機体の中心から各超音波センサーが付いている面までの距離 |
yuki0701 | 7:48af3a9c5bdd | 291 | double D1=30,D2=30,D3=30,D4=30; //各超音波センサーが付いている面の中心から各超音波センサーまでの距離 |
yuki0701 | 7:48af3a9c5bdd | 292 | |
yuki0701 | 7:48af3a9c5bdd | 293 | now_angle=gyro.getAngle(); |
yuki0701 | 7:48af3a9c5bdd | 294 | |
yuki0701 | 7:48af3a9c5bdd | 295 | if(tgt_angle==0){ |
yuki0701 | 7:48af3a9c5bdd | 296 | if((xy_type==0 || xy_type==2) && pm_typeX==0){ |
yuki0701 | 7:48af3a9c5bdd | 297 | |
yuki0701 | 7:48af3a9c5bdd | 298 | info.nowX.usw = x_base - (usw_data4 + R4*cos(now_angle*PI/180) + D4*sin(now_angle*PI/180)); |
yuki0701 | 7:48af3a9c5bdd | 299 | |
yuki0701 | 7:48af3a9c5bdd | 300 | }else if((xy_type==0 || xy_type==2) && pm_typeX==1){ |
yuki0701 | 7:48af3a9c5bdd | 301 | |
yuki0701 | 7:48af3a9c5bdd | 302 | info.nowX.usw = x_base + (usw_data3 + R3*cos(now_angle*PI/180) + D3*sin(now_angle*PI/180)); |
yuki0701 | 7:48af3a9c5bdd | 303 | |
yuki0701 | 7:48af3a9c5bdd | 304 | } |
yuki0701 | 7:48af3a9c5bdd | 305 | if((xy_type==1 || xy_type==2) && pm_typeY==0){ |
yuki0701 | 7:48af3a9c5bdd | 306 | |
yuki0701 | 7:48af3a9c5bdd | 307 | info.nowY.usw = y_base - (usw_data2 + R2*cos(now_angle*PI/180) + D2*sin(now_angle*PI/180)); |
yuki0701 | 7:48af3a9c5bdd | 308 | |
yuki0701 | 7:48af3a9c5bdd | 309 | }else if((xy_type==1 || xy_type==2) && pm_typeY==1){ |
yuki0701 | 7:48af3a9c5bdd | 310 | |
yuki0701 | 7:48af3a9c5bdd | 311 | info.nowY.usw = y_base + (usw_data1 + R1*cos(now_angle*PI/180) + D1*sin(now_angle*PI/180)); |
yuki0701 | 7:48af3a9c5bdd | 312 | |
yuki0701 | 7:48af3a9c5bdd | 313 | } |
yuki0701 | 7:48af3a9c5bdd | 314 | |
yuki0701 | 7:48af3a9c5bdd | 315 | }else if(tgt_angle==90){ |
yuki0701 | 7:48af3a9c5bdd | 316 | if((xy_type==0 || xy_type==2) && pm_typeX==0){ |
yuki0701 | 7:48af3a9c5bdd | 317 | |
yuki0701 | 7:48af3a9c5bdd | 318 | info.nowX.usw = x_base - (usw_data1 + R1*cos(now_angle*PI/180) + D1*sin(now_angle*PI/180)); |
yuki0701 | 7:48af3a9c5bdd | 319 | |
yuki0701 | 7:48af3a9c5bdd | 320 | }else if((xy_type==0 || xy_type==2) && pm_typeX==1){ |
yuki0701 | 7:48af3a9c5bdd | 321 | |
yuki0701 | 7:48af3a9c5bdd | 322 | info.nowX.usw = x_base + (usw_data2 + R2*cos(now_angle*PI/180) + D2*sin(now_angle*PI/180)); |
yuki0701 | 7:48af3a9c5bdd | 323 | |
yuki0701 | 7:48af3a9c5bdd | 324 | } |
yuki0701 | 7:48af3a9c5bdd | 325 | if((xy_type==1 || xy_type==2) && pm_typeY==0){ |
yuki0701 | 7:48af3a9c5bdd | 326 | |
yuki0701 | 7:48af3a9c5bdd | 327 | info.nowY.usw = y_base - (usw_data4 + R4*cos(now_angle*PI/180) + D4*sin(now_angle*PI/180)); |
yuki0701 | 7:48af3a9c5bdd | 328 | |
yuki0701 | 7:48af3a9c5bdd | 329 | }else if((xy_type==1 || xy_type==2) && pm_typeY==1){ |
yuki0701 | 7:48af3a9c5bdd | 330 | |
yuki0701 | 7:48af3a9c5bdd | 331 | info.nowY.usw = y_base + (usw_data3 + R3*cos(now_angle*PI/180) + D3*sin(now_angle*PI/180)); |
yuki0701 | 7:48af3a9c5bdd | 332 | |
yuki0701 | 7:48af3a9c5bdd | 333 | } |
yuki0701 | 7:48af3a9c5bdd | 334 | |
yuki0701 | 7:48af3a9c5bdd | 335 | }else if(tgt_angle==180){ |
yuki0701 | 7:48af3a9c5bdd | 336 | if((xy_type==0 || xy_type==2) && pm_typeX==0){ |
yuki0701 | 7:48af3a9c5bdd | 337 | |
yuki0701 | 7:48af3a9c5bdd | 338 | info.nowX.usw = x_base - (usw_data3 + R3*cos(now_angle*PI/180) + D3*sin(now_angle*PI/180)); |
yuki0701 | 7:48af3a9c5bdd | 339 | |
yuki0701 | 7:48af3a9c5bdd | 340 | }else if((xy_type==0 || xy_type==2) && pm_typeX==1){ |
yuki0701 | 7:48af3a9c5bdd | 341 | |
yuki0701 | 7:48af3a9c5bdd | 342 | info.nowX.usw = x_base + (usw_data4 + R4*cos(now_angle*PI/180) + D4*sin(now_angle*PI/180)); |
yuki0701 | 7:48af3a9c5bdd | 343 | |
yuki0701 | 7:48af3a9c5bdd | 344 | } |
yuki0701 | 7:48af3a9c5bdd | 345 | if((xy_type==1 || xy_type==2) && pm_typeY==0){ |
yuki0701 | 7:48af3a9c5bdd | 346 | |
yuki0701 | 7:48af3a9c5bdd | 347 | info.nowY.usw = y_base - (usw_data1+ R1*cos(now_angle*PI/180) + D1*sin(now_angle*PI/180)); |
yuki0701 | 7:48af3a9c5bdd | 348 | |
yuki0701 | 7:48af3a9c5bdd | 349 | }else if((xy_type==1 || xy_type==2) && pm_typeY==1){ |
yuki0701 | 7:48af3a9c5bdd | 350 | |
yuki0701 | 7:48af3a9c5bdd | 351 | info.nowY.usw = y_base + (usw_data2 + R2*cos(now_angle*PI/180) + D2*sin(now_angle*PI/180)); |
yuki0701 | 7:48af3a9c5bdd | 352 | |
yuki0701 | 7:48af3a9c5bdd | 353 | } |
yuki0701 | 7:48af3a9c5bdd | 354 | |
yuki0701 | 7:48af3a9c5bdd | 355 | } |
yuki0701 | 7:48af3a9c5bdd | 356 | |
yuki0701 | 7:48af3a9c5bdd | 357 | } |
yuki0701 | 7:48af3a9c5bdd | 358 | |
yuki0701 | 7:48af3a9c5bdd | 359 | void calc_xy(double target_angle, double u,double v){ //エンコーダにより求めた機体の座標と超音波センサーにより求めた機体の座標を(エンコーダ : 超音波 = u : i-u / v : i-v)の割合で混ぜて now_x,now_y に代入する。 |
yuki0701 | 7:48af3a9c5bdd | 360 | |
yuki0701 | 7:48af3a9c5bdd | 361 | calc_xy_enc(); |
yuki0701 | 7:48af3a9c5bdd | 362 | |
yuki0701 | 7:48af3a9c5bdd | 363 | if(u != 1){ |
yuki0701 | 7:48af3a9c5bdd | 364 | calc_xy_usw(target_angle); //エンコーダの値しか使用しない場合は超音波センサーによる座標計算は行わずに計算量を減らす。 |
yuki0701 | 7:48af3a9c5bdd | 365 | } |
yuki0701 | 7:48af3a9c5bdd | 366 | if(v != 1){ |
yuki0701 | 7:48af3a9c5bdd | 367 | calc_xy_usw(target_angle); |
yuki0701 | 7:48af3a9c5bdd | 368 | } |
yuki0701 | 7:48af3a9c5bdd | 369 | |
yuki0701 | 7:48af3a9c5bdd | 370 | now_x = u * info.nowX.enc + (1-u) * info.nowX.usw; |
yuki0701 | 7:48af3a9c5bdd | 371 | now_y = v * info.nowY.enc + (1-v) * info.nowY.usw; |
yuki0701 | 7:48af3a9c5bdd | 372 | |
yuki0701 | 6:efe1bc381434 | 373 | } |
yuki0701 | 6:efe1bc381434 | 374 | |
yuki0701 | 6:efe1bc381434 | 375 | //ここからそれぞれのプログラム///////////////////////////////////////////////////////////////////////////////////////////////////////////////// |
yuki0701 | 6:efe1bc381434 | 376 | //now_x(現在のx座標),now_y(現在のy座標),now_angle(機体角度(ラジアンではない)(0~360や-180~180とは限らない))(反時計回りが正) |
yuki0701 | 6:efe1bc381434 | 377 | //ジャイロの出力は角度だが三角関数はラジアンとして計算する |
yuki0701 | 6:efe1bc381434 | 378 | //通常の移動+座標のずれ補正+機体の角度補正(+必要に応じさらに別補正) |
yuki0701 | 6:efe1bc381434 | 379 | //ジャイロの仕様上、角度補正をするときに計算式内で角度はそのままよりsinをとったほうがいいかもね |
yuki0701 | 6:efe1bc381434 | 380 | |
yuki0701 | 7:48af3a9c5bdd | 381 | void purecurve2(int type,double u,double v, //正面を変えずに円弧or楕円を描いて曲がる |
yuki0701 | 6:efe1bc381434 | 382 | double point_x1,double point_y1, |
yuki0701 | 6:efe1bc381434 | 383 | double point_x2,double point_y2, |
yuki0701 | 6:efe1bc381434 | 384 | int theta, |
yuki0701 | 6:efe1bc381434 | 385 | double speed, |
yuki0701 | 6:efe1bc381434 | 386 | double q_p,double q_d, |
yuki0701 | 6:efe1bc381434 | 387 | double r_p,double r_d, |
yuki0701 | 6:efe1bc381434 | 388 | double r_out_max, |
yuki0701 | 6:efe1bc381434 | 389 | double target_angle) |
yuki0701 | 6:efe1bc381434 | 390 | //type:動きの種類(8パターン) point_x1,point_y1=出発地点の座標 point_x2,point_x2=目標地点の座標 theta=plotの間隔(0~90°) speed=速度 |
yuki0701 | 6:efe1bc381434 | 391 | { |
yuki0701 | 6:efe1bc381434 | 392 | //-----PathFollowingのパラメーター設定-----// |
yuki0701 | 6:efe1bc381434 | 393 | q_setPDparam(q_p,q_d); //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数 |
yuki0701 | 6:efe1bc381434 | 394 | r_setPDparam(r_p,r_d); //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数 |
yuki0701 | 6:efe1bc381434 | 395 | set_r_out(r_out_max); //旋回時の最大出力値設定関数 |
yuki0701 | 6:efe1bc381434 | 396 | set_target_angle(target_angle); //機体目標角度設定関数 |
yuki0701 | 6:efe1bc381434 | 397 | |
yuki0701 | 6:efe1bc381434 | 398 | int s; |
yuki0701 | 6:efe1bc381434 | 399 | int t = 0; |
yuki0701 | 6:efe1bc381434 | 400 | double X,Y;//X=楕円の中心座標、Y=楕円の中心座標 |
yuki0701 | 6:efe1bc381434 | 401 | double a,b; //a=楕円のx軸方向の幅の半分,b=楕円のy軸方向の幅の半分 |
yuki0701 | 6:efe1bc381434 | 402 | double plotx[(90/theta)+1]; //楕円にとるplotのx座標 |
yuki0701 | 6:efe1bc381434 | 403 | double ploty[(90/theta)+1]; |
yuki0701 | 6:efe1bc381434 | 404 | |
yuki0701 | 6:efe1bc381434 | 405 | double x_out,y_out,r_out; |
yuki0701 | 6:efe1bc381434 | 406 | |
yuki0701 | 6:efe1bc381434 | 407 | a=fabs(point_x1-point_x2); |
yuki0701 | 6:efe1bc381434 | 408 | b=fabs(point_y1-point_y2); |
yuki0701 | 6:efe1bc381434 | 409 | |
yuki0701 | 6:efe1bc381434 | 410 | switch(type) { |
yuki0701 | 6:efe1bc381434 | 411 | |
yuki0701 | 6:efe1bc381434 | 412 | case 1://→↑移動 |
yuki0701 | 6:efe1bc381434 | 413 | X=point_x1; |
yuki0701 | 6:efe1bc381434 | 414 | Y=point_y2; |
yuki0701 | 6:efe1bc381434 | 415 | |
yuki0701 | 6:efe1bc381434 | 416 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 6:efe1bc381434 | 417 | plotx[s] = X + a * cos(-PI/2 + s * (PI*theta/180)); |
yuki0701 | 6:efe1bc381434 | 418 | ploty[s] = Y + b * sin(-PI/2 + s * (PI*theta/180)); |
yuki0701 | 6:efe1bc381434 | 419 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 6:efe1bc381434 | 420 | } |
yuki0701 | 6:efe1bc381434 | 421 | break; |
yuki0701 | 6:efe1bc381434 | 422 | |
yuki0701 | 6:efe1bc381434 | 423 | case 2://↑→移動 |
yuki0701 | 6:efe1bc381434 | 424 | X=point_x2; |
yuki0701 | 6:efe1bc381434 | 425 | Y=point_y1; |
yuki0701 | 6:efe1bc381434 | 426 | |
yuki0701 | 6:efe1bc381434 | 427 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 6:efe1bc381434 | 428 | plotx[s] = X + a * cos(PI - s * (PI*theta/180)); |
yuki0701 | 6:efe1bc381434 | 429 | ploty[s] = Y + b * sin(PI - s * (PI*theta/180)); |
yuki0701 | 6:efe1bc381434 | 430 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 6:efe1bc381434 | 431 | } |
yuki0701 | 6:efe1bc381434 | 432 | break; |
yuki0701 | 6:efe1bc381434 | 433 | |
yuki0701 | 6:efe1bc381434 | 434 | case 3://↑←移動 |
yuki0701 | 6:efe1bc381434 | 435 | X=point_x2; |
yuki0701 | 6:efe1bc381434 | 436 | Y=point_y1; |
yuki0701 | 6:efe1bc381434 | 437 | |
yuki0701 | 6:efe1bc381434 | 438 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 6:efe1bc381434 | 439 | plotx[s] = X + a * cos(s * (PI*theta/180)); |
yuki0701 | 6:efe1bc381434 | 440 | ploty[s] = Y + b * sin(s * (PI*theta/180)); |
yuki0701 | 6:efe1bc381434 | 441 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 6:efe1bc381434 | 442 | } |
yuki0701 | 6:efe1bc381434 | 443 | break; |
yuki0701 | 6:efe1bc381434 | 444 | |
yuki0701 | 6:efe1bc381434 | 445 | case 4://←↑移動 |
yuki0701 | 6:efe1bc381434 | 446 | X=point_x1; |
yuki0701 | 6:efe1bc381434 | 447 | Y=point_y2; |
yuki0701 | 6:efe1bc381434 | 448 | |
yuki0701 | 6:efe1bc381434 | 449 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 6:efe1bc381434 | 450 | plotx[s] = X + a * cos(-PI/2 - s * (PI*theta/180)); |
yuki0701 | 6:efe1bc381434 | 451 | ploty[s] = Y + b * sin(-PI/2 - s * (PI*theta/180)); |
yuki0701 | 6:efe1bc381434 | 452 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 6:efe1bc381434 | 453 | } |
yuki0701 | 6:efe1bc381434 | 454 | break; |
yuki0701 | 6:efe1bc381434 | 455 | |
yuki0701 | 6:efe1bc381434 | 456 | case 5://←↓移動 |
yuki0701 | 6:efe1bc381434 | 457 | X=point_x1; |
yuki0701 | 6:efe1bc381434 | 458 | Y=point_y2; |
yuki0701 | 6:efe1bc381434 | 459 | |
yuki0701 | 6:efe1bc381434 | 460 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 6:efe1bc381434 | 461 | plotx[s] = X + a * cos(PI/2 + s * (PI*theta/180)); |
yuki0701 | 6:efe1bc381434 | 462 | ploty[s] = Y + b * sin(PI/2 + s * (PI*theta/180)); |
yuki0701 | 6:efe1bc381434 | 463 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 6:efe1bc381434 | 464 | } |
yuki0701 | 6:efe1bc381434 | 465 | break; |
yuki0701 | 6:efe1bc381434 | 466 | |
yuki0701 | 6:efe1bc381434 | 467 | case 6://↓←移動 |
yuki0701 | 6:efe1bc381434 | 468 | X=point_x2; |
yuki0701 | 6:efe1bc381434 | 469 | Y=point_y1; |
yuki0701 | 6:efe1bc381434 | 470 | |
yuki0701 | 6:efe1bc381434 | 471 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 6:efe1bc381434 | 472 | plotx[s] = X + a * cos(-s * (PI*theta/180)); |
yuki0701 | 6:efe1bc381434 | 473 | ploty[s] = Y + b * sin(-s * (PI*theta/180)); |
yuki0701 | 6:efe1bc381434 | 474 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 6:efe1bc381434 | 475 | } |
yuki0701 | 6:efe1bc381434 | 476 | break; |
yuki0701 | 6:efe1bc381434 | 477 | |
yuki0701 | 6:efe1bc381434 | 478 | case 7://↓→移動 |
yuki0701 | 6:efe1bc381434 | 479 | X=point_x2; |
yuki0701 | 6:efe1bc381434 | 480 | Y=point_y1; |
yuki0701 | 6:efe1bc381434 | 481 | |
yuki0701 | 6:efe1bc381434 | 482 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 6:efe1bc381434 | 483 | plotx[s] = X + a * cos(PI + s * (PI*theta/180)); |
yuki0701 | 6:efe1bc381434 | 484 | ploty[s] = Y + b * sin(PI + s * (PI*theta/180)); |
yuki0701 | 6:efe1bc381434 | 485 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 6:efe1bc381434 | 486 | } |
yuki0701 | 6:efe1bc381434 | 487 | break; |
yuki0701 | 6:efe1bc381434 | 488 | |
yuki0701 | 6:efe1bc381434 | 489 | case 8://→↓移動 |
yuki0701 | 6:efe1bc381434 | 490 | X=point_x1; |
yuki0701 | 6:efe1bc381434 | 491 | Y=point_y2; |
yuki0701 | 6:efe1bc381434 | 492 | |
yuki0701 | 6:efe1bc381434 | 493 | for(s=0; s<((90/theta)+1); s++) { |
yuki0701 | 6:efe1bc381434 | 494 | plotx[s] = X + a * cos(PI/2 - s * (PI*theta/180)); |
yuki0701 | 6:efe1bc381434 | 495 | ploty[s] = Y + b * sin(PI/2 - s * (PI*theta/180)); |
yuki0701 | 6:efe1bc381434 | 496 | //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); |
yuki0701 | 6:efe1bc381434 | 497 | } |
yuki0701 | 6:efe1bc381434 | 498 | break; |
yuki0701 | 6:efe1bc381434 | 499 | } |
yuki0701 | 6:efe1bc381434 | 500 | |
yuki0701 | 6:efe1bc381434 | 501 | while(1) { |
yuki0701 | 6:efe1bc381434 | 502 | |
yuki0701 | 7:48af3a9c5bdd | 503 | calc_xy(target_angle,u,v); |
yuki0701 | 6:efe1bc381434 | 504 | |
yuki0701 | 6:efe1bc381434 | 505 | XYRmotorout(plotx[t],ploty[t],plotx[t+1],ploty[t+1],&x_out,&y_out,&r_out,speed,speed); |
yuki0701 | 6:efe1bc381434 | 506 | CalMotorOut(x_out,y_out,r_out); |
yuki0701 | 6:efe1bc381434 | 507 | //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 | 6:efe1bc381434 | 508 | |
yuki0701 | 6:efe1bc381434 | 509 | base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),4095); //m1~m4に代入 |
yuki0701 | 6:efe1bc381434 | 510 | //debug_printf("t=%d (0)=%f (1)=%f (2)=%f (3)=%f\n\r",t,GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3)); |
yuki0701 | 6:efe1bc381434 | 511 | |
yuki0701 | 6:efe1bc381434 | 512 | if(((plotx[t+1] - now_x)*(plotx[t+1] - plotx[t]) + (ploty[t+1] - now_y)*(ploty[t+1] - ploty[t])) < 0)t++; |
yuki0701 | 6:efe1bc381434 | 513 | |
yuki0701 | 6:efe1bc381434 | 514 | MotorControl(m_1,m_2,m_3,m_4); //出力 |
yuki0701 | 6:efe1bc381434 | 515 | debug_printf("t=%d m1=%d m2=%d m3=%d m4=%d x=%f y=%f angle=%f\n\r",t,m_1,m_2,m_3,m_4,now_x,now_y,now_angle); |
yuki0701 | 6:efe1bc381434 | 516 | |
yuki0701 | 6:efe1bc381434 | 517 | if(t == (90/theta))break; |
yuki0701 | 6:efe1bc381434 | 518 | } |
yuki0701 | 6:efe1bc381434 | 519 | } |
yuki0701 | 6:efe1bc381434 | 520 | |
yuki0701 | 6:efe1bc381434 | 521 | |
yuki0701 | 7:48af3a9c5bdd | 522 | void gogo_straight(double u,double v, |
yuki0701 | 7:48af3a9c5bdd | 523 | double x1_point,double y1_point, //直線運動プログラム |
yuki0701 | 6:efe1bc381434 | 524 | double x2_point,double y2_point, |
yuki0701 | 6:efe1bc381434 | 525 | double speed1,double speed2, |
yuki0701 | 6:efe1bc381434 | 526 | double q_p,double q_d, |
yuki0701 | 6:efe1bc381434 | 527 | double r_p,double r_d, |
yuki0701 | 6:efe1bc381434 | 528 | double r_out_max, |
yuki0701 | 7:48af3a9c5bdd | 529 | double target_angle) |
yuki0701 | 6:efe1bc381434 | 530 | //引数:出発地点の座標(x,y)、目標地点の座標(x,y)、初速度(speed1)、目標速度(speed2)//speed1=speed2 のとき等速運動 |
yuki0701 | 6:efe1bc381434 | 531 | { |
yuki0701 | 6:efe1bc381434 | 532 | //-----PathFollowingのパラメーター設定-----// |
yuki0701 | 6:efe1bc381434 | 533 | q_setPDparam(q_p,q_d); //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数 |
yuki0701 | 6:efe1bc381434 | 534 | r_setPDparam(r_p,r_d); //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数 |
yuki0701 | 6:efe1bc381434 | 535 | set_r_out(r_out_max); //旋回時の最大出力値設定関数 |
yuki0701 | 6:efe1bc381434 | 536 | set_target_angle(target_angle); //機体目標角度設定関数 |
yuki0701 | 6:efe1bc381434 | 537 | |
yuki0701 | 6:efe1bc381434 | 538 | while (1) { |
yuki0701 | 6:efe1bc381434 | 539 | |
yuki0701 | 7:48af3a9c5bdd | 540 | calc_xy(target_angle,u,v); |
yuki0701 | 6:efe1bc381434 | 541 | |
yuki0701 | 6:efe1bc381434 | 542 | XYRmotorout(x1_point,y1_point,x2_point,y2_point,&x_out,&y_out,&r_out,speed1,speed2); |
yuki0701 | 6:efe1bc381434 | 543 | //printf("x = %f, y = %f,angle = %f,x_out=%lf, y_out=%lf, r_out=%lf\n\r",now_x,now_y,now_angle,x_out, y_out,r_out); |
yuki0701 | 6:efe1bc381434 | 544 | |
yuki0701 | 6:efe1bc381434 | 545 | CalMotorOut(x_out,y_out,r_out); |
yuki0701 | 6:efe1bc381434 | 546 | //printf("out1=%lf, out2=%lf, out3=%lf, out4=%lf\n",GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3)); |
yuki0701 | 6:efe1bc381434 | 547 | |
yuki0701 | 6:efe1bc381434 | 548 | base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),4095); |
yuki0701 | 6:efe1bc381434 | 549 | //printf("m1=%d, m2=%d, m3=%d, m4=%d\r\n",m_1,m_2,m_3,m_4); |
yuki0701 | 6:efe1bc381434 | 550 | |
yuki0701 | 7:48af3a9c5bdd | 551 | MotorControl(m_1,m_2,m_3,m_4); |
yuki0701 | 6:efe1bc381434 | 552 | debug_printf("m1=%d m2=%d m3=%d m4=%d x=%f y=%f angle=%f\n\r",m_1,m_2,m_3,m_4,now_x,now_y,now_angle); |
yuki0701 | 6:efe1bc381434 | 553 | |
yuki0701 | 6:efe1bc381434 | 554 | if(((x2_point - now_x)*(x2_point - x1_point) + (y2_point - now_y)*(y2_point - y1_point)) < 0)break; |
yuki0701 | 6:efe1bc381434 | 555 | } |
yuki0701 | 6:efe1bc381434 | 556 | } |
yuki0701 | 6:efe1bc381434 | 557 |