harurobo_mbed_undercarriage_sub

Committer:
yuki0701
Date:
Sat Dec 22 02:50:28 2018 +0000
Revision:
6:efe1bc381434
Parent:
4:69775231687c
a; ;

Who changed what in which revision?

UserRevisionLine numberNew contents of line
la00noix 0:591749f315ac 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 6:efe1bc381434 43
yuki0701 6:efe1bc381434 44
yuki0701 6:efe1bc381434 45
yuki0701 6:efe1bc381434 46 void UserLoopSetting2(){
yuki0701 6:efe1bc381434 47
yuki0701 6:efe1bc381434 48 gyro.initialize();
yuki0701 6:efe1bc381434 49 // motor_tick.attach(&calOmega,0.05); //0.05秒間隔で角速度を計算
yuki0701 6:efe1bc381434 50 EC1.setDiameter_mm(48);
yuki0701 6:efe1bc381434 51 EC2.setDiameter_mm(48); //測定輪半径//後で測定
yuki0701 6:efe1bc381434 52
yuki0701 6:efe1bc381434 53
yuki0701 6:efe1bc381434 54 }
yuki0701 6:efe1bc381434 55
la00noix 0:591749f315ac 56 //初期座標:A, 目標座標:B、機体位置:C、点Cから直線ABに下ろした垂線の足:H
yuki0701 4:69775231687c 57 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 58 //plot_x1,plot_y1:出発地点の座標
yuki0701 4:69775231687c 59 //plot_x2,plot_y2:目標地点の座標
yuki0701 4:69775231687c 60 //speed1:初期速度
yuki0701 4:69775231687c 61 //speed2:目標速度
la00noix 0:591749f315ac 62 {
la00noix 0:591749f315ac 63 double Vector_P[2] = {(plot_x2 - plot_x1), (plot_y2 - plot_y1)}; //ベクトルAB
la00noix 0:591749f315ac 64 double A_Vector_P = hypot(Vector_P[0], Vector_P[1]); //ベクトルABの大きさ(hypot(a,b)で√(a^2+b^2)を計算できる <math.h>))
la00noix 0:591749f315ac 65 double UnitVector_P[2] = {Vector_P[0]/A_Vector_P, Vector_P[1]/A_Vector_P}; //ベクトルABの単位ベクトル
la00noix 0:591749f315ac 66 double UnitVector_Q[2] = {UnitVector_P[1], -UnitVector_P[0]}; //ベクトルCHの単位ベクトル
la00noix 0:591749f315ac 67 double Vector_R[2] = {(now_x - plot_x1), (now_y - plot_y1)}; //ベクトルAC
la00noix 0:591749f315ac 68 double diff = UnitVector_P[0]*Vector_R[1] - UnitVector_P[1]*Vector_R[0]; //機体位置と直線ABの距離(外積を用いて計算)
la00noix 0:591749f315ac 69
yuki0701 4:69775231687c 70
yuki0701 4:69775231687c 71 //double VectorOut_P[2]= {0}; //ベクトルABに平行方向の出力をx軸方向、y軸方向の出力に分解*/
la00noix 0:591749f315ac 72
la00noix 0:591749f315ac 73 ///////////////////<XYRmotorout関数内>以下、ベクトルABに垂直な方向の誤差を埋めるPD制御(ベクトルABに垂直方向の出力を求め、x軸方向、y軸方向の出力に分解)//////////////////////
la00noix 0:591749f315ac 74
la00noix 0:591749f315ac 75 timer.start();
la00noix 0:591749f315ac 76 now_timeQ=timer.read();
la00noix 0:591749f315ac 77 out_dutyQ=Kvq_p*diff+Kvq_d*(diff-diff_old)/(now_timeQ-old_timeQ); //ベクトルABに垂直方向の出力を決定
la00noix 0:591749f315ac 78 diff_old=diff;
la00noix 0:591749f315ac 79
yuki0701 2:32362343f091 80 if(out_dutyQ>500)out_dutyQ=500;
yuki0701 2:32362343f091 81 if(out_dutyQ<-500)out_dutyQ=-500;
la00noix 0:591749f315ac 82
la00noix 0:591749f315ac 83 old_timeQ=now_timeQ;
la00noix 0:591749f315ac 84
la00noix 0:591749f315ac 85 double VectorOut_Q[2] = {out_dutyQ*UnitVector_Q[0], out_dutyQ*UnitVector_Q[1]}; //ベクトルABに垂直方向の出力をx軸方向、y軸方向の出力に分解
la00noix 0:591749f315ac 86
la00noix 0:591749f315ac 87 ///////////////////////////////<XYRmotorout関数内>以下、機体角度と目標角度の誤差を埋めるPD制御(旋回のための出力値を決定)//////////////////////////////////
la00noix 0:591749f315ac 88
la00noix 0:591749f315ac 89 now_timeR=timer.read();
la00noix 0:591749f315ac 90 diffangle=target_angle-now_angle;
yuki0701 1:d438093cb464 91 out_dutyR=-(Kvr_p*diffangle+Kvr_d*(diffangle-diffangle_old)/(now_timeR-old_timeR));
la00noix 0:591749f315ac 92 diffangle_old=diffangle;
la00noix 0:591749f315ac 93
yuki0701 1:d438093cb464 94 if(out_dutyR>r_out_max)out_dutyR=r_out_max;
yuki0701 1:d438093cb464 95 if(out_dutyR<-r_out_max)out_dutyR=-r_out_max;
la00noix 0:591749f315ac 96
la00noix 0:591749f315ac 97 old_timeR=now_timeR;
la00noix 0:591749f315ac 98
la00noix 0:591749f315ac 99 //////////////////////////<XYRmotorout関数内>以下、x軸方向、y軸方向、旋回の出力をそれぞれad_x_out,ad_y_out,ad_r_outの指すアドレスに書き込む/////////////////////////////
la00noix 0:591749f315ac 100 ////////////////////////////////////////////その際、x軸方向、y軸方向の出力はフィールドの座標系から機体の座標系に変換する。///////////////////////////////////////////////
yuki0701 4:69775231687c 101
yuki0701 4:69775231687c 102 diff_st = hypot(now_x-plot_x1,now_y-plot_y1); //出発座標と機体の位置の距離
yuki0701 4:69775231687c 103 diff_tgt = hypot(now_x - plot_x2, now_y - plot_y2); //機体の位置と目標座標の距離
yuki0701 4:69775231687c 104 diff_st_tgt = hypot(plot_x1-plot_x2,plot_y1-plot_y2); //出発座標と目標座標の距離
yuki0701 4:69775231687c 105
yuki0701 4:69775231687c 106 if(speed1 == speed2) { //等速移動
yuki0701 4:69775231687c 107
yuki0701 4:69775231687c 108 double VectorOut_P[2] = {speed1*UnitVector_P[0], speed1*UnitVector_P[1]};
yuki0701 4:69775231687c 109
yuki0701 4:69775231687c 110 *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 111 *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 112 *ad_r_out = out_dutyR;
la00noix 0:591749f315ac 113
yuki0701 4:69775231687c 114 } else if(speed2 == 0) { //減速移動(目標速度が0)→ベクトルABに垂直な方向の出力にもP制御をかける。
yuki0701 4:69775231687c 115
yuki0701 4:69775231687c 116 double VectorOut_P[2] = {speed1*UnitVector_P[0], speed1*UnitVector_P[1]};
yuki0701 4:69775231687c 117
yuki0701 4:69775231687c 118 if(diff_tgt > diff_st_tgt) {
yuki0701 4:69775231687c 119 diff_tgt = diff_st_tgt;
yuki0701 4:69775231687c 120 }
yuki0701 2:32362343f091 121
yuki0701 4:69775231687c 122 p_param=(diff_tgt/diff_st_tgt);
yuki0701 4:69775231687c 123
yuki0701 4:69775231687c 124 *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 125 *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 126 *ad_r_out = out_dutyR;
yuki0701 4:69775231687c 127
yuki0701 4:69775231687c 128 } else if(speed1 > speed2) { //減速移動(目標速度が0でない)
yuki0701 2:32362343f091 129
yuki0701 4:69775231687c 130 if(diff_tgt > diff_st_tgt) {
yuki0701 4:69775231687c 131 diff_tgt = diff_st_tgt;
yuki0701 4:69775231687c 132 }
yuki0701 4:69775231687c 133
yuki0701 4:69775231687c 134 p_param=(diff_tgt/diff_st_tgt);
yuki0701 4:69775231687c 135
yuki0701 4:69775231687c 136 double speed3 = speed2 + (speed1-speed2)*p_param;
yuki0701 4:69775231687c 137
yuki0701 4:69775231687c 138 double VectorOut_P[2] = {speed3*UnitVector_P[0], speed3*UnitVector_P[1]};
yuki0701 4:69775231687c 139
yuki0701 4:69775231687c 140 *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 141 *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 142 *ad_r_out = out_dutyR;
yuki0701 2:32362343f091 143
yuki0701 4:69775231687c 144 } else if(speed1 < speed2) { //加速移動(speed1)
yuki0701 4:69775231687c 145
yuki0701 4:69775231687c 146 if(diff_st > diff_st_tgt) {
yuki0701 4:69775231687c 147 diff_st = diff_st_tgt;
yuki0701 4:69775231687c 148 }
yuki0701 4:69775231687c 149
yuki0701 4:69775231687c 150 p_param=(diff_st/diff_st_tgt);
yuki0701 2:32362343f091 151
yuki0701 4:69775231687c 152 double speed4 = speed1 + (speed2-speed1)*p_param;
yuki0701 4:69775231687c 153
yuki0701 4:69775231687c 154 double VectorOut_P[2] = {speed4*UnitVector_P[0], speed4*UnitVector_P[1]};
yuki0701 4:69775231687c 155
yuki0701 4:69775231687c 156 *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 157 *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 158 *ad_r_out = out_dutyR;
yuki0701 2:32362343f091 159 }
la00noix 0:591749f315ac 160 }
la00noix 0:591749f315ac 161
la00noix 0:591749f315ac 162 ////////////////////////////////////////////////////////////<XYRmotorout関数は以上>////////////////////////////////////////////////////////////////
la00noix 0:591749f315ac 163
la00noix 0:591749f315ac 164
yuki0701 4:69775231687c 165 /*void set_p_out(double p) //ベクトルABに平行方向の出力値設定関数
la00noix 0:591749f315ac 166 {
la00noix 0:591749f315ac 167 p_out = p;
yuki0701 4:69775231687c 168 }*/
la00noix 0:591749f315ac 169
la00noix 0:591749f315ac 170 void q_setPDparam(double q_p,double q_d) //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数
la00noix 0:591749f315ac 171 {
la00noix 0:591749f315ac 172 Kvq_p=q_p;
la00noix 0:591749f315ac 173 Kvq_d=q_d;
la00noix 0:591749f315ac 174 }
la00noix 0:591749f315ac 175
la00noix 0:591749f315ac 176 void r_setPDparam(double r_p,double r_d) //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数
la00noix 0:591749f315ac 177 {
la00noix 0:591749f315ac 178 Kvr_p=r_p;
la00noix 0:591749f315ac 179 Kvr_d=r_d;
la00noix 0:591749f315ac 180 }
la00noix 0:591749f315ac 181
la00noix 0:591749f315ac 182 void set_r_out(double r) //旋回時の最大出力値設定関数
la00noix 0:591749f315ac 183 {
yuki0701 1:d438093cb464 184 r_out_max = r;
la00noix 0:591749f315ac 185 }
la00noix 0:591749f315ac 186
la00noix 0:591749f315ac 187 void set_target_angle(double t) //機体の目標角度設定関数
la00noix 0:591749f315ac 188 {
la00noix 0:591749f315ac 189 target_angle = t;
la00noix 0:591749f315ac 190 }
yuki0701 6:efe1bc381434 191
yuki0701 6:efe1bc381434 192
yuki0701 6:efe1bc381434 193 void UserLoopSetting(); // initialize setting
yuki0701 6:efe1bc381434 194 void DAC_Write(int16_t data, DigitalOut* DAC_cs);
yuki0701 6:efe1bc381434 195 void MotorControl(int16_t val_md1, int16_t val_md2, int16_t val_md3, int16_t val_md4);
yuki0701 6:efe1bc381434 196
yuki0701 6:efe1bc381434 197 void calOmega() //角速度計算関数
yuki0701 6:efe1bc381434 198 {
yuki0701 6:efe1bc381434 199 EC1.CalOmega();
yuki0701 6:efe1bc381434 200 EC2.CalOmega();
yuki0701 6:efe1bc381434 201 }
yuki0701 6:efe1bc381434 202
yuki0701 6:efe1bc381434 203 void output(double FL,double BL,double BR,double FR)
yuki0701 6:efe1bc381434 204 {
yuki0701 6:efe1bc381434 205 m1=FL;
yuki0701 6:efe1bc381434 206 m2=BL;
yuki0701 6:efe1bc381434 207 m3=BR;
yuki0701 6:efe1bc381434 208 m4=FR;
yuki0701 6:efe1bc381434 209 }
yuki0701 6:efe1bc381434 210
yuki0701 6:efe1bc381434 211 void base(double FL,double BL,double BR,double FR,double Max)
yuki0701 6:efe1bc381434 212 //いろんな加算をしても最大OR最小がMaxになるような補正//絶対値が一番でかいやつで除算
yuki0701 6:efe1bc381434 213 //DCモーターならMax=1、マクソンは-4095~4095だからMax=4095にする
yuki0701 6:efe1bc381434 214 {
yuki0701 6:efe1bc381434 215 if(fabs(FL)>=Max||fabs(BL)>=Max||fabs(BR)>=Max||fabs(FR)>=Max) {
yuki0701 6:efe1bc381434 216
yuki0701 6:efe1bc381434 217 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 218 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 219 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 220 else output(Max*FL/fabs(FR),Max*BL/fabs(FR),Max*BR/fabs(FR),Max*FR/fabs(FR));
yuki0701 6:efe1bc381434 221 } else {
yuki0701 6:efe1bc381434 222 output(FL,BL,BR,FR);
yuki0701 6:efe1bc381434 223 }
yuki0701 6:efe1bc381434 224 }
yuki0701 6:efe1bc381434 225
yuki0701 6:efe1bc381434 226 void calc_xy()
yuki0701 6:efe1bc381434 227 {
yuki0701 6:efe1bc381434 228 now_angle=gyro.getAngle(); //ジャイロの値読み込み
yuki0701 6:efe1bc381434 229
yuki0701 6:efe1bc381434 230 new_dist1=EC1.getDistance_mm();
yuki0701 6:efe1bc381434 231 new_dist2=EC2.getDistance_mm();
yuki0701 6:efe1bc381434 232 d_dist1=new_dist1-old_dist1;
yuki0701 6:efe1bc381434 233 d_dist2=new_dist2-old_dist2;
yuki0701 6:efe1bc381434 234 old_dist1=new_dist1;
yuki0701 6:efe1bc381434 235 old_dist2=new_dist2; //微小時間当たりのエンコーダ読み込み
yuki0701 6:efe1bc381434 236
yuki0701 6:efe1bc381434 237 d_x=d_dist2*sin(now_angle*PI/180)-d_dist1*cos(now_angle*PI/180);
yuki0701 6:efe1bc381434 238 d_y=d_dist2*cos(now_angle*PI/180)+d_dist1*sin(now_angle*PI/180); //微小時間毎の座標変化
yuki0701 6:efe1bc381434 239 now_x=now_x+d_x;
yuki0701 6:efe1bc381434 240 now_y=now_y-d_y; //微小時間毎に座標に加算
yuki0701 6:efe1bc381434 241 }
yuki0701 6:efe1bc381434 242
yuki0701 6:efe1bc381434 243 //ここからそれぞれのプログラム/////////////////////////////////////////////////////////////////////////////////////////////////////////////////
yuki0701 6:efe1bc381434 244 //now_x(現在のx座標),now_y(現在のy座標),now_angle(機体角度(ラジアンではない)(0~360や-180~180とは限らない))(反時計回りが正)
yuki0701 6:efe1bc381434 245 //ジャイロの出力は角度だが三角関数はラジアンとして計算する
yuki0701 6:efe1bc381434 246 //通常の移動+座標のずれ補正+機体の角度補正(+必要に応じさらに別補正)
yuki0701 6:efe1bc381434 247 //ジャイロの仕様上、角度補正をするときに計算式内で角度はそのままよりsinをとったほうがいいかもね
yuki0701 6:efe1bc381434 248
yuki0701 6:efe1bc381434 249 void purecurve2(int type, //正面を変えずに円弧or楕円を描いて曲がる
yuki0701 6:efe1bc381434 250 double point_x1,double point_y1,
yuki0701 6:efe1bc381434 251 double point_x2,double point_y2,
yuki0701 6:efe1bc381434 252 int theta,
yuki0701 6:efe1bc381434 253 double speed,
yuki0701 6:efe1bc381434 254 double q_p,double q_d,
yuki0701 6:efe1bc381434 255 double r_p,double r_d,
yuki0701 6:efe1bc381434 256 double r_out_max,
yuki0701 6:efe1bc381434 257 double target_angle)
yuki0701 6:efe1bc381434 258 //type:動きの種類(8パターン) point_x1,point_y1=出発地点の座標 point_x2,point_x2=目標地点の座標 theta=plotの間隔(0~90°) speed=速度
yuki0701 6:efe1bc381434 259 {
yuki0701 6:efe1bc381434 260 //-----PathFollowingのパラメーター設定-----//
yuki0701 6:efe1bc381434 261 q_setPDparam(q_p,q_d); //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数
yuki0701 6:efe1bc381434 262 r_setPDparam(r_p,r_d); //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数
yuki0701 6:efe1bc381434 263 set_r_out(r_out_max); //旋回時の最大出力値設定関数
yuki0701 6:efe1bc381434 264 set_target_angle(target_angle); //機体目標角度設定関数
yuki0701 6:efe1bc381434 265
yuki0701 6:efe1bc381434 266 int s;
yuki0701 6:efe1bc381434 267 int t = 0;
yuki0701 6:efe1bc381434 268 double X,Y;//X=楕円の中心座標、Y=楕円の中心座標
yuki0701 6:efe1bc381434 269 double a,b; //a=楕円のx軸方向の幅の半分,b=楕円のy軸方向の幅の半分
yuki0701 6:efe1bc381434 270 double plotx[(90/theta)+1]; //楕円にとるplotのx座標
yuki0701 6:efe1bc381434 271 double ploty[(90/theta)+1];
yuki0701 6:efe1bc381434 272
yuki0701 6:efe1bc381434 273 double x_out,y_out,r_out;
yuki0701 6:efe1bc381434 274
yuki0701 6:efe1bc381434 275 a=fabs(point_x1-point_x2);
yuki0701 6:efe1bc381434 276 b=fabs(point_y1-point_y2);
yuki0701 6:efe1bc381434 277
yuki0701 6:efe1bc381434 278 switch(type) {
yuki0701 6:efe1bc381434 279
yuki0701 6:efe1bc381434 280 case 1://→↑移動
yuki0701 6:efe1bc381434 281 X=point_x1;
yuki0701 6:efe1bc381434 282 Y=point_y2;
yuki0701 6:efe1bc381434 283
yuki0701 6:efe1bc381434 284 for(s=0; s<((90/theta)+1); s++) {
yuki0701 6:efe1bc381434 285 plotx[s] = X + a * cos(-PI/2 + s * (PI*theta/180));
yuki0701 6:efe1bc381434 286 ploty[s] = Y + b * sin(-PI/2 + s * (PI*theta/180));
yuki0701 6:efe1bc381434 287 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 6:efe1bc381434 288 }
yuki0701 6:efe1bc381434 289 break;
yuki0701 6:efe1bc381434 290
yuki0701 6:efe1bc381434 291 case 2://↑→移動
yuki0701 6:efe1bc381434 292 X=point_x2;
yuki0701 6:efe1bc381434 293 Y=point_y1;
yuki0701 6:efe1bc381434 294
yuki0701 6:efe1bc381434 295 for(s=0; s<((90/theta)+1); s++) {
yuki0701 6:efe1bc381434 296 plotx[s] = X + a * cos(PI - s * (PI*theta/180));
yuki0701 6:efe1bc381434 297 ploty[s] = Y + b * sin(PI - s * (PI*theta/180));
yuki0701 6:efe1bc381434 298 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 6:efe1bc381434 299 }
yuki0701 6:efe1bc381434 300 break;
yuki0701 6:efe1bc381434 301
yuki0701 6:efe1bc381434 302 case 3://↑←移動
yuki0701 6:efe1bc381434 303 X=point_x2;
yuki0701 6:efe1bc381434 304 Y=point_y1;
yuki0701 6:efe1bc381434 305
yuki0701 6:efe1bc381434 306 for(s=0; s<((90/theta)+1); s++) {
yuki0701 6:efe1bc381434 307 plotx[s] = X + a * cos(s * (PI*theta/180));
yuki0701 6:efe1bc381434 308 ploty[s] = Y + b * sin(s * (PI*theta/180));
yuki0701 6:efe1bc381434 309 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 6:efe1bc381434 310 }
yuki0701 6:efe1bc381434 311 break;
yuki0701 6:efe1bc381434 312
yuki0701 6:efe1bc381434 313 case 4://←↑移動
yuki0701 6:efe1bc381434 314 X=point_x1;
yuki0701 6:efe1bc381434 315 Y=point_y2;
yuki0701 6:efe1bc381434 316
yuki0701 6:efe1bc381434 317 for(s=0; s<((90/theta)+1); s++) {
yuki0701 6:efe1bc381434 318 plotx[s] = X + a * cos(-PI/2 - s * (PI*theta/180));
yuki0701 6:efe1bc381434 319 ploty[s] = Y + b * sin(-PI/2 - s * (PI*theta/180));
yuki0701 6:efe1bc381434 320 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 6:efe1bc381434 321 }
yuki0701 6:efe1bc381434 322 break;
yuki0701 6:efe1bc381434 323
yuki0701 6:efe1bc381434 324 case 5://←↓移動
yuki0701 6:efe1bc381434 325 X=point_x1;
yuki0701 6:efe1bc381434 326 Y=point_y2;
yuki0701 6:efe1bc381434 327
yuki0701 6:efe1bc381434 328 for(s=0; s<((90/theta)+1); s++) {
yuki0701 6:efe1bc381434 329 plotx[s] = X + a * cos(PI/2 + s * (PI*theta/180));
yuki0701 6:efe1bc381434 330 ploty[s] = Y + b * sin(PI/2 + s * (PI*theta/180));
yuki0701 6:efe1bc381434 331 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 6:efe1bc381434 332 }
yuki0701 6:efe1bc381434 333 break;
yuki0701 6:efe1bc381434 334
yuki0701 6:efe1bc381434 335 case 6://↓←移動
yuki0701 6:efe1bc381434 336 X=point_x2;
yuki0701 6:efe1bc381434 337 Y=point_y1;
yuki0701 6:efe1bc381434 338
yuki0701 6:efe1bc381434 339 for(s=0; s<((90/theta)+1); s++) {
yuki0701 6:efe1bc381434 340 plotx[s] = X + a * cos(-s * (PI*theta/180));
yuki0701 6:efe1bc381434 341 ploty[s] = Y + b * sin(-s * (PI*theta/180));
yuki0701 6:efe1bc381434 342 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 6:efe1bc381434 343 }
yuki0701 6:efe1bc381434 344 break;
yuki0701 6:efe1bc381434 345
yuki0701 6:efe1bc381434 346 case 7://↓→移動
yuki0701 6:efe1bc381434 347 X=point_x2;
yuki0701 6:efe1bc381434 348 Y=point_y1;
yuki0701 6:efe1bc381434 349
yuki0701 6:efe1bc381434 350 for(s=0; s<((90/theta)+1); s++) {
yuki0701 6:efe1bc381434 351 plotx[s] = X + a * cos(PI + s * (PI*theta/180));
yuki0701 6:efe1bc381434 352 ploty[s] = Y + b * sin(PI + s * (PI*theta/180));
yuki0701 6:efe1bc381434 353 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 6:efe1bc381434 354 }
yuki0701 6:efe1bc381434 355 break;
yuki0701 6:efe1bc381434 356
yuki0701 6:efe1bc381434 357 case 8://→↓移動
yuki0701 6:efe1bc381434 358 X=point_x1;
yuki0701 6:efe1bc381434 359 Y=point_y2;
yuki0701 6:efe1bc381434 360
yuki0701 6:efe1bc381434 361 for(s=0; s<((90/theta)+1); s++) {
yuki0701 6:efe1bc381434 362 plotx[s] = X + a * cos(PI/2 - s * (PI*theta/180));
yuki0701 6:efe1bc381434 363 ploty[s] = Y + b * sin(PI/2 - s * (PI*theta/180));
yuki0701 6:efe1bc381434 364 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 6:efe1bc381434 365 }
yuki0701 6:efe1bc381434 366 break;
yuki0701 6:efe1bc381434 367 }
yuki0701 6:efe1bc381434 368
yuki0701 6:efe1bc381434 369 while(1) {
yuki0701 6:efe1bc381434 370
yuki0701 6:efe1bc381434 371 calc_xy();
yuki0701 6:efe1bc381434 372
yuki0701 6:efe1bc381434 373 XYRmotorout(plotx[t],ploty[t],plotx[t+1],ploty[t+1],&x_out,&y_out,&r_out,speed,speed);
yuki0701 6:efe1bc381434 374 CalMotorOut(x_out,y_out,r_out);
yuki0701 6:efe1bc381434 375 //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 376
yuki0701 6:efe1bc381434 377 base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),4095); //m1~m4に代入
yuki0701 6:efe1bc381434 378 //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 379
yuki0701 6:efe1bc381434 380 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 381
yuki0701 6:efe1bc381434 382 MotorControl(m_1,m_2,m_3,m_4); //出力
yuki0701 6:efe1bc381434 383 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 384
yuki0701 6:efe1bc381434 385 if(t == (90/theta))break;
yuki0701 6:efe1bc381434 386 }
yuki0701 6:efe1bc381434 387 }
yuki0701 6:efe1bc381434 388
yuki0701 6:efe1bc381434 389
yuki0701 6:efe1bc381434 390 void gogo_straight(double x1_point,double y1_point, //直線運動プログラム
yuki0701 6:efe1bc381434 391 double x2_point,double y2_point,
yuki0701 6:efe1bc381434 392 double speed1,double speed2,
yuki0701 6:efe1bc381434 393 double q_p,double q_d,
yuki0701 6:efe1bc381434 394 double r_p,double r_d,
yuki0701 6:efe1bc381434 395 double r_out_max,
yuki0701 6:efe1bc381434 396 double target_angle)
yuki0701 6:efe1bc381434 397 //引数:出発地点の座標(x,y)、目標地点の座標(x,y)、初速度(speed1)、目標速度(speed2)//speed1=speed2 のとき等速運動
yuki0701 6:efe1bc381434 398 {
yuki0701 6:efe1bc381434 399 //-----PathFollowingのパラメーター設定-----//
yuki0701 6:efe1bc381434 400 q_setPDparam(q_p,q_d); //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数
yuki0701 6:efe1bc381434 401 r_setPDparam(r_p,r_d); //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数
yuki0701 6:efe1bc381434 402 set_r_out(r_out_max); //旋回時の最大出力値設定関数
yuki0701 6:efe1bc381434 403 set_target_angle(target_angle); //機体目標角度設定関数
yuki0701 6:efe1bc381434 404
yuki0701 6:efe1bc381434 405 while (1) {
yuki0701 6:efe1bc381434 406
yuki0701 6:efe1bc381434 407 calc_xy();
yuki0701 6:efe1bc381434 408
yuki0701 6:efe1bc381434 409 XYRmotorout(x1_point,y1_point,x2_point,y2_point,&x_out,&y_out,&r_out,speed1,speed2);
yuki0701 6:efe1bc381434 410 //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 411
yuki0701 6:efe1bc381434 412 CalMotorOut(x_out,y_out,r_out);
yuki0701 6:efe1bc381434 413 //printf("out1=%lf, out2=%lf, out3=%lf, out4=%lf\n",GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3));
yuki0701 6:efe1bc381434 414
yuki0701 6:efe1bc381434 415 base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),4095);
yuki0701 6:efe1bc381434 416 //printf("m1=%d, m2=%d, m3=%d, m4=%d\r\n",m_1,m_2,m_3,m_4);
yuki0701 6:efe1bc381434 417
yuki0701 6:efe1bc381434 418 MotorControl(m1,m2,m3,m4);
yuki0701 6:efe1bc381434 419 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 420
yuki0701 6:efe1bc381434 421 if(((x2_point - now_x)*(x2_point - x1_point) + (y2_point - now_y)*(y2_point - y1_point)) < 0)break;
yuki0701 6:efe1bc381434 422 }
yuki0701 6:efe1bc381434 423 }
yuki0701 6:efe1bc381434 424