harurobo_mbed_undercarriage_sub

Dependencies:   mbed Maxon_setting move4wheel2 EC PathFollowing_12_22 CruizCore_R1370P

Committer:
yuki0701
Date:
Sat Dec 15 13:25:43 2018 +0000
Revision:
0:f0f40dddc0c4
Child:
1:0c9f53f5c9d0
k;

Who changed what in which revision?

UserRevisionLine numberNew contents of line
yuki0701 0:f0f40dddc0c4 1 #include "mbed.h"
yuki0701 0:f0f40dddc0c4 2 #include "EC.h"
yuki0701 0:f0f40dddc0c4 3 #include "R1370P.h"
yuki0701 0:f0f40dddc0c4 4 #include "move4wheel.h"
yuki0701 0:f0f40dddc0c4 5 #include "PathFollowing.h"
yuki0701 0:f0f40dddc0c4 6 #include <stdarg.h>
yuki0701 0:f0f40dddc0c4 7
yuki0701 0:f0f40dddc0c4 8 #define PI 3.141592
yuki0701 0:f0f40dddc0c4 9
yuki0701 0:f0f40dddc0c4 10 #define DEBUG_MODE // compile as debug mode (comment out if you don't use)
yuki0701 0:f0f40dddc0c4 11 #ifdef DEBUG_MODE
yuki0701 0:f0f40dddc0c4 12 #define DEBUG_PRINT // enable debug_printf
yuki0701 0:f0f40dddc0c4 13 #endif
yuki0701 0:f0f40dddc0c4 14
yuki0701 0:f0f40dddc0c4 15 Serial pc(USBTX,USBRX);
yuki0701 0:f0f40dddc0c4 16 void debug_printf(const char* format,...); // work as printf in debug
yuki0701 0:f0f40dddc0c4 17 void Debug_Control(); // control by PC keybord
yuki0701 0:f0f40dddc0c4 18
yuki0701 0:f0f40dddc0c4 19 #define SPI_FREQ 1000000 // 1MHz
yuki0701 0:f0f40dddc0c4 20 #define SPI_BITS 16
yuki0701 0:f0f40dddc0c4 21 #define SPI_MODE 0
yuki0701 0:f0f40dddc0c4 22 #define SPI_WAIT_US 1 // 1us
yuki0701 0:f0f40dddc0c4 23
yuki0701 0:f0f40dddc0c4 24 /*モーターの配置
yuki0701 0:f0f40dddc0c4 25 * md1//---F---\\md4
yuki0701 0:f0f40dddc0c4 26 * | |
yuki0701 0:f0f40dddc0c4 27 * L + R
yuki0701 0:f0f40dddc0c4 28 * | |
yuki0701 0:f0f40dddc0c4 29 * md2\\---B---//md3
yuki0701 0:f0f40dddc0c4 30 */
yuki0701 0:f0f40dddc0c4 31
yuki0701 0:f0f40dddc0c4 32 //-----mbed-----//
yuki0701 0:f0f40dddc0c4 33 SPI spi(p5,p6,p7);
yuki0701 0:f0f40dddc0c4 34 CAN can1(p30,p29,1000000);
yuki0701 0:f0f40dddc0c4 35
yuki0701 0:f0f40dddc0c4 36 DigitalOut ss_md1(p15); //エスコンの設定
yuki0701 0:f0f40dddc0c4 37 DigitalOut ss_md2(p16);
yuki0701 0:f0f40dddc0c4 38 DigitalOut ss_md3(p17);
yuki0701 0:f0f40dddc0c4 39 DigitalOut ss_md4(p18);
yuki0701 0:f0f40dddc0c4 40
yuki0701 0:f0f40dddc0c4 41 DigitalOut md_enable(p25);
yuki0701 0:f0f40dddc0c4 42 //DigitalIn md_ch_enable(p10); // check enable switch is open or close
yuki0701 0:f0f40dddc0c4 43 //Timer md_disable;
yuki0701 0:f0f40dddc0c4 44 DigitalOut md_stop(p24); // stop all motor
yuki0701 0:f0f40dddc0c4 45 DigitalIn md_check(p23); // check error of all motor driver //とりあえず使わない
yuki0701 0:f0f40dddc0c4 46
yuki0701 0:f0f40dddc0c4 47 Ec EC1(p8,p26,NC,500,0.05);
yuki0701 0:f0f40dddc0c4 48 Ec EC2(p21,p22,NC,500,0.05);
yuki0701 0:f0f40dddc0c4 49 R1370P gyro(p28,p27);
yuki0701 0:f0f40dddc0c4 50
yuki0701 0:f0f40dddc0c4 51 Ticker motor_tick; //角速度計算用ticker
yuki0701 0:f0f40dddc0c4 52 Ticker ticker; //for enc
yuki0701 0:f0f40dddc0c4 53
yuki0701 0:f0f40dddc0c4 54 /*-----nucleo-----//
yuki0701 0:f0f40dddc0c4 55 SPI spi(PB_5,PB_4,PB_3);
yuki0701 0:f0f40dddc0c4 56
yuki0701 0:f0f40dddc0c4 57 DigitalOut ss_md1(PB_15); //エスコンの設定
yuki0701 0:f0f40dddc0c4 58 DigitalOut ss_md2(PB_14);
yuki0701 0:f0f40dddc0c4 59 DigitalOut ss_md3(PB_13);
yuki0701 0:f0f40dddc0c4 60 DigitalOut ss_md4(PC_4);
yuki0701 0:f0f40dddc0c4 61
yuki0701 0:f0f40dddc0c4 62 DigitalOut md_enable(PA_13); // do all motor driver enable
yuki0701 0:f0f40dddc0c4 63 //DigitalIn md_ch_enable(p10); // check enable switch is open or close
yuki0701 0:f0f40dddc0c4 64 //Timer md_disable;
yuki0701 0:f0f40dddc0c4 65 DigitalOut md_stop(PA_14); // stop all motor
yuki0701 0:f0f40dddc0c4 66 DigitalIn md_check(PB_7); // check error of all motor driver //とりあえず使わない
yuki0701 0:f0f40dddc0c4 67
yuki0701 0:f0f40dddc0c4 68 Ec EC1(PC_6,PC_8,NC,500,0.05);
yuki0701 0:f0f40dddc0c4 69 Ec EC2(PB_1,PB_12,NC,500,0.05);
yuki0701 0:f0f40dddc0c4 70 R1370P gyro(PC_6,PC_7);
yuki0701 0:f0f40dddc0c4 71
yuki0701 0:f0f40dddc0c4 72 Ticker motor_tick; //角速度計算用ticker
yuki0701 0:f0f40dddc0c4 73 Ticker ticker; //for enc */
yuki0701 0:f0f40dddc0c4 74
yuki0701 0:f0f40dddc0c4 75
yuki0701 0:f0f40dddc0c4 76
yuki0701 0:f0f40dddc0c4 77 //DigitalOut can_led(LED1); //if can enable -> toggle
yuki0701 0:f0f40dddc0c4 78 DigitalOut debug_led(LED2); //if debugmode -> on
yuki0701 0:f0f40dddc0c4 79 DigitalOut md_stop_led(LED3); //if motor stop -> on
yuki0701 0:f0f40dddc0c4 80 DigitalOut md_err_led(LED4); //if driver error -> on //とりあえず使わない
yuki0701 0:f0f40dddc0c4 81 DigitalOut led(LED1);
yuki0701 0:f0f40dddc0c4 82
yuki0701 0:f0f40dddc0c4 83 double new_dist1=0,new_dist2=0;
yuki0701 0:f0f40dddc0c4 84 double old_dist1=0,old_dist2=0;
yuki0701 0:f0f40dddc0c4 85 double d_dist1=0,d_dist2=0; //座標計算用関数
yuki0701 0:f0f40dddc0c4 86 double d_x,d_y;
yuki0701 0:f0f40dddc0c4 87 //現在地X,y座標、現在角度については、PathFollowingでnow_x,now_y,now_angleを定義済
yuki0701 0:f0f40dddc0c4 88 double start_x=0,start_y=0; //スタート位置
yuki0701 0:f0f40dddc0c4 89
yuki0701 0:f0f40dddc0c4 90 double x_out,y_out,r_out; //出力値
yuki0701 0:f0f40dddc0c4 91
yuki0701 0:f0f40dddc0c4 92 static int16_t m1=0, m2=0, m3=0, m4=0; //int16bit = int2byte
yuki0701 0:f0f40dddc0c4 93
yuki0701 0:f0f40dddc0c4 94 double usw_data1,usw_data2,usw_data3,usw_data4;//CAN通信で受け取った超音波センサーの値(1000倍してあったものを0.01倍して単位を㎝から㎜に直しつつ元の値に戻す(超音波センサーは㎝で距離を読み取る))
yuki0701 0:f0f40dddc0c4 95
yuki0701 0:f0f40dddc0c4 96
yuki0701 0:f0f40dddc0c4 97 ///////////////////機体情報をメンバとする構造体"robo_data"と構造体型変数info(←この変数に各センサーにより求めた機体情報(機体位置/機体角度)を格納する)の宣言/////////////////
yuki0701 0:f0f40dddc0c4 98
yuki0701 0:f0f40dddc0c4 99 /*「info.(機体情報の種類).(使用センサーの種類)」に各情報を格納する
yuki0701 0:f0f40dddc0c4 100 *状況に応じて、どのセンサーにより算出した情報を信用するかを選択し、その都度now_angle,now_x,now_yに代入する。(何種類かのセンサーの情報を混ぜて使用することも可能)
yuki0701 0:f0f40dddc0c4 101 *(ex)
yuki0701 0:f0f40dddc0c4 102 *info.nowX.enc → エンコーダにより算出した機体位置のx座標
yuki0701 0:f0f40dddc0c4 103 *info.nowY.usw → 超音波センサーにより求めた機体位置のy座標
yuki0701 0:f0f40dddc0c4 104 */
yuki0701 0:f0f40dddc0c4 105
yuki0701 0:f0f40dddc0c4 106 typedef struct{ //使用センサーの種類
yuki0701 0:f0f40dddc0c4 107 double usw; //超音波センサー
yuki0701 0:f0f40dddc0c4 108 double enc; //エンコーダ
yuki0701 0:f0f40dddc0c4 109 double gyro; //ジャイロ
yuki0701 0:f0f40dddc0c4 110 //double line;//ラインセンサー
yuki0701 0:f0f40dddc0c4 111 }robo_sensor;
yuki0701 0:f0f40dddc0c4 112
yuki0701 0:f0f40dddc0c4 113 typedef struct{ //機体情報の種類
yuki0701 0:f0f40dddc0c4 114 robo_sensor angle; //←機体角度は超音波センサーやラインセンサーからも算出可能なので一応格納先を用意したが、ジャイロの値を完全に信用してもいいかも
yuki0701 0:f0f40dddc0c4 115 robo_sensor nowX;
yuki0701 0:f0f40dddc0c4 116 robo_sensor nowY;
yuki0701 0:f0f40dddc0c4 117 }robo_data;
yuki0701 0:f0f40dddc0c4 118
yuki0701 0:f0f40dddc0c4 119 robo_data info={{0,0,0},{0,0,0},{0,0,0}}; //全てのデータを0に初期化
yuki0701 0:f0f40dddc0c4 120
yuki0701 0:f0f40dddc0c4 121
yuki0701 0:f0f40dddc0c4 122 ///////////////////////////////////////////////////関数のプロトタイプ宣言////////////////////////////////////////////////////
yuki0701 0:f0f40dddc0c4 123
yuki0701 0:f0f40dddc0c4 124 void UserLoopSetting(); // initialize setting
yuki0701 0:f0f40dddc0c4 125 void DAC_Write(int16_t data, DigitalOut* DAC_cs);
yuki0701 0:f0f40dddc0c4 126 void MotorControl(int16_t val_md1, int16_t val_md2, int16_t val_md3, int16_t val_md4);
yuki0701 0:f0f40dddc0c4 127
yuki0701 0:f0f40dddc0c4 128 void calOmega() //角速度計算関数
yuki0701 0:f0f40dddc0c4 129 {
yuki0701 0:f0f40dddc0c4 130 EC1.CalOmega();
yuki0701 0:f0f40dddc0c4 131 EC2.CalOmega();
yuki0701 0:f0f40dddc0c4 132 }
yuki0701 0:f0f40dddc0c4 133
yuki0701 0:f0f40dddc0c4 134 void can_read(){//CAN通信受信
yuki0701 0:f0f40dddc0c4 135
yuki0701 0:f0f40dddc0c4 136 CANMessage msg;
yuki0701 0:f0f40dddc0c4 137
yuki0701 0:f0f40dddc0c4 138 if(can1.read(msg)){
yuki0701 0:f0f40dddc0c4 139
yuki0701 0:f0f40dddc0c4 140 if(msg.id == 1){
yuki0701 0:f0f40dddc0c4 141 led = 1;
yuki0701 0:f0f40dddc0c4 142 usw_data1 = 0.01 * (short)((msg.data[0]<<8) | msg.data[1]);
yuki0701 0:f0f40dddc0c4 143 //printf("usw_data1 = %d:%d,%d\n\r",msg.data[0],msg.data[1],x);
yuki0701 0:f0f40dddc0c4 144 }else if(msg.id == 2){
yuki0701 0:f0f40dddc0c4 145 led = 1;
yuki0701 0:f0f40dddc0c4 146 usw_data2 = 0.01 * (short)((msg.data[0]<<8) | msg.data[1]);
yuki0701 0:f0f40dddc0c4 147 //printf("usw_data2 = %d:%d,%d\n\r",msg.data[0],msg.data[1],x);
yuki0701 0:f0f40dddc0c4 148 }else if(msg.id == 3){
yuki0701 0:f0f40dddc0c4 149 led = 1;
yuki0701 0:f0f40dddc0c4 150 usw_data3 = 0.01 * (short)((msg.data[0]<<8) | msg.data[1]);
yuki0701 0:f0f40dddc0c4 151 //printf("usw_data3 = %d:%d,%d\n\r",msg.data[0],msg.data[1],x);
yuki0701 0:f0f40dddc0c4 152 }else if(msg.id == 4){
yuki0701 0:f0f40dddc0c4 153 led = 1;
yuki0701 0:f0f40dddc0c4 154 usw_data4 = 0.01 * (short)((msg.data[0]<<8) | msg.data[1]);
yuki0701 0:f0f40dddc0c4 155 //printf("usw_data4 = %d:%d,%d\n\r",msg.data[0],msg.data[1],x);
yuki0701 0:f0f40dddc0c4 156 }
yuki0701 0:f0f40dddc0c4 157
yuki0701 0:f0f40dddc0c4 158 }
yuki0701 0:f0f40dddc0c4 159 }
yuki0701 0:f0f40dddc0c4 160
yuki0701 0:f0f40dddc0c4 161
yuki0701 0:f0f40dddc0c4 162 void output(double FL,double BL,double BR,double FR)
yuki0701 0:f0f40dddc0c4 163 {
yuki0701 0:f0f40dddc0c4 164 m1=FL;
yuki0701 0:f0f40dddc0c4 165 m2=BL;
yuki0701 0:f0f40dddc0c4 166 m3=BR;
yuki0701 0:f0f40dddc0c4 167 m4=FR;
yuki0701 0:f0f40dddc0c4 168 }
yuki0701 0:f0f40dddc0c4 169
yuki0701 0:f0f40dddc0c4 170 void base(double FL,double BL,double BR,double FR,double Max)
yuki0701 0:f0f40dddc0c4 171 //いろんな加算をしても最大OR最小がMaxになるような補正//絶対値が一番でかいやつで除算
yuki0701 0:f0f40dddc0c4 172 //DCモーターならMax=1、マクソンは-4095~4095だからMax=4095にする
yuki0701 0:f0f40dddc0c4 173 {
yuki0701 0:f0f40dddc0c4 174 if(fabs(FL)>=Max||fabs(BL)>=Max||fabs(BR)>=Max||fabs(FR)>=Max) {
yuki0701 0:f0f40dddc0c4 175
yuki0701 0:f0f40dddc0c4 176 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:f0f40dddc0c4 177 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:f0f40dddc0c4 178 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:f0f40dddc0c4 179 else output(Max*FL/fabs(FR),Max*BL/fabs(FR),Max*BR/fabs(FR),Max*FR/fabs(FR));
yuki0701 0:f0f40dddc0c4 180 } else {
yuki0701 0:f0f40dddc0c4 181 output(FL,BL,BR,FR);
yuki0701 0:f0f40dddc0c4 182 }
yuki0701 0:f0f40dddc0c4 183 }
yuki0701 0:f0f40dddc0c4 184
yuki0701 0:f0f40dddc0c4 185 void calc_xy() //エンコーダによる座標計算
yuki0701 0:f0f40dddc0c4 186 {
yuki0701 0:f0f40dddc0c4 187 now_angle=gyro.getAngle(); //ジャイロの値読み込み
yuki0701 0:f0f40dddc0c4 188
yuki0701 0:f0f40dddc0c4 189 new_dist1=EC1.getDistance_mm();
yuki0701 0:f0f40dddc0c4 190 new_dist2=EC2.getDistance_mm();
yuki0701 0:f0f40dddc0c4 191 d_dist1=new_dist1-old_dist1;
yuki0701 0:f0f40dddc0c4 192 d_dist2=new_dist2-old_dist2;
yuki0701 0:f0f40dddc0c4 193 old_dist1=new_dist1;
yuki0701 0:f0f40dddc0c4 194 old_dist2=new_dist2; //微小時間当たりのエンコーダ読み込み
yuki0701 0:f0f40dddc0c4 195
yuki0701 0:f0f40dddc0c4 196 d_x=d_dist2*sin(now_angle*PI/180)-d_dist1*cos(now_angle*PI/180);
yuki0701 0:f0f40dddc0c4 197 d_y=d_dist2*cos(now_angle*PI/180)+d_dist1*sin(now_angle*PI/180); //微小時間毎の座標変化
yuki0701 0:f0f40dddc0c4 198 info.nowX.enc = info.nowX.enc + d_x;
yuki0701 0:f0f40dddc0c4 199 info.nowY.enc = info.nowY.enc - d_y; //微小時間毎に座標に加算
yuki0701 0:f0f40dddc0c4 200 }
yuki0701 0:f0f40dddc0c4 201
yuki0701 0:f0f40dddc0c4 202
yuki0701 0:f0f40dddc0c4 203 void calc_xy_usw(double tgt_angle,int xy_type,int pm_type,double xy_base){ //超音波センサーによる座標計算(機体が旋回する場合はこの方法による座標計算は出来ない)
yuki0701 0:f0f40dddc0c4 204 //tgt_angle:機体の目標角度(運動初期角度と同じ/今大会では0,90,180のみ)
yuki0701 0:f0f40dddc0c4 205 //xy_type:(0:Y軸平行の壁を読む/1:X軸平行の壁を読む)
yuki0701 0:f0f40dddc0c4 206 //pm_type:(0:各軸正方向側の壁を読む/1:各軸負方向側の壁を読む)
yuki0701 0:f0f40dddc0c4 207 //xy_base:超音波センサーで読む壁の座標(x軸平行の壁のy座標/y軸並行の壁のx座標)
yuki0701 0:f0f40dddc0c4 208
yuki0701 0:f0f40dddc0c4 209 double R1=130,R2=130,R3=130,R4=130; //機体の中心から各超音波センサーが付いている面までの距離
yuki0701 0:f0f40dddc0c4 210 double D1=50,D2=50,D3=50,D4=50; //各超音波センサーが付いている面の中心から各超音波センサーまでの距離
yuki0701 0:f0f40dddc0c4 211
yuki0701 0:f0f40dddc0c4 212 now_angle=gyro.getAngle();
yuki0701 0:f0f40dddc0c4 213
yuki0701 0:f0f40dddc0c4 214 if(tgt_angle==0){
yuki0701 0:f0f40dddc0c4 215 if(xy_type==0 && pm_type==0){
yuki0701 0:f0f40dddc0c4 216
yuki0701 0:f0f40dddc0c4 217 info.nowX.usw = xy_base - (usw_data3 + R3*cos(now_angle*PI/180) + D3*sin(now_angle*PI/180));
yuki0701 0:f0f40dddc0c4 218
yuki0701 0:f0f40dddc0c4 219 }else if(xy_type==0 && pm_type==1){
yuki0701 0:f0f40dddc0c4 220
yuki0701 0:f0f40dddc0c4 221 info.nowX.usw = xy_base + (usw_data4 + R4*cos(now_angle*PI/180) + D4*sin(now_angle*PI/180));
yuki0701 0:f0f40dddc0c4 222
yuki0701 0:f0f40dddc0c4 223 }else if(xy_type==1 && pm_type==0){
yuki0701 0:f0f40dddc0c4 224
yuki0701 0:f0f40dddc0c4 225 info.nowY.usw = xy_base - (usw_data1 + R1*cos(now_angle*PI/180) + D1*sin(now_angle*PI/180));
yuki0701 0:f0f40dddc0c4 226
yuki0701 0:f0f40dddc0c4 227 }else if(xy_type==1 && pm_type==1){
yuki0701 0:f0f40dddc0c4 228
yuki0701 0:f0f40dddc0c4 229 info.nowY.usw = xy_base + (usw_data2 + R2*cos(now_angle*PI/180) + D2*sin(now_angle*PI/180));
yuki0701 0:f0f40dddc0c4 230
yuki0701 0:f0f40dddc0c4 231 }
yuki0701 0:f0f40dddc0c4 232
yuki0701 0:f0f40dddc0c4 233 }else if(tgt_angle==90){
yuki0701 0:f0f40dddc0c4 234 if(xy_type==0 && pm_type==0){
yuki0701 0:f0f40dddc0c4 235
yuki0701 0:f0f40dddc0c4 236 info.nowX.usw = xy_base - (usw_data2 + R2*cos(now_angle*PI/180) + D2*sin(now_angle*PI/180));
yuki0701 0:f0f40dddc0c4 237
yuki0701 0:f0f40dddc0c4 238 }else if(xy_type==0 && pm_type==1){
yuki0701 0:f0f40dddc0c4 239
yuki0701 0:f0f40dddc0c4 240 info.nowX.usw = xy_base + (usw_data1 + R1*cos(now_angle*PI/180) + D1*sin(now_angle*PI/180));
yuki0701 0:f0f40dddc0c4 241
yuki0701 0:f0f40dddc0c4 242 }else if(xy_type==1 && pm_type==0){
yuki0701 0:f0f40dddc0c4 243
yuki0701 0:f0f40dddc0c4 244 info.nowY.usw = xy_base - (usw_data3 + R3*cos(now_angle*PI/180) + D3*sin(now_angle*PI/180));
yuki0701 0:f0f40dddc0c4 245
yuki0701 0:f0f40dddc0c4 246 }else if(xy_type==1 && pm_type==1){
yuki0701 0:f0f40dddc0c4 247
yuki0701 0:f0f40dddc0c4 248 info.nowY.usw = xy_base + (usw_data4 + R4*cos(now_angle*PI/180) + D4*sin(now_angle*PI/180));
yuki0701 0:f0f40dddc0c4 249
yuki0701 0:f0f40dddc0c4 250 }
yuki0701 0:f0f40dddc0c4 251
yuki0701 0:f0f40dddc0c4 252 }else if(tgt_angle==180){
yuki0701 0:f0f40dddc0c4 253 if(xy_type==0 && pm_type==0){
yuki0701 0:f0f40dddc0c4 254
yuki0701 0:f0f40dddc0c4 255 info.nowX.usw = xy_base - (usw_data4 + R4*cos(now_angle*PI/180) + D4*sin(now_angle*PI/180));
yuki0701 0:f0f40dddc0c4 256
yuki0701 0:f0f40dddc0c4 257 }else if(xy_type==0 && pm_type==1){
yuki0701 0:f0f40dddc0c4 258
yuki0701 0:f0f40dddc0c4 259 info.nowX.usw = xy_base + (usw_data3 + R3*cos(now_angle*PI/180) + D3*sin(now_angle*PI/180));
yuki0701 0:f0f40dddc0c4 260
yuki0701 0:f0f40dddc0c4 261 }else if(xy_type==1 && pm_type==0){
yuki0701 0:f0f40dddc0c4 262
yuki0701 0:f0f40dddc0c4 263 info.nowY.usw = xy_base - (usw_data2+ R2*cos(now_angle*PI/180) + D2*sin(now_angle*PI/180));
yuki0701 0:f0f40dddc0c4 264
yuki0701 0:f0f40dddc0c4 265 }else if(xy_type==1 && pm_type==1){
yuki0701 0:f0f40dddc0c4 266
yuki0701 0:f0f40dddc0c4 267 info.nowY.usw = xy_base + (usw_data1 + R1*cos(now_angle*PI/180) + D1*sin(now_angle*PI/180));
yuki0701 0:f0f40dddc0c4 268
yuki0701 0:f0f40dddc0c4 269 }
yuki0701 0:f0f40dddc0c4 270
yuki0701 0:f0f40dddc0c4 271 }
yuki0701 0:f0f40dddc0c4 272
yuki0701 0:f0f40dddc0c4 273 }
yuki0701 0:f0f40dddc0c4 274
yuki0701 0:f0f40dddc0c4 275 //ここからそれぞれのプログラム/////////////////////////////////////////////////////////////////////////////////////////////////////////////////
yuki0701 0:f0f40dddc0c4 276 //now_x(現在のx座標),now_y(現在のy座標),now_angle(機体角度(ラジアンではない)(0~360や-180~180とは限らない))(反時計回りが正)
yuki0701 0:f0f40dddc0c4 277 //ジャイロの出力は角度だが三角関数はラジアンとして計算する
yuki0701 0:f0f40dddc0c4 278 //通常の移動+座標のずれ補正+機体の角度補正(+必要に応じさらに別補正)
yuki0701 0:f0f40dddc0c4 279 //ジャイロの仕様上、角度補正をするときに計算式内で角度はそのままよりsinをとったほうがいいかもね
yuki0701 0:f0f40dddc0c4 280
yuki0701 0:f0f40dddc0c4 281 void purecurve2(int type, //正面を変えずに円弧or楕円を描いて曲がる
yuki0701 0:f0f40dddc0c4 282 double point_x1,double point_y1,
yuki0701 0:f0f40dddc0c4 283 double point_x2,double point_y2,
yuki0701 0:f0f40dddc0c4 284 int theta,
yuki0701 0:f0f40dddc0c4 285 double speed,
yuki0701 0:f0f40dddc0c4 286 double q_p,double q_d,
yuki0701 0:f0f40dddc0c4 287 double r_p,double r_d,
yuki0701 0:f0f40dddc0c4 288 double r_out_max,
yuki0701 0:f0f40dddc0c4 289 double target_angle)
yuki0701 0:f0f40dddc0c4 290 //type:動きの種類(8パターン) point_x1,point_y1=出発地点の座標 point_x2,point_x2=目標地点の座標 theta=plotの間隔(0~90°) speed=速度
yuki0701 0:f0f40dddc0c4 291 {
yuki0701 0:f0f40dddc0c4 292 //-----PathFollowingのパラメーター設定-----//
yuki0701 0:f0f40dddc0c4 293 q_setPDparam(q_p,q_d); //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数
yuki0701 0:f0f40dddc0c4 294 r_setPDparam(r_p,r_d); //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数
yuki0701 0:f0f40dddc0c4 295 set_r_out(r_out_max); //旋回時の最大出力値設定関数
yuki0701 0:f0f40dddc0c4 296 set_target_angle(target_angle); //機体目標角度設定関数
yuki0701 0:f0f40dddc0c4 297
yuki0701 0:f0f40dddc0c4 298 int s;
yuki0701 0:f0f40dddc0c4 299 int t = 0;
yuki0701 0:f0f40dddc0c4 300 double X,Y;//X=楕円の中心座標、Y=楕円の中心座標
yuki0701 0:f0f40dddc0c4 301 double a,b; //a=楕円のx軸方向の幅の半分,b=楕円のy軸方向の幅の半分
yuki0701 0:f0f40dddc0c4 302 double plotx[(90/theta)+1]; //楕円にとるplotのx座標
yuki0701 0:f0f40dddc0c4 303 double ploty[(90/theta)+1];
yuki0701 0:f0f40dddc0c4 304
yuki0701 0:f0f40dddc0c4 305 double x_out,y_out,r_out;
yuki0701 0:f0f40dddc0c4 306
yuki0701 0:f0f40dddc0c4 307 a=fabs(point_x1-point_x2);
yuki0701 0:f0f40dddc0c4 308 b=fabs(point_y1-point_y2);
yuki0701 0:f0f40dddc0c4 309
yuki0701 0:f0f40dddc0c4 310 switch(type) {
yuki0701 0:f0f40dddc0c4 311
yuki0701 0:f0f40dddc0c4 312 case 1://→↑移動
yuki0701 0:f0f40dddc0c4 313 X=point_x1;
yuki0701 0:f0f40dddc0c4 314 Y=point_y2;
yuki0701 0:f0f40dddc0c4 315
yuki0701 0:f0f40dddc0c4 316 for(s=0; s<((90/theta)+1); s++) {
yuki0701 0:f0f40dddc0c4 317 plotx[s] = X + a * cos(-PI/2 + s * (PI*theta/180));
yuki0701 0:f0f40dddc0c4 318 ploty[s] = Y + b * sin(-PI/2 + s * (PI*theta/180));
yuki0701 0:f0f40dddc0c4 319 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 0:f0f40dddc0c4 320 }
yuki0701 0:f0f40dddc0c4 321 break;
yuki0701 0:f0f40dddc0c4 322
yuki0701 0:f0f40dddc0c4 323 case 2://↑→移動
yuki0701 0:f0f40dddc0c4 324 X=point_x2;
yuki0701 0:f0f40dddc0c4 325 Y=point_y1;
yuki0701 0:f0f40dddc0c4 326
yuki0701 0:f0f40dddc0c4 327 for(s=0; s<((90/theta)+1); s++) {
yuki0701 0:f0f40dddc0c4 328 plotx[s] = X + a * cos(PI - s * (PI*theta/180));
yuki0701 0:f0f40dddc0c4 329 ploty[s] = Y + b * sin(PI - s * (PI*theta/180));
yuki0701 0:f0f40dddc0c4 330 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 0:f0f40dddc0c4 331 }
yuki0701 0:f0f40dddc0c4 332 break;
yuki0701 0:f0f40dddc0c4 333
yuki0701 0:f0f40dddc0c4 334 case 3://↑←移動
yuki0701 0:f0f40dddc0c4 335 X=point_x2;
yuki0701 0:f0f40dddc0c4 336 Y=point_y1;
yuki0701 0:f0f40dddc0c4 337
yuki0701 0:f0f40dddc0c4 338 for(s=0; s<((90/theta)+1); s++) {
yuki0701 0:f0f40dddc0c4 339 plotx[s] = X + a * cos(s * (PI*theta/180));
yuki0701 0:f0f40dddc0c4 340 ploty[s] = Y + b * sin(s * (PI*theta/180));
yuki0701 0:f0f40dddc0c4 341 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 0:f0f40dddc0c4 342 }
yuki0701 0:f0f40dddc0c4 343 break;
yuki0701 0:f0f40dddc0c4 344
yuki0701 0:f0f40dddc0c4 345 case 4://←↑移動
yuki0701 0:f0f40dddc0c4 346 X=point_x1;
yuki0701 0:f0f40dddc0c4 347 Y=point_y2;
yuki0701 0:f0f40dddc0c4 348
yuki0701 0:f0f40dddc0c4 349 for(s=0; s<((90/theta)+1); s++) {
yuki0701 0:f0f40dddc0c4 350 plotx[s] = X + a * cos(-PI/2 - s * (PI*theta/180));
yuki0701 0:f0f40dddc0c4 351 ploty[s] = Y + b * sin(-PI/2 - s * (PI*theta/180));
yuki0701 0:f0f40dddc0c4 352 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 0:f0f40dddc0c4 353 }
yuki0701 0:f0f40dddc0c4 354 break;
yuki0701 0:f0f40dddc0c4 355
yuki0701 0:f0f40dddc0c4 356 case 5://←↓移動
yuki0701 0:f0f40dddc0c4 357 X=point_x1;
yuki0701 0:f0f40dddc0c4 358 Y=point_y2;
yuki0701 0:f0f40dddc0c4 359
yuki0701 0:f0f40dddc0c4 360 for(s=0; s<((90/theta)+1); s++) {
yuki0701 0:f0f40dddc0c4 361 plotx[s] = X + a * cos(PI/2 + s * (PI*theta/180));
yuki0701 0:f0f40dddc0c4 362 ploty[s] = Y + b * sin(PI/2 + s * (PI*theta/180));
yuki0701 0:f0f40dddc0c4 363 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 0:f0f40dddc0c4 364 }
yuki0701 0:f0f40dddc0c4 365 break;
yuki0701 0:f0f40dddc0c4 366
yuki0701 0:f0f40dddc0c4 367 case 6://↓←移動
yuki0701 0:f0f40dddc0c4 368 X=point_x2;
yuki0701 0:f0f40dddc0c4 369 Y=point_y1;
yuki0701 0:f0f40dddc0c4 370
yuki0701 0:f0f40dddc0c4 371 for(s=0; s<((90/theta)+1); s++) {
yuki0701 0:f0f40dddc0c4 372 plotx[s] = X + a * cos(-s * (PI*theta/180));
yuki0701 0:f0f40dddc0c4 373 ploty[s] = Y + b * sin(-s * (PI*theta/180));
yuki0701 0:f0f40dddc0c4 374 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 0:f0f40dddc0c4 375 }
yuki0701 0:f0f40dddc0c4 376 break;
yuki0701 0:f0f40dddc0c4 377
yuki0701 0:f0f40dddc0c4 378 case 7://↓→移動
yuki0701 0:f0f40dddc0c4 379 X=point_x2;
yuki0701 0:f0f40dddc0c4 380 Y=point_y1;
yuki0701 0:f0f40dddc0c4 381
yuki0701 0:f0f40dddc0c4 382 for(s=0; s<((90/theta)+1); s++) {
yuki0701 0:f0f40dddc0c4 383 plotx[s] = X + a * cos(PI + s * (PI*theta/180));
yuki0701 0:f0f40dddc0c4 384 ploty[s] = Y + b * sin(PI + s * (PI*theta/180));
yuki0701 0:f0f40dddc0c4 385 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 0:f0f40dddc0c4 386 }
yuki0701 0:f0f40dddc0c4 387 break;
yuki0701 0:f0f40dddc0c4 388
yuki0701 0:f0f40dddc0c4 389 case 8://→↓移動
yuki0701 0:f0f40dddc0c4 390 X=point_x1;
yuki0701 0:f0f40dddc0c4 391 Y=point_y2;
yuki0701 0:f0f40dddc0c4 392
yuki0701 0:f0f40dddc0c4 393 for(s=0; s<((90/theta)+1); s++) {
yuki0701 0:f0f40dddc0c4 394 plotx[s] = X + a * cos(PI/2 - s * (PI*theta/180));
yuki0701 0:f0f40dddc0c4 395 ploty[s] = Y + b * sin(PI/2 - s * (PI*theta/180));
yuki0701 0:f0f40dddc0c4 396 //debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
yuki0701 0:f0f40dddc0c4 397 }
yuki0701 0:f0f40dddc0c4 398 break;
yuki0701 0:f0f40dddc0c4 399 }
yuki0701 0:f0f40dddc0c4 400
yuki0701 0:f0f40dddc0c4 401 while(1) {
yuki0701 0:f0f40dddc0c4 402
yuki0701 0:f0f40dddc0c4 403 calc_xy();
yuki0701 0:f0f40dddc0c4 404
yuki0701 0:f0f40dddc0c4 405 now_x = info.nowX.enc; //カーブする時はエンコーダにより求める機体位置を100%信用
yuki0701 0:f0f40dddc0c4 406 now_y = info.nowY.enc;
yuki0701 0:f0f40dddc0c4 407
yuki0701 0:f0f40dddc0c4 408 XYRmotorout(plotx[t],ploty[t],plotx[t+1],ploty[t+1],&x_out,&y_out,&r_out,speed,speed);
yuki0701 0:f0f40dddc0c4 409 CalMotorOut(x_out,y_out,r_out);
yuki0701 0:f0f40dddc0c4 410 //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:f0f40dddc0c4 411
yuki0701 0:f0f40dddc0c4 412 base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),4095); //m1~m4に代入
yuki0701 0:f0f40dddc0c4 413 //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:f0f40dddc0c4 414
yuki0701 0:f0f40dddc0c4 415 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:f0f40dddc0c4 416
yuki0701 0:f0f40dddc0c4 417 MotorControl(m1,m2,m3,m4); //出力
yuki0701 0:f0f40dddc0c4 418 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:f0f40dddc0c4 419
yuki0701 0:f0f40dddc0c4 420 if(t == (90/theta))break;
yuki0701 0:f0f40dddc0c4 421 }
yuki0701 0:f0f40dddc0c4 422 }
yuki0701 0:f0f40dddc0c4 423
yuki0701 0:f0f40dddc0c4 424
yuki0701 0:f0f40dddc0c4 425 void gogo_straight(double x1_point,double y1_point, //直線運動プログラム
yuki0701 0:f0f40dddc0c4 426 double x2_point,double y2_point,
yuki0701 0:f0f40dddc0c4 427 double speed1,double speed2,
yuki0701 0:f0f40dddc0c4 428 double q_p,double q_d,
yuki0701 0:f0f40dddc0c4 429 double r_p,double r_d,
yuki0701 0:f0f40dddc0c4 430 double r_out_max,
yuki0701 0:f0f40dddc0c4 431 double target_angle)
yuki0701 0:f0f40dddc0c4 432 //引数:出発地点の座標(x,y)、目標地点の座標(x,y)、初速度(speed1)、目標速度(speed2)//speed1=speed2 のとき等速運動
yuki0701 0:f0f40dddc0c4 433 {
yuki0701 0:f0f40dddc0c4 434 //-----PathFollowingのパラメーター設定-----//
yuki0701 0:f0f40dddc0c4 435 q_setPDparam(q_p,q_d); //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数
yuki0701 0:f0f40dddc0c4 436 r_setPDparam(r_p,r_d); //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数
yuki0701 0:f0f40dddc0c4 437 set_r_out(r_out_max); //旋回時の最大出力値設定関数
yuki0701 0:f0f40dddc0c4 438 set_target_angle(target_angle); //機体目標角度設定関数
yuki0701 0:f0f40dddc0c4 439
yuki0701 0:f0f40dddc0c4 440 while (1) {
yuki0701 0:f0f40dddc0c4 441
yuki0701 0:f0f40dddc0c4 442 calc_xy();
yuki0701 0:f0f40dddc0c4 443
yuki0701 0:f0f40dddc0c4 444 XYRmotorout(x1_point,y1_point,x2_point,y2_point,&x_out,&y_out,&r_out,speed1,speed2);
yuki0701 0:f0f40dddc0c4 445 //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 0:f0f40dddc0c4 446
yuki0701 0:f0f40dddc0c4 447 CalMotorOut(x_out,y_out,r_out);
yuki0701 0:f0f40dddc0c4 448 //printf("out1=%lf, out2=%lf, out3=%lf, out4=%lf\n",GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3));
yuki0701 0:f0f40dddc0c4 449
yuki0701 0:f0f40dddc0c4 450 base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),4095);
yuki0701 0:f0f40dddc0c4 451 //printf("m1=%d, m2=%d, m3=%d, m4=%d\r\n",m1,m2,m3,m4);
yuki0701 0:f0f40dddc0c4 452
yuki0701 0:f0f40dddc0c4 453 MotorControl(m1,m2,m3,m4);
yuki0701 0:f0f40dddc0c4 454 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:f0f40dddc0c4 455
yuki0701 0:f0f40dddc0c4 456 if(((x2_point - now_x)*(x2_point - x1_point) + (y2_point - now_y)*(y2_point - y1_point)) < 0)break;
yuki0701 0:f0f40dddc0c4 457 }
yuki0701 0:f0f40dddc0c4 458 }
yuki0701 0:f0f40dddc0c4 459
yuki0701 0:f0f40dddc0c4 460 /*void usw_pos_correction(int type,double error,double base_x,double base_y,double x1_point,double y1_point,double x2_point,double y2_point){ //超音波センサーによる位置補正プログラム(x軸 or y軸に平行なきのみ)
yuki0701 0:f0f40dddc0c4 461 //type(1:x方向-果物アーム側/2:y方向-果物アーム/3:y方向-三宝アーム側)
yuki0701 0:f0f40dddc0c4 462 //error:補正の終了を判断するときの目標値からの許容誤差
yuki0701 0:f0f40dddc0c4 463 //base_x,base_y:超音波センサーで読む壁の座標(y軸平行の壁のx座標/x軸平行の壁のy座標)
yuki0701 0:f0f40dddc0c4 464 //x1_point,y2_point:出発地点の座標
yuki0701 0:f0f40dddc0c4 465 //x2_point,y2_point:目標地点の座標
yuki0701 0:f0f40dddc0c4 466
yuki0701 0:f0f40dddc0c4 467
yuki0701 0:f0f40dddc0c4 468 }*/
yuki0701 0:f0f40dddc0c4 469
yuki0701 0:f0f40dddc0c4 470 //////////////////////////////////////////////////////////////以下main文/////////////////////////////////////////////////////////////////
yuki0701 0:f0f40dddc0c4 471 int main()
yuki0701 0:f0f40dddc0c4 472 {
yuki0701 0:f0f40dddc0c4 473 UserLoopSetting();
yuki0701 0:f0f40dddc0c4 474 //Debug_Control()
yuki0701 0:f0f40dddc0c4 475
yuki0701 0:f0f40dddc0c4 476 //purecurve2(2,start_x,start_y,500,1000,9,1000,5,0.1,10,0.1,600,0);
yuki0701 0:f0f40dddc0c4 477
yuki0701 0:f0f40dddc0c4 478 purecurve2(5,start_x,start_y,-500,-500,9,1500,5,0.1,10,0.1,600,0);
yuki0701 0:f0f40dddc0c4 479 gogo_straight(-500,-500,-500,-1500,2000,2000,5,0.1,10,0.1,600,0);
yuki0701 0:f0f40dddc0c4 480
yuki0701 0:f0f40dddc0c4 481 //purecurve2(3,now_x,now_y,0,2500,9,1000,5,0.1,10,0.1,600,0);
yuki0701 0:f0f40dddc0c4 482
yuki0701 0:f0f40dddc0c4 483 MotorControl(0,0,0,0);
yuki0701 0:f0f40dddc0c4 484 }
yuki0701 0:f0f40dddc0c4 485 ///////////////////////////////////////////////////////////////////////以下マクソン関連///////////////////////////////////////////////////////////////////////////
yuki0701 0:f0f40dddc0c4 486
yuki0701 0:f0f40dddc0c4 487 void UserLoopSetting()
yuki0701 0:f0f40dddc0c4 488 {
yuki0701 0:f0f40dddc0c4 489 //------機体情報の初期化------//
yuki0701 0:f0f40dddc0c4 490
yuki0701 0:f0f40dddc0c4 491 //info.nowX = {0,0,0};
yuki0701 0:f0f40dddc0c4 492 //info.nowY = {0,0,0};
yuki0701 0:f0f40dddc0c4 493
yuki0701 0:f0f40dddc0c4 494 //-----エスコンの初期設定-----//
yuki0701 0:f0f40dddc0c4 495 spi.format(SPI_BITS, SPI_MODE);
yuki0701 0:f0f40dddc0c4 496 spi.frequency(SPI_FREQ);
yuki0701 0:f0f40dddc0c4 497 ss_md1 = 1;
yuki0701 0:f0f40dddc0c4 498 ss_md2 = 1;
yuki0701 0:f0f40dddc0c4 499 ss_md3 = 1;
yuki0701 0:f0f40dddc0c4 500 ss_md4 = 1;
yuki0701 0:f0f40dddc0c4 501 md_enable = 1; //enable on
yuki0701 0:f0f40dddc0c4 502 md_err_led = 0;
yuki0701 0:f0f40dddc0c4 503 md_stop = 1;
yuki0701 0:f0f40dddc0c4 504 md_stop_led = 1;
yuki0701 0:f0f40dddc0c4 505 //-----センサーの初期設定-----//
yuki0701 0:f0f40dddc0c4 506 gyro.initialize();
yuki0701 0:f0f40dddc0c4 507 motor_tick.attach(&calOmega,0.05); //0.05秒間隔で角速度を計算
yuki0701 0:f0f40dddc0c4 508 EC1.setDiameter_mm(48);
yuki0701 0:f0f40dddc0c4 509 EC2.setDiameter_mm(48); //測定輪半径//後で測定
yuki0701 0:f0f40dddc0c4 510
yuki0701 0:f0f40dddc0c4 511 #ifdef DEBUG_MODE
yuki0701 0:f0f40dddc0c4 512 debug_led = 1;
yuki0701 0:f0f40dddc0c4 513 pc.attach(Debug_Control, Serial::RxIrq);
yuki0701 0:f0f40dddc0c4 514 #else
yuki0701 0:f0f40dddc0c4 515 debug_led = 0;
yuki0701 0:f0f40dddc0c4 516 #endif
yuki0701 0:f0f40dddc0c4 517 }
yuki0701 0:f0f40dddc0c4 518
yuki0701 0:f0f40dddc0c4 519 #define MCP4922_AB (1<<15)
yuki0701 0:f0f40dddc0c4 520 #define MCP4922_BUF (1<<14)
yuki0701 0:f0f40dddc0c4 521 #define MCP4922_GA (1<<13)
yuki0701 0:f0f40dddc0c4 522 #define MCP4922_SHDN (1<<12)
yuki0701 0:f0f40dddc0c4 523
yuki0701 0:f0f40dddc0c4 524 #define MCP4922_SET_OUTA (0x3000) //( MCP4922_GA || MCP4922_SHDN ) //12288
yuki0701 0:f0f40dddc0c4 525 #define MCP4922_SET_OUTB (0xB000) //( MCP4922_AB || MCP4922_GA || MCP4922_SHDN ) //45056
yuki0701 0:f0f40dddc0c4 526 #define MCP4922_MASKSET (0x0FFF) //4095
yuki0701 0:f0f40dddc0c4 527
yuki0701 0:f0f40dddc0c4 528 void DAC_Write(int16_t data, DigitalOut* DAC_cs) //(出力,出力場所)
yuki0701 0:f0f40dddc0c4 529 {
yuki0701 0:f0f40dddc0c4 530 static uint16_t dataA; //送るデータ
yuki0701 0:f0f40dddc0c4 531 static uint16_t dataB;
yuki0701 0:f0f40dddc0c4 532
yuki0701 0:f0f40dddc0c4 533 dataA = MCP4922_SET_OUTA;
yuki0701 0:f0f40dddc0c4 534 dataB = MCP4922_SET_OUTB;
yuki0701 0:f0f40dddc0c4 535
yuki0701 0:f0f40dddc0c4 536 if(data >= 0) {
yuki0701 0:f0f40dddc0c4 537 if(data > 4095) {
yuki0701 0:f0f40dddc0c4 538 data = 4095;
yuki0701 0:f0f40dddc0c4 539 }
yuki0701 0:f0f40dddc0c4 540 dataA += (MCP4922_MASKSET & (uint16_t)(data));
yuki0701 0:f0f40dddc0c4 541 } else {
yuki0701 0:f0f40dddc0c4 542 if(data < -4095) {
yuki0701 0:f0f40dddc0c4 543 data = -4095;
yuki0701 0:f0f40dddc0c4 544 }
yuki0701 0:f0f40dddc0c4 545 dataB += (MCP4922_MASKSET & (uint16_t)(-data));
yuki0701 0:f0f40dddc0c4 546 }
yuki0701 0:f0f40dddc0c4 547
yuki0701 0:f0f40dddc0c4 548 //Aの出力設定
yuki0701 0:f0f40dddc0c4 549 (DigitalOut)(*DAC_cs)=0;
yuki0701 0:f0f40dddc0c4 550 wait_us(SPI_WAIT_US);
yuki0701 0:f0f40dddc0c4 551 spi.write(dataA);
yuki0701 0:f0f40dddc0c4 552 wait_us(SPI_WAIT_US);
yuki0701 0:f0f40dddc0c4 553 (DigitalOut)(*DAC_cs)=1;
yuki0701 0:f0f40dddc0c4 554 wait_us(SPI_WAIT_US);
yuki0701 0:f0f40dddc0c4 555
yuki0701 0:f0f40dddc0c4 556 //Bの出力設定
yuki0701 0:f0f40dddc0c4 557 (DigitalOut)(*DAC_cs)=0;
yuki0701 0:f0f40dddc0c4 558 wait_us(SPI_WAIT_US);
yuki0701 0:f0f40dddc0c4 559 spi.write(dataB);
yuki0701 0:f0f40dddc0c4 560 wait_us(SPI_WAIT_US);
yuki0701 0:f0f40dddc0c4 561 (DigitalOut)(*DAC_cs)=1;
yuki0701 0:f0f40dddc0c4 562
yuki0701 0:f0f40dddc0c4 563 }
yuki0701 0:f0f40dddc0c4 564
yuki0701 0:f0f40dddc0c4 565 void MotorControl(int16_t val_md1, int16_t val_md2, int16_t val_md3, int16_t val_md4) //出力
yuki0701 0:f0f40dddc0c4 566 {
yuki0701 0:f0f40dddc0c4 567 static int16_t zero_check;
yuki0701 0:f0f40dddc0c4 568
yuki0701 0:f0f40dddc0c4 569 DAC_Write(val_md1, &ss_md1);
yuki0701 0:f0f40dddc0c4 570 DAC_Write(val_md2, &ss_md2);
yuki0701 0:f0f40dddc0c4 571 DAC_Write(val_md3, &ss_md3);
yuki0701 0:f0f40dddc0c4 572 DAC_Write(val_md4, &ss_md4);
yuki0701 0:f0f40dddc0c4 573
yuki0701 0:f0f40dddc0c4 574 zero_check = (val_md1 | val_md2 | val_md3 | val_md4); //すべての出力が0なら強制停止
yuki0701 0:f0f40dddc0c4 575 if(zero_check == 0) {
yuki0701 0:f0f40dddc0c4 576 md_stop = 1;
yuki0701 0:f0f40dddc0c4 577 md_stop_led = 1;
yuki0701 0:f0f40dddc0c4 578 } else {
yuki0701 0:f0f40dddc0c4 579 md_stop = 0;
yuki0701 0:f0f40dddc0c4 580 md_stop_led = 0;
yuki0701 0:f0f40dddc0c4 581 }
yuki0701 0:f0f40dddc0c4 582 }
yuki0701 0:f0f40dddc0c4 583
yuki0701 0:f0f40dddc0c4 584 #ifdef DEBUG_MODE
yuki0701 0:f0f40dddc0c4 585 void Debug_Control()
yuki0701 0:f0f40dddc0c4 586 {
yuki0701 0:f0f40dddc0c4 587 static char pc_command = '\0';
yuki0701 0:f0f40dddc0c4 588
yuki0701 0:f0f40dddc0c4 589 pc_command = pc.getc();
yuki0701 0:f0f40dddc0c4 590
yuki0701 0:f0f40dddc0c4 591 if(pc_command == 'w') { //前進
yuki0701 0:f0f40dddc0c4 592 m1+=500;
yuki0701 0:f0f40dddc0c4 593 m2+=500;
yuki0701 0:f0f40dddc0c4 594 m3-=500;
yuki0701 0:f0f40dddc0c4 595 m4-=500;
yuki0701 0:f0f40dddc0c4 596 } else if(pc_command == 's') { //後進
yuki0701 0:f0f40dddc0c4 597 m1-=500;
yuki0701 0:f0f40dddc0c4 598 m2-=500;
yuki0701 0:f0f40dddc0c4 599 m3+=500;
yuki0701 0:f0f40dddc0c4 600 m4+=500;
yuki0701 0:f0f40dddc0c4 601 } else if(pc_command == 'd') { //右回り
yuki0701 0:f0f40dddc0c4 602 m1+=500;
yuki0701 0:f0f40dddc0c4 603 m2+=500;
yuki0701 0:f0f40dddc0c4 604 m3+=500;
yuki0701 0:f0f40dddc0c4 605 m4+=500;
yuki0701 0:f0f40dddc0c4 606 } else if(pc_command == 'a') { //左回り
yuki0701 0:f0f40dddc0c4 607 m1-=500;
yuki0701 0:f0f40dddc0c4 608 m2-=500;
yuki0701 0:f0f40dddc0c4 609 m3-=500;
yuki0701 0:f0f40dddc0c4 610 m4-=500;
yuki0701 0:f0f40dddc0c4 611 } else {
yuki0701 0:f0f40dddc0c4 612 m1=0;
yuki0701 0:f0f40dddc0c4 613 m2=0;
yuki0701 0:f0f40dddc0c4 614 m3=0;
yuki0701 0:f0f40dddc0c4 615 m4=0;
yuki0701 0:f0f40dddc0c4 616 }
yuki0701 0:f0f40dddc0c4 617
yuki0701 0:f0f40dddc0c4 618 if(m1>4095) { //最大値を超えないように
yuki0701 0:f0f40dddc0c4 619 m1=4095;
yuki0701 0:f0f40dddc0c4 620 } else if(m1<-4095) {
yuki0701 0:f0f40dddc0c4 621 m1=-4095;
yuki0701 0:f0f40dddc0c4 622 }
yuki0701 0:f0f40dddc0c4 623 if(m2>4095) {
yuki0701 0:f0f40dddc0c4 624 m2=4095;
yuki0701 0:f0f40dddc0c4 625 } else if(m2<-4095) {
yuki0701 0:f0f40dddc0c4 626 m2=-4095;
yuki0701 0:f0f40dddc0c4 627 }
yuki0701 0:f0f40dddc0c4 628 if(m3>4095) {
yuki0701 0:f0f40dddc0c4 629 m3=4095;
yuki0701 0:f0f40dddc0c4 630 } else if(m3<-4095) {
yuki0701 0:f0f40dddc0c4 631 m3=-4095;
yuki0701 0:f0f40dddc0c4 632 }
yuki0701 0:f0f40dddc0c4 633 if(m4>4095) {
yuki0701 0:f0f40dddc0c4 634 m4=4095;
yuki0701 0:f0f40dddc0c4 635 } else if(m4<-4095) {
yuki0701 0:f0f40dddc0c4 636 m4=-4095;
yuki0701 0:f0f40dddc0c4 637 }
yuki0701 0:f0f40dddc0c4 638
yuki0701 0:f0f40dddc0c4 639 debug_printf("%d %d %d %d\r\n",m1,m2,m3,m4);
yuki0701 0:f0f40dddc0c4 640 MotorControl(m1,m2,m3,m4);
yuki0701 0:f0f40dddc0c4 641 pc_command = '\0';
yuki0701 0:f0f40dddc0c4 642 }
yuki0701 0:f0f40dddc0c4 643 #endif
yuki0701 0:f0f40dddc0c4 644
yuki0701 0:f0f40dddc0c4 645 #ifdef DEBUG_PRINT
yuki0701 0:f0f40dddc0c4 646 void debug_printf(const char* format,...)
yuki0701 0:f0f40dddc0c4 647 {
yuki0701 0:f0f40dddc0c4 648 va_list arg;
yuki0701 0:f0f40dddc0c4 649 va_start(arg, format);
yuki0701 0:f0f40dddc0c4 650 vprintf(format, arg);
yuki0701 0:f0f40dddc0c4 651 va_end(arg);
yuki0701 0:f0f40dddc0c4 652 }
yuki0701 0:f0f40dddc0c4 653 #endif