あ
Dependencies: uw_28015 mbed move4wheel2 EC CruizCore_R6093U CruizCore_R1370P
movement/movement.cpp
- Committer:
- yuki0701
- Date:
- 2019-11-16
- Revision:
- 1:26fc1b2f1c42
- Parent:
- 0:b87fd8dd4322
- Child:
- 2:820dcd23c8e3
File content as of revision 1:26fc1b2f1c42:
#include "EC.h" #include "R1370P.h" #include "move4wheel.h" #include "mbed.h" #include "math.h" #include "PathFollowing.h" #include "movement.h" #include "manual.h" #include "can.h" #include "R6093U.h" #define PI 3.141592 char can_ashileddata[2]= {0}; char can_ashileddata2[8]= {0}; //char can_ashileddata3[2]= {0}; //char can_ashileddata4[2]= {0}; //char can_ashileddata5[2]= {0}; int can_ashileddata0_0,can_ashileddata0_1,can_ashileddata0_2,can_ashileddata0_3; Ec EC2(p16,p15,NC,2048,0.05); Ec EC1(p18,p17,NC,500,0.05); Ticker ec_ticker; //ec角速度計算用ticker //R1370P gyro(p9,p10); R6093U gyro(p9,p10); double new_dist1=0,new_dist2=0; double old_dist1=0,old_dist2=0; double d_dist1=0,d_dist2=0; //座標計算用関数 double d_x,d_y; //現在地X,y座標、現在角度については、PathFollowingでnow_x,now_y,now_angleを定義済 double start_x=0,start_y=0; //スタート位置 double x_out,y_out,r_out; //出力値 int16_t m1=0, m2=0, m3=0, m4=0; //int16bit = int2byte double xy_type,pm_typeX,pm_typeY,x_base,y_base; int flag; int RL_mode; ///////////////////機体情報をメンバとする構造体"robo_data"と構造体型変数info(←この変数に各センサーにより求めた機体情報(機体位置/機体角度)を格納する)の宣言///////////////// /*「info.(機体情報の種類).(使用センサーの種類)」に各情報を格納する *状況に応じて、どのセンサーにより算出した情報を信用するかを選択し、その都度now_angle,now_x,now_yに代入する。(何種類かのセンサーの情報を混ぜて使用することも可能) *(ex) *info.nowX.enc → エンコーダにより算出した機体位置のx座標 *info.nowY.usw → 超音波センサーにより求めた機体位置のy座標 */ typedef struct { //使用センサーの種類 double usw; //超音波センサー double enc; //エンコーダ double gyro; //ジャイロ //double line;//ラインセンサー } robo_sensor; typedef struct { //機体情報の種類 robo_sensor angle; //←機体角度は超音波センサーやラインセンサーからも算出可能なので一応格納先を用意したが、ジャイロの値を完全に信用してもいいかも robo_sensor nowX; robo_sensor nowY; } robo_data; robo_data info= {{0,0,0},{0,0,0},{0,0,0}}; //全てのデータを0に初期化 //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// void UserLoopSetting_sensor() { gyro.initialize(); ec_ticker.attach(&calOmega,0.05); //0.05秒間隔で角速度を計算 EC1.setDiameter_mm(70); EC2.setDiameter_mm(70); //測定輪半径//後で測定 info.nowX.enc = 0; //初期位置の設定 info.nowY.enc = 0; } void UserLoopSetting_enc_right() { info.nowX.enc = 3112; //エンコーダの初期位置の設定(右側フィールド) info.nowY.enc = 3500; RL_mode = 0; } void UserLoopSetting_enc_left() { info.nowX.enc = -3112; //エンコーダの初期位置の設定(左側フィールド) info.nowY.enc = 3500; RL_mode = 1; } void calOmega() //角速度計算関数 { EC1.CalOmega(); EC2.CalOmega(); } void output(double FL,double BL,double BR,double FR) { m1=FL; m2=BL; m3=BR; m4=FR; } void base(double FL,double BL,double BR,double FR,double Max) //いろんな加算をしても最大OR最小がMaxになるような補正//絶対値が一番でかいやつで除算 //DCモーターならMax=1、マクソンは-4095~4095だからMax=4095にする { if(fabs(FL)>=Max||fabs(BL)>=Max||fabs(BR)>=Max||fabs(FR)>=Max) { if (fabs(FL)>=fabs(BL)&&fabs(FL)>=fabs(BR)&&fabs(FL)>=fabs(FR))output(Max*FL/fabs(FL),Max*BL/fabs(FL),Max*BR/fabs(FL),Max*FR/fabs(FL)); else if(fabs(BL)>=fabs(FL)&&fabs(BL)>=fabs(BR)&&fabs(BL)>=fabs(FR))output(Max*FL/fabs(BL),Max*BL/fabs(BL),Max*BR/fabs(BL),Max*FR/fabs(BL)); else if(fabs(BR)>=fabs(FL)&&fabs(BR)>=fabs(BL)&&fabs(BR)>=fabs(FR))output(Max*FL/fabs(BR),Max*BL/fabs(BR),Max*BR/fabs(BR),Max*FR/fabs(BR)); else output(Max*FL/fabs(FR),Max*BL/fabs(FR),Max*BR/fabs(FR),Max*FR/fabs(FR)); } else { output(FL,BL,BR,FR); } } void ashi_led() { if(now_angle > -1 && now_angle < 1) { can_ashileddata0_0 = 1; } else { can_ashileddata0_0 = 0; } if(now_angle > 350) { can_ashileddata0_1 = 1; } else { can_ashileddata0_1 = 0; } if(RL_mode == 0) { if(now_x > 3110 && now_x < 3114) { can_ashileddata0_2 = 1; } else { can_ashileddata0_2 = 0; } if(now_y > 3498 && now_y < 3502) { can_ashileddata0_3 = 1; } else { can_ashileddata0_3 = 0; } } else if(RL_mode == 1) { if(now_x > -3114 && now_x < -3110) { can_ashileddata0_2 = 1; } else { can_ashileddata0_2 = 0; } if(now_y > 3498 && now_y < 3502) { can_ashileddata0_3 = 1; } else { can_ashileddata0_3 = 0; } } can_ashileddata[0] = (can_ashileddata0_0<<7 | can_ashileddata0_1<<6 | can_ashileddata0_2<<5 | can_ashileddata0_3<<4); } void calc_gyro() { //now_angle=gyro.getAngle(); //ジャイロの値読み込み now_angle = -gyro.getZ_Angle(); } void print_gyro() { while(1) { //printf("now_gyro = %f\n\r",-gyro.getAngle()); } } void calc_xy_enc() //エンコーダ&ジャイロによる座標計算 { //now_angle=gyro.getAngle(); //ジャイロの値読み込み now_angle = -gyro.getZ_Angle(); new_dist1=EC1.getDistance_mm(); new_dist2=EC2.getDistance_mm(); d_dist1=new_dist1-old_dist1; d_dist2=new_dist2-old_dist2; old_dist1=new_dist1; old_dist2=new_dist2; //微小時間当たりのエンコーダ読み込み d_x=d_dist2*sin(now_angle*PI/180)-d_dist1*cos(now_angle*PI/180); d_y=d_dist2*cos(now_angle*PI/180)+d_dist1*sin(now_angle*PI/180); //微小時間毎の座標変化 info.nowX.enc = info.nowX.enc + d_x; info.nowY.enc = info.nowY.enc - d_y; //微小時間毎に座標に加算 } void set_cond(int t, int px, double bx, int py, double by) //超音波センサーを使用するときの条件設定関数 { //引数の詳細は関数"calc_xy_usw"参照 xy_type = t; pm_typeX = px; x_base = bx; pm_typeY = py; y_base = by; } void calc_xy_usw(double tgt_angle) //超音波センサーによる座標計算(機体が旋回する場合はこの方法による座標計算は出来ない) { //tgt_angle:機体の目標角度(運動初期角度と同じ/今大会では0,90,180のみ) //xy_type:(0:Y軸平行の壁を読む/1:X軸平行の壁を読む/2:X,Y軸平行の壁を共に読む) //pm_typeX,pm_typeY:(0:各軸正方向側の壁を読む/1:各軸負方向側の壁を読む) //x_base,y_base:超音波センサーで読む壁の座標(y軸並行の壁のx座標/x軸平行の壁のy座標) double R1=240,R2=240,R3=240,R4=240; //機体の中心から各超音波センサーが付いている面までの距離 double D1=30,D2=0,D3=0,D4=0; //各超音波センサーが付いている面の中心から各超音波センサーまでの距離(時計回りを正とする) // now_angle=gyro.getAngle(); //ジャイロの値読み込み now_angle = -gyro.getZ_Angle(); if(tgt_angle==0) { if((xy_type==0 || xy_type==2) && pm_typeX==0) { info.nowX.usw = x_base - (usw_data4 + R4*cos(now_angle*PI/180) + D4*sin(now_angle*PI/180)); } else if((xy_type==0 || xy_type==2) && pm_typeX==1) { info.nowX.usw = x_base + (usw_data3 + R3*cos(now_angle*PI/180) + D3*sin(now_angle*PI/180)); } if((xy_type==1 || xy_type==2) && pm_typeY==0) { info.nowY.usw = y_base - (usw_data2 + R2*cos(now_angle*PI/180) + D2*sin(now_angle*PI/180)); } else if((xy_type==1 || xy_type==2) && pm_typeY==1) { info.nowY.usw = y_base + (usw_data1 + R1*cos(now_angle*PI/180) + D1*sin(now_angle*PI/180)); } } else if(tgt_angle==90) { if((xy_type==0 || xy_type==2) && pm_typeX==0) { info.nowX.usw = x_base - (usw_data1 + R1*cos((now_angle-tgt_angle)*PI/180) + D1*sin(now_angle*PI/180)); } else if((xy_type==0 || xy_type==2) && pm_typeX==1) { info.nowX.usw = x_base + (usw_data2 + R2*cos((now_angle-tgt_angle)*PI/180) + D2*sin(now_angle*PI/180)); } if((xy_type==1 || xy_type==2) && pm_typeY==0) { info.nowY.usw = y_base - (usw_data4 + R4*cos((now_angle-tgt_angle)*PI/180) + D4*sin(now_angle*PI/180)); } else if((xy_type==1 || xy_type==2) && pm_typeY==1) { info.nowY.usw = y_base + (usw_data3 + R3*cos((now_angle-tgt_angle)*PI/180) + D3*sin(now_angle*PI/180)); } } else if(tgt_angle==180 || tgt_angle==-180) { if((xy_type==0 || xy_type==2) && pm_typeX==0) { info.nowX.usw = x_base - (usw_data3 + R3*cos((now_angle-tgt_angle)*PI/180) + D3*sin(now_angle*PI/180)); } else if((xy_type==0 || xy_type==2) && pm_typeX==1) { info.nowX.usw = x_base + (usw_data4 + R4*cos((now_angle-tgt_angle)*PI/180) + D4*sin(now_angle*PI/180)); } if((xy_type==1 || xy_type==2) && pm_typeY==0) { info.nowY.usw = y_base - (usw_data1+ R1*cos((now_angle-tgt_angle)*PI/180) + D1*sin(now_angle*PI/180)); } else if((xy_type==1 || xy_type==2) && pm_typeY==1) { info.nowY.usw = y_base + (usw_data2 + R2*cos((now_angle-tgt_angle)*PI/180) + D2*sin(now_angle*PI/180)); } } else if(tgt_angle==-90) { if((xy_type==0 || xy_type==2) && pm_typeX==0) { info.nowX.usw = x_base - (usw_data2 + R2*cos((now_angle-tgt_angle)*PI/180) + D2*sin(now_angle*PI/180)); } else if((xy_type==0 || xy_type==2) && pm_typeX==1) { info.nowX.usw = x_base + (usw_data1 + R1*cos((now_angle-tgt_angle)*PI/180) + D1*sin(now_angle*PI/180)); } if((xy_type==1 || xy_type==2) && pm_typeY==0) { info.nowY.usw = y_base - (usw_data3 + R3*cos((now_angle-tgt_angle)*PI/180) + D3*sin(now_angle*PI/180)); } else if((xy_type==1 || xy_type==2) && pm_typeY==1) { info.nowY.usw = y_base + (usw_data4 + R4*cos((now_angle-tgt_angle)*PI/180) + D4*sin(now_angle*PI/180)); } } } void calc_xy(double target_angle, double u,double v) { //エンコーダにより求めた機体の座標と超音波センサーにより求めた機体の座標を(エンコーダ : 超音波 = u : 1-u / v : 1-v)の割合で混ぜて now_x,now_y に代入する calc_xy_enc(); if(u != 1 || v != 1) { calc_xy_usw(target_angle); //エンコーダの値しか使用しない場合は超音波センサーによる座標計算は行わずに計算量を減らす。 } now_x = u * info.nowX.enc + (1-u) * info.nowX.usw; now_y = v * info.nowY.enc + (1-v) * info.nowY.usw; /*if(now_x >-1 && now_x <1 && now_y >-1 && now_y <1){ //スタート時の0合わせ用 ec_led = 1; }else{ ec_led = 0; } if(now_angle >-0.5 && now_angle <0.5){ gyro_led = 1; }else{ gyro_led = 0; }*/ } void enc_correction(int x_select,int y_select) //エンコーダの座標を超音波センサの座標で上書き { //x_select,y_select → (0:上書きしない/1:上書きする) if(x_select == 1) { info.nowX.enc = info.nowX.usw; } if(y_select == 1) { info.nowY.enc = info.nowY.usw; } } //ここからそれぞれのプログラム///////////////////////////////////////////////////////////////////////////////////////////////////////////////// //now_x(現在のx座標),now_y(現在のy座標),now_angle(機体角度(ラジアンではない)(0~360や-180~180とは限らない))(反時計回りが正) //ジャイロの出力は角度だが三角関数はラジアンとして計算する //通常の移動+座標のずれ補正+機体の角度補正(+必要に応じさらに別補正) //ジャイロの仕様上、角度補正をするときに計算式内で角度はそのままよりsinをとったほうがいいかもね void purecurve(int type,double u,double v, //正面を変えずに円弧or楕円を描いて曲がる double point_x1,double point_y1, double point_x2,double point_y2, int theta, double speed, double q_p,double q_d, double r_p,double r_d, double r_out_max, double target_angle) //type:動きの種類(8パターン) point_x1,point_y1=出発地点の座標 point_x2,point_x2=目標地点の座標 theta=plotの間隔(0~90°) speed=速度 { //-----PathFollowingのパラメーター設定-----// q_setPDparam(q_p,q_d); //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数 r_setPDparam(r_p,r_d); //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数 set_r_out(r_out_max); //旋回時の最大出力値設定関数 set_target_angle(target_angle); //機体目標角度設定関数 int s; int t = 0; double X,Y;//X=楕円の中心座標、Y=楕円の中心座標 double a,b; //a=楕円のx軸方向の幅の半分,b=楕円のy軸方向の幅の半分 double plotx[(90/theta)+1]; //楕円にとるplotのx座標 double ploty[(90/theta)+1]; double x_out,y_out,r_out; a=fabs(point_x1-point_x2); b=fabs(point_y1-point_y2); switch(type) { case 1://→↑移動 X=point_x1; Y=point_y2; for(s=0; s<((90/theta)+1); s++) { plotx[s] = X + a * cos(-PI/2 + s * (PI*theta/180)); ploty[s] = Y + b * sin(-PI/2 + s * (PI*theta/180)); //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); } break; case 2://↑→移動 X=point_x2; Y=point_y1; for(s=0; s<((90/theta)+1); s++) { plotx[s] = X + a * cos(PI - s * (PI*theta/180)); ploty[s] = Y + b * sin(PI - s * (PI*theta/180)); //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); } break; case 3://↑←移動 X=point_x2; Y=point_y1; for(s=0; s<((90/theta)+1); s++) { plotx[s] = X + a * cos(s * (PI*theta/180)); ploty[s] = Y + b * sin(s * (PI*theta/180)); //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); } break; case 4://←↑移動 X=point_x1; Y=point_y2; for(s=0; s<((90/theta)+1); s++) { plotx[s] = X + a * cos(-PI/2 - s * (PI*theta/180)); ploty[s] = Y + b * sin(-PI/2 - s * (PI*theta/180)); //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); } break; case 5://←↓移動 X=point_x1; Y=point_y2; for(s=0; s<((90/theta)+1); s++) { plotx[s] = X + a * cos(PI/2 + s * (PI*theta/180)); ploty[s] = Y + b * sin(PI/2 + s * (PI*theta/180)); //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); } break; case 6://↓←移動 X=point_x2; Y=point_y1; for(s=0; s<((90/theta)+1); s++) { plotx[s] = X + a * cos(-s * (PI*theta/180)); ploty[s] = Y + b * sin(-s * (PI*theta/180)); //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); } break; case 7://↓→移動 X=point_x2; Y=point_y1; for(s=0; s<((90/theta)+1); s++) { plotx[s] = X + a * cos(PI + s * (PI*theta/180)); ploty[s] = Y + b * sin(PI + s * (PI*theta/180)); //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); } break; case 8://→↓移動 X=point_x1; Y=point_y2; for(s=0; s<((90/theta)+1); s++) { plotx[s] = X + a * cos(PI/2 - s * (PI*theta/180)); ploty[s] = Y + b * sin(PI/2 - s * (PI*theta/180)); //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]); } break; } while(1) { if(id1_value[0] != 1)break; if(id1_value[6] != flag)break; calc_xy(target_angle,u,v); XYRmotorout(plotx[t],ploty[t],plotx[t+1],ploty[t+1],&x_out,&y_out,&r_out,speed,speed); CalMotorOut(x_out,y_out,r_out); //debug_printf("t=%d now_x=%f now_y=%f x_out=%f y_out=%f\n\r",t,now_x,now_y,x_out,y_out); base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),4095); //m1~m4に代入 //debug_printf("t=%d (0)=%f (1)=%f (2)=%f (3)=%f\n\r",t,GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3)); if(((plotx[t+1] - now_x)*(plotx[t+1] - plotx[t]) + (ploty[t+1] - now_y)*(ploty[t+1] - ploty[t])) < 0)t++; // MaxonControl(m1,m2,m3,m4); //出力 // debug_printf("t=%d m1=%d m2=%d m3=%d m4=%d x=%f y=%f angle=%f\n\r",t,m1,m2,m3,m4,now_x,now_y,now_angle); if(t == (90/theta))break; } } void gogo_straight(double u,double v, //直線運動プログラム double x1_point,double y1_point, double x2_point,double y2_point, double speed1,double speed2, double q_p,double q_d, double r_p,double r_d, double r_out_max, double target_angle) //引数:出発地点の座標(x,y)、目標地点の座標(x,y)、初速度(speed1)、目標速度(speed2)//speed1=speed2 のとき等速運動 { //-----PathFollowingのパラメーター設定-----// q_setPDparam(q_p,q_d); //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数 r_setPDparam(r_p,r_d); //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数 set_r_out(r_out_max); //旋回時の最大出力値設定関数 set_target_angle(target_angle); //機体目標角度設定関数 while (1) { if(id1_value[0] != 1)break; if(id1_value[6] != flag)break; calc_xy(target_angle,u,v); XYRmotorout(x1_point,y1_point,x2_point,y2_point,&x_out,&y_out,&r_out,speed1,speed2); //printf("n_x = %f, n_y = %f,n_angle = %f, t_x = %f, t_y = %f, t_angle = %f, x_out=%lf, y_out=%lf, r_out=%lf\n\r",now_x,now_y,now_angle,x2_point,y2_point,target_angle,x_out, y_out,r_out); CalMotorOut(x_out,y_out,r_out); //printf("out1=%lf, out2=%lf, out3=%lf, out4=%lf\n",GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3)); base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),4095); //printf("m1=%d, m2=%d, m3=%d, m4=%d\r\n",m_1,m_2,m_3,m_4); // MaxonControl(m1,m2,m3,m4); // debug_printf("m1=%d m2=%d m3=%d m4=%d x=%f y=%f angle=%f\n\r",m1,m2,m3,m4,now_x,now_y,now_angle); printf("m1=%d m2=%d m3=%d m4=%d x=%f y=%f angle=%f\n\r",m1,m2,m3,m4,now_x,now_y,now_angle); if(((x2_point - now_x)*(x2_point - x1_point) + (y2_point - now_y)*(y2_point - y1_point)) < 0)break; } } /*void pos_correction(double tgt_x, double tgt_y, double tgt_angle, double u, double v) //位置補正(使用前にMaxonControl(0,0,0,0)を入れる) { double r, R=10; // r:一回補正が入るごとの機体の位置と目標位置の距離(ズレ) R:補正終了とみなす目標位置からの機体の位置のズレ double out; calc_xy(tgt_angle, u, v); while(1) { //機体の位置を目標領域(目標座標+許容誤差)に収める gogo_straight(u,v,now_x,now_y,tgt_x,tgt_y,200,50,5,0.1,10,0.1,500,tgt_angle); MaxonControl(0,0,0,0); calc_xy(tgt_angle, u, v); r=hypot(now_x - tgt_x, now_y - tgt_y); if(r < R) break; if(id1_value[0] != 1)break; } while(1) { calc_gyro(); out = 10 * (tgt_angle - now_angle); if(out > 300) { //0~179°のときは時計回りに回転 MaxonControl(300,300,300,300); } else if(out < -300) { MaxonControl(-300,-300,-300,-300); } else if(out <= 300 && out > -300) { MaxonControl(out,out,out,out); } if(tgt_angle - 0.5 < now_angle && now_angle < tgt_angle + 0.5) break; //目標角度からの許容誤差内に機体の角度が収まった時、補正終了 if(id1_value[0] != 1)break; } MaxonControl(0,0,0,0); }*/ void pos_correction(double tgt_x, double tgt_y, double tgt_angle, double u, double v) //改良版 位置補正(使用前にMaxonControl(0,0,0,0)を入れる) { //距離に比例させて補正初速度を増加させる。(最大速度を設定しそれ以上は出ないようにする) double first_speed, first_speed50 = 10, last_speed = 10, Max_speed = 500; double r, R=10; // r:一回補正が入るごとの機体の位置と目標位置の距離(ズレ) R:補正終了とみなす目標位置からの機体の位置のズレ double out; calc_xy(tgt_angle, u, v); //r = hypot(now_x - tgt_x, now_y - tgt_y); while(1) { //機体の位置を目標領域(目標座標+許容誤差)に収める //printf("col\n\n\n"); if(id1_value[0] != 1)break; if(id1_value[6] != flag)break; //first_speed = first_speed50 * r / 50; /*if(first_speed > Max_speed){ gogo_straight(u,v,now_x,now_y,tgt_x,tgt_y,Max_speed,Max_speed,5,0.1,10,0.1,500,tgt_angle); }else{ gogo_straight(u,v,now_x,now_y,tgt_x,tgt_y,first_speed,last_speed,5,0.1,10,0.1,500,tgt_angle); }*/ //gogo_straight(u,v,now_x,now_y,tgt_x,tgt_y,first_speed50,last_speed,5,0.1,10,0.1,500,tgt_angle); gogo_straight(u,v,now_x,now_y,tgt_x,tgt_y,10,10,5,0.1,10,0.1,50,tgt_angle); //gogo_straight(1,1,0,0,200,0,50,500,5,0.1,10,0.1,50,0); //gogo_straight(u,v,now_x,now_y,0,100,first_speed50,last_speed,5,0.1,10,0.1,500,tgt_angle); // MaxonControl(0,0,0,0); m1 = 0; m2 = 0; m3 = 0; m4 = 0; calc_xy(tgt_angle, u, v); r=hypot(now_x - tgt_x, now_y - tgt_y); if(r < R) break; } while(1) { if(id1_value[0] != 1)break; if(id1_value[6] != flag)break; //calc_gyro(); // now_angle=gyro.getAngle(); now_angle = -gyro.getZ_Angle(); printf("angle = %f\n\r",now_angle); out = 10 * (tgt_angle - now_angle); if(out > 300) { //0~179°のときは時計回りに回転 // MaxonControl(-300,-300,-300,-300); m1 = -300; m2 = -300; m3 = -300; m4 = -300; } else if(out < -300) { // MaxonControl(300,300,300,300); m1 = 300; m2 = 300; m3 = 300; m4 = 300; } else if(out <= 300 && out > -300) { // MaxonControl(-out,-out,-out,-out); m1 = -out; m2 = -out; m3 = -out; m4 = -out; } if(tgt_angle - 1 < now_angle && now_angle < tgt_angle + 1) break; //目標角度からの許容誤差内に機体の角度が収まった時、補正終了 } // MaxonControl(0,0,0,0); m1 = 0; m2 = 0; m3 = 0; m4 = 0; } void mt_stop() { m1 = 0; m2 = 0; m3 = 0; m4 = 0; printf("motor stop\n\r"); }