2月25日

Dependencies:   uw_28015 mbed ros_lib_kinetic move4wheel2 EC CruizCore_R6093U CruizCore_R1370P

Committer:
yuki0701
Date:
Tue Feb 25 01:20:43 2020 +0000
Revision:
0:44f9a43e4ab2
a;

Who changed what in which revision?

UserRevisionLine numberNew contents of line
yuki0701 0:44f9a43e4ab2 1 #ifndef HARUROBO2019_MOVEMENT
yuki0701 0:44f9a43e4ab2 2 #define HARUROBO2019_MOVEMENT
yuki0701 0:44f9a43e4ab2 3
yuki0701 0:44f9a43e4ab2 4 extern char can_ashileddata[2];
yuki0701 0:44f9a43e4ab2 5 extern char can_ashileddata2[8];
yuki0701 0:44f9a43e4ab2 6 extern char can_num[1];
yuki0701 0:44f9a43e4ab2 7 extern double info_x, info_y, info_r;
yuki0701 0:44f9a43e4ab2 8 //extern char can_ashileddata3[2];
yuki0701 0:44f9a43e4ab2 9 //extern char can_ashileddata4[2];
yuki0701 0:44f9a43e4ab2 10 //extern char can_ashileddata5[2];
yuki0701 0:44f9a43e4ab2 11
yuki0701 0:44f9a43e4ab2 12 void print_gyro();
yuki0701 0:44f9a43e4ab2 13
yuki0701 0:44f9a43e4ab2 14 extern int16_t m1,m2,m3,m4;
yuki0701 0:44f9a43e4ab2 15
yuki0701 0:44f9a43e4ab2 16 extern int flag;
yuki0701 0:44f9a43e4ab2 17
yuki0701 0:44f9a43e4ab2 18 void UserLoopSetting_sensor();
yuki0701 0:44f9a43e4ab2 19
yuki0701 0:44f9a43e4ab2 20 void UserLoopSetting_enc_right();
yuki0701 0:44f9a43e4ab2 21
yuki0701 0:44f9a43e4ab2 22 void UserLoopSetting_enc_left();
yuki0701 0:44f9a43e4ab2 23
yuki0701 0:44f9a43e4ab2 24 void calOmega();
yuki0701 0:44f9a43e4ab2 25
yuki0701 0:44f9a43e4ab2 26 void cal_uw();
yuki0701 0:44f9a43e4ab2 27
yuki0701 0:44f9a43e4ab2 28 void output(double FL,double BL,double BR,double FR);
yuki0701 0:44f9a43e4ab2 29
yuki0701 0:44f9a43e4ab2 30 void base(double FL,double BL,double BR,double FR,double Max);
yuki0701 0:44f9a43e4ab2 31
yuki0701 0:44f9a43e4ab2 32 void ashi_led();
yuki0701 0:44f9a43e4ab2 33
yuki0701 0:44f9a43e4ab2 34 void calc_gyro();
yuki0701 0:44f9a43e4ab2 35
yuki0701 0:44f9a43e4ab2 36 void calc_xy_enc();
yuki0701 0:44f9a43e4ab2 37
yuki0701 0:44f9a43e4ab2 38 void set_cond(int t, int px, double bx, int py, double by);
yuki0701 0:44f9a43e4ab2 39
yuki0701 0:44f9a43e4ab2 40 void calc_xy_usw(double tgt_angle);
yuki0701 0:44f9a43e4ab2 41
yuki0701 0:44f9a43e4ab2 42 void uwflag_reset();
yuki0701 0:44f9a43e4ab2 43
yuki0701 0:44f9a43e4ab2 44 void uwflag_change(int u1,int u2, int u3, int u4);
yuki0701 0:44f9a43e4ab2 45
yuki0701 0:44f9a43e4ab2 46 void calc_xy(double tgt_angle, double u, double v);
yuki0701 0:44f9a43e4ab2 47
yuki0701 0:44f9a43e4ab2 48 void copy_xyr_usw();
yuki0701 0:44f9a43e4ab2 49
yuki0701 0:44f9a43e4ab2 50 void enc_correction(int x_select,int y_select);
yuki0701 0:44f9a43e4ab2 51
yuki0701 0:44f9a43e4ab2 52 void enc_correction2(int x_plot1, int y_plot2);
yuki0701 0:44f9a43e4ab2 53
yuki0701 0:44f9a43e4ab2 54 void purecurve(int type,double u, double v, //正面を変えずに円弧or楕円を描いて曲がる
yuki0701 0:44f9a43e4ab2 55 double point_x1,double point_y1,
yuki0701 0:44f9a43e4ab2 56 double point_x2,double point_y2,
yuki0701 0:44f9a43e4ab2 57 int theta,
yuki0701 0:44f9a43e4ab2 58 double speed,
yuki0701 0:44f9a43e4ab2 59 double q_p,double q_d,
yuki0701 0:44f9a43e4ab2 60 double r_p,double r_d,
yuki0701 0:44f9a43e4ab2 61 double r_out_max,
yuki0701 0:44f9a43e4ab2 62 double target_angle, double v_base, double q_out_max);
yuki0701 0:44f9a43e4ab2 63
yuki0701 0:44f9a43e4ab2 64 void gogo_straight(double u, double v, double x1_point,double y1_point, //直線運動プログラム
yuki0701 0:44f9a43e4ab2 65 double x2_point,double y2_point,
yuki0701 0:44f9a43e4ab2 66 double speed1,double speed2,
yuki0701 0:44f9a43e4ab2 67 double q_p,double q_d,
yuki0701 0:44f9a43e4ab2 68 double r_p,double r_d,
yuki0701 0:44f9a43e4ab2 69 double r_out_max,
yuki0701 0:44f9a43e4ab2 70 double target_angle, double v_base, double q_out_max);
yuki0701 0:44f9a43e4ab2 71
yuki0701 0:44f9a43e4ab2 72 double spline_base(int i, int k, double t, int nv[]);
yuki0701 0:44f9a43e4ab2 73
yuki0701 0:44f9a43e4ab2 74 void spline_move(double u, double v,
yuki0701 0:44f9a43e4ab2 75 double st_x,double st_y,double end_x,double end_y,
yuki0701 0:44f9a43e4ab2 76 double cont1_x,double cont1_y,double cont2_x,double cont2_y,
yuki0701 0:44f9a43e4ab2 77 double st_speed, double end_speed,
yuki0701 0:44f9a43e4ab2 78 double q_p,double q_d,
yuki0701 0:44f9a43e4ab2 79 double r_p,double r_d,
yuki0701 0:44f9a43e4ab2 80 double r_out_max,
yuki0701 0:44f9a43e4ab2 81 double target_angle, double v_base, double q_out_max, int num);
yuki0701 0:44f9a43e4ab2 82
yuki0701 0:44f9a43e4ab2 83 void pos_correction(double tgt_x, double tgt_y, double tgt_angle, double u, double v, double v_base);
yuki0701 0:44f9a43e4ab2 84
yuki0701 0:44f9a43e4ab2 85 void mt_stop();
yuki0701 0:44f9a43e4ab2 86
yuki0701 0:44f9a43e4ab2 87 void mt_check(double out, int dr);
yuki0701 0:44f9a43e4ab2 88 #endif