春ロボ1班(元F3RC4班+) / Mbed 2 deprecated harurobo_main_ver4

Dependencies:   mbed EC PathFollowing-ver10 CruizCore_R1370P

main.cpp

Committer:
yuki0701
Date:
2018-12-01
Revision:
6:14cb400f99f7
Parent:
5:7493649d098b
Child:
7:e269985951bf

File content as of revision 6:14cb400f99f7:

#include "mbed.h"
#include "EC.h"
#include "R1370P.h"
#include "move4wheel.h"
#include "PathFollowing.h"
#include <stdarg.h>

#define PI 3.141592

#define DEBUG_MODE                              // compile as debug mode (comment out if you don't use)
#ifdef DEBUG_MODE
#define DEBUG_PRINT                             // enable debug_printf
#endif

Serial pc(USBTX,USBRX);
void debug_printf(const char* format,...);      // work as printf in debug
void Debug_Control();                           // control by PC keybord

#define SPI_FREQ    1000000         // 1MHz
#define SPI_BITS    16
#define SPI_MODE    0
#define SPI_WAIT_US 1               // 1us
//SPI spi(PB_5,PB_4,PB_3); //Nucleo
SPI spi(p5,p6,p7);  //mbed

/*DigitalOut ss_md1(PB_15);           //エスコンの設定
DigitalOut ss_md2(PB_14);
DigitalOut ss_md3(PB_13);
DigitalOut ss_md4(PC_4);

DigitalOut md_enable(PA_13);        // do all motor driver enable
//DigitalIn md_ch_enable(p10);        // check enable switch is open or close
//Timer md_disable;
DigitalOut md_stop(PA_14);          // stop all motor
DigitalIn  md_check(PB_7);           // check error of all motor driver  //とりあえず使わない*/

DigitalOut ss_md1(p15);           //エスコンの設定
DigitalOut ss_md2(p16);
DigitalOut ss_md3(p17);
DigitalOut ss_md4(p18);

DigitalOut md_enable(p25);
//Timer md_disable;
DigitalOut md_stop(p24);          // stop all motor
DigitalIn  md_check(p23);           // check error of all motor driver  //とりあえず使わない


/*モーターの配置
*     md1//---F---\\md4
*        |         |
*        L    +    R
*        |         |
*     md2\\---B---//md3
*/


//Ec EC1(PC_6,PC_8,NC,500,0.05);
//Ec EC2(PB_1,PB_12,NC,500,0.05);  //Nucleo

Ec EC1(p21,p22,NC,500,0.05);
Ec EC2(p8,p26,NC,500,0.05); //←mbad
Ticker motor_tick;  //角速度計算用ticker
Ticker ticker;  //for enc

//R1370P gyro(PC_6,PC_7);  //ジャイロ
R1370P gyro(p28,p27);

//DigitalOut can_led(LED1);           //if can enable -> toggle
DigitalOut debug_led(LED2);         //if debugmode -> on
DigitalOut md_stop_led(LED3);       //if motor stop -> on
DigitalOut md_err_led(LED4);        //if driver error -> on  //とりあえず使わない

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;//出力値

static int16_t m1=0, m2=0, m3=0, m4=0;  //int16bit = int2byte

///////////////////////////////////////////////////関数のプロトタイプ宣言////////////////////////////////////////////////////
void UserLoopSetting();             // initialize setting
void DAC_Write(int16_t data, DigitalOut* DAC_cs);
void MotorControl(int16_t val_md1, int16_t val_md2, int16_t val_md3, int16_t val_md4);

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最小が1になるような補正(?)//絶対値が一番でかいやつで除算//double Max(0~1)
//マクソンは-4095~4095だからMax=4095にする//最速スピードを出すための関数になってる
{
    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));
}

void calc_xy()
{
    now_angle=gyro.getAngle();  //ジャイロの値読み込み

    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);  //微小時間毎の座標変化
    now_x=now_x+d_x;
    now_y=now_y-d_y;  //微小時間毎に座標に加算

}

//ここからそれぞれのプログラム//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//now_x(現在のx座標),now_y(現在のy座標),now_angle(機体角度(ラジアンではない)(0~360や-180~180とは限らない))(反時計回りが正)
//ジャイロの出力は角度だが三角関数はラジアンとして計算する
//通常の移動+座標のずれ補正+機体の角度補正(+必要に応じさらに別補正)
//ジャイロの仕様上、角度補正をするときに計算式内で角度はそのままよりsinをとったほうがいいかもね

void purecurve(int type,double X,double Y,double r,int theta,double speed/*,double v*/)
{
//正面を変えずに円弧を描いて90°曲がる
//X=円弧の中心座標、Y=円弧の中心座標、r=円弧の半径、theta=plotの間隔(0~90°)、v=目標速度

    int s;
    int t = 0;
    double plotx[(90/theta)+1];  //円弧にとるplotのx座標
    double ploty[(90/theta)+1];
    //double plotvx[(90/theta)+1];  //各plotにおける速度
    //double plotvy[(90/theta)+1];

    double x_out,y_out,r_out;

    switch(type) {
        case 1://↑から→

            for(s=0; s<((90/theta)+1); s++) {
                plotx[s] = X + r * cos(PI - s * (PI*theta/180));
                ploty[s] = Y + r * sin(PI - s * (PI*theta/180));
                //plotvx[s] = -v * cos(PI - s * (PI*theta/180));
                //plotvy[s] = v * sin(PI - s * (PI*theta/180));
                debug_printf("plotx[%d]=%f ploty[%d]=%f\n\r",s,plotx[s],s,ploty[s]);
            }

            while(1) {
                now_angle=gyro.getAngle();  //ジャイロの値読み込み

                calc_xy();

                XYRmotorout(1,plotx[t],ploty[t],plotx[t+1],ploty[t+1],&x_out,&y_out,&r_out);
                CalMotorOut(x_out,y_out,r_out);  //move4wheel内のモーター番号定義または成分分解が違うかも?
                //CalMotorOut(plotvx[t], plotvy[t],0);

                //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);
                //debug_printf("t=%d (0)=%f (1)=%f (2)=%f (3)=%f\n\r",t,GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3));

                base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),1000);  //m1~m4に代入

                if(((plotx[t+1] - now_x)*(plotx[t+1] - plotx[t]) + (ploty[t+1] - now_y)*(ploty[t+1] - ploty[t])) < 0)t++;
                if(t == (90/theta))break;

                MotorControl(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);

            }

        case 2://↑から←  //まだ編集してない

            for(s=0; s<((90/theta)+1); s++) {
                plotx[s] = X + r * cos(s * (PI*theta/180));
                ploty[s] = Y + r * sin(s * (PI*theta/180));
            }

            while(1) {

                now_angle=gyro.getAngle();  //ジャイロの値読み込み

                calc_xy();

                XYRmotorout(1,plotx[t],ploty[t],plotx[t+1],ploty[t+1],&x_out,&y_out,&r_out);
                CalMotorOut(x_out,y_out,r_out);
                base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),1000);
                if(((plotx[t+1] - now_x)*(plotx[t+1] - plotx[t]) + (ploty[t+1] - now_y)*(ploty[t+1] - ploty[t])) < 0)t++;
                if(t == (90/theta))break;

                MotorControl(m1,m2,m3,m4);
            }
    }
}

void purecurve2(int type,double point_x1,double point_y1,double point_x2,double point_y2,int theta/*,double speed,double v*/)
{
//正面を変えずに円弧を描いて90°曲がる
//point_x1,point_y1=出発地点の座標  point_x2,point_x2=目標地点の座標,theta=plotの間隔(0~90°)、v=目標速度
//type:動きの種類(8パターン)

    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 plotvx[(90/theta)+1];  //各plotにおける速度
    //double plotvy[(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) {
        //now_angle=gyro.getAngle();  //ジャイロの値読み込み

        calc_xy();

        XYRmotorout(1,plotx[t],ploty[t],plotx[t+1],ploty[t+1],&x_out,&y_out,&r_out);
        CalMotorOut(x_out,y_out,r_out);  //move4wheel内のモーター番号定義または成分分解が違うかも?
        //CalMotorOut(plotvx[t], plotvy[t],0);

        //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);
        //debug_printf("t=%d (0)=%f (1)=%f (2)=%f (3)=%f\n\r",t,GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3));

        base(GetMotorOut(0),GetMotorOut(1),GetMotorOut(2),GetMotorOut(3),1000);  //m1~m4に代入

        if(((plotx[t+1] - now_x)*(plotx[t+1] - plotx[t]) + (ploty[t+1] - now_y)*(ploty[t+1] - ploty[t])) < 0)t++;
        if(t == (90/theta))break;

        MotorControl(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);

    }
}




void gogo_straight(int type, double x1_point,double y1_point,double x2_point,double y2_point)   //直線運動プログラム(引数:type→(1:減速なし/2:減速あり)、出発地点の座標(x,y)、目標地点の座標(x,y))
{
    while (1) {

        //now_angle=gyro.getAngle();

        calc_xy();
        printf("x = %f, y = %f, angle = %f\r\n",now_x,now_y,now_angle);


        //Debug_Control();
        XYRmotorout(type,x1_point,y1_point,x2_point,y2_point,&x_out,&y_out,&r_out);
        //printf("x=%lf, y=%lf, r=%lf",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),1000);
        //printf("m1=%d, m2=%d, m3=%d, m4=%d\r\n",m1,m2,m3,m4);
        MotorControl(m1,m2,m3,m4);



        if(((x2_point - now_x)*(x2_point - x1_point) + (y2_point - now_y)*(y2_point - y1_point)) < 0) break;

    }

    MotorControl(0,0,0,0);
}

void go_straight(int type,double goal_x,double goal_y,double speed,double front)   //移動パターン(1,2,3,4)、目標X、目標Y、最高速度(0~1)、正面角度
{
    double y_hosei=(now_y-goal_y)*0.001;//Y座標(mm単位)にP処理
    double x_hosei=(now_x-goal_x)*0.001;//X座標(mm単位)にP処理
    double incl_hosei=sin(now_angle-front)*(PI/180)*0.1;//機体角度(sin(数度→ラジアンに変換))にP処理

    switch(type) {
        case 1://Y座標一定の正方向横移動
            while(now_x<goal_x) {
                base(-1-y_hosei-incl_hosei,-1+y_hosei-incl_hosei,1+y_hosei-incl_hosei,1-y_hosei-incl_hosei,speed);
            }
            break;

        case 2://Y座標一定の負方向横移動
            while(now_x>goal_x) {
                base(1-y_hosei-incl_hosei,1+y_hosei-incl_hosei,-1+y_hosei-incl_hosei,-1-y_hosei-incl_hosei,speed);
            }
            break;

        case 3://Y座標一定の正方向横移動
            while(now_y<goal_y) {
                base(1+x_hosei-incl_hosei,-1+x_hosei-incl_hosei,-1-x_hosei-incl_hosei,1-x_hosei-incl_hosei,speed);
            }
            break;

        case 4://X座標一定の負方向横移動
            while(now_y>goal_y) {
                base(-1+x_hosei-incl_hosei,1+x_hosei-incl_hosei,1-x_hosei-incl_hosei,-1-x_hosei-incl_hosei,speed);
            }
            break;
    }
}



//////////////////////////////////////////////////////////////以下main文////////////////////////////////////////////////////////////////////////

int main()
{
    UserLoopSetting();

    void reset();
    EC1.reset();
    EC2.reset();

    now_x=start_x;
    now_y=start_y;

    /*set_target_angle(0);
    purecurve2(1,0,0,1000,1000,9);
    MotorControl(0,0,0,0);*/

    /*  set_target_angle(0);
        while(1){
        purecurve2(7,0,0,500,-500,9);
        MotorControl(0,0,0,0);
        purecurve2(1,500,-500,1000,0,9);
        MotorControl(0,0,0,0);
        purecurve2(3,1000,0,500,500,9);
        MotorControl(0,0,0,0);
        purecurve2(5,500,500,0,0,9);
        MotorControl(0,0,0,0);
    }*/

   int a=0;
    while(1) {
        set_target_angle(a);
        gogo_straight(2,0,0,0,-1500);
        MotorControl(0,0,0,0);
        wait(1);

        a=a+90;

        set_target_angle(a);
        gogo_straight(2,0,-1500,0,0);
        MotorControl(0,0,0,0);
        wait(1);

        a=a+90;

    }

}
///////////////////////////////////////////////////////////////////////以下マクソン関連///////////////////////////////////////////////////////////////////////////

void UserLoopSetting()
{
//-----エスコンの初期設定-----//
    spi.format(SPI_BITS, SPI_MODE);
    spi.frequency(SPI_FREQ);
    ss_md1 = 1;
    ss_md2 = 1;
    ss_md3 = 1;
    ss_md4 = 1;
    md_enable = 1;  //enable on
    md_err_led = 0;
    md_stop = 1;
    md_stop_led = 1;
//-----センサーの初期設定-----//
    gyro.initialize();
    motor_tick.attach(&calOmega,0.05);  //0.05秒間隔で角速度を計算
    EC1.setDiameter_mm(48);
    EC2.setDiameter_mm(48);  //測定輪半径
//-----PathFollowingのパラメーター設定-----//
    set_p_out(800);  //ベクトルABに平行方向の出力値設定関数(カーブを曲がる速度)
    q_setPDparam(5,0.1);  //ベクトルABに垂直な方向の誤差を埋めるPD制御のパラメータ設定関数
    r_setPDparam(10,0.1);  //機体角度と目標角度の誤差を埋めるPD制御のパラメータ設定関数
    set_r_out(600);  //旋回時の最大出力値設定関数
    //  set_target_angle(0);  //機体目標角度設定関数

#ifdef DEBUG_MODE
    debug_led = 1;
    pc.attach(Debug_Control, Serial::RxIrq);
#else
    debug_led = 0;
#endif
}

#define MCP4922_AB      (1<<15)
#define MCP4922_BUF     (1<<14)
#define MCP4922_GA      (1<<13)
#define MCP4922_SHDN    (1<<12)

#define MCP4922_SET_OUTA    (0x3000)    //( MCP4922_GA || MCP4922_SHDN )  //12288
#define MCP4922_SET_OUTB    (0xB000)    //( MCP4922_AB || MCP4922_GA || MCP4922_SHDN )  //45056
#define MCP4922_MASKSET     (0x0FFF)    //4095

void DAC_Write(int16_t data, DigitalOut* DAC_cs)   //(出力,出力場所)
{
    static uint16_t dataA;  //送るデータ
    static uint16_t dataB;

    dataA = MCP4922_SET_OUTA;
    dataB = MCP4922_SET_OUTB;

    if(data >= 0) {
        if(data > 4095) {
            data = 4095;
        }
        dataA += (MCP4922_MASKSET & (uint16_t)(data));
    } else {
        if(data < -4095) {
            data = -4095;
        }
        dataB += (MCP4922_MASKSET & (uint16_t)(-data));
    }

    //Aの出力設定
    (DigitalOut)(*DAC_cs)=0;
    wait_us(SPI_WAIT_US);
    spi.write(dataA);
    wait_us(SPI_WAIT_US);
    (DigitalOut)(*DAC_cs)=1;
    wait_us(SPI_WAIT_US);

    //Bの出力設定
    (DigitalOut)(*DAC_cs)=0;
    wait_us(SPI_WAIT_US);
    spi.write(dataB);
    wait_us(SPI_WAIT_US);
    (DigitalOut)(*DAC_cs)=1;

}

void MotorControl(int16_t val_md1, int16_t val_md2, int16_t val_md3, int16_t val_md4)   //出力
{
    static int16_t zero_check;

    DAC_Write(val_md1, &ss_md1);
    DAC_Write(val_md2, &ss_md2);
    DAC_Write(val_md3, &ss_md3);
    DAC_Write(val_md4, &ss_md4);

    zero_check = (val_md1 | val_md2 | val_md3 | val_md4);  //すべての出力が0なら強制停止
    if(zero_check == 0) {
        md_stop = 1;
        md_stop_led = 1;
    } else {
        md_stop = 0;
        md_stop_led = 0;
    }
}

#ifdef DEBUG_MODE
void Debug_Control()
{
    static char pc_command = '\0';

    pc_command = pc.getc();

    if(pc_command == 'w') {  //前進
        m1+=500;
        m2+=500;
        m3-=500;
        m4-=500;
    } else if(pc_command == 's') {  //後進
        m1-=500;
        m2-=500;
        m3+=500;
        m4+=500;
    } else if(pc_command == 'd') {  //右回り
        m1+=500;
        m2+=500;
        m3+=500;
        m4+=500;
    } else if(pc_command == 'a') {  //左回り
        m1-=500;
        m2-=500;
        m3-=500;
        m4-=500;
    } else {
        m1=0;
        m2=0;
        m3=0;
        m4=0;
    }

    if(m1>4095) {  //最大値を超えないように
        m1=4095;
    } else if(m1<-4095) {
        m1=-4095;
    }
    if(m2>4095) {
        m2=4095;
    } else if(m2<-4095) {
        m2=-4095;
    }
    if(m3>4095) {
        m3=4095;
    } else if(m3<-4095) {
        m3=-4095;
    }
    if(m4>4095) {
        m4=4095;
    } else if(m4<-4095) {
        m4=-4095;
    }

    debug_printf("%d %d %d %d\r\n",m1,m2,m3,m4);
    MotorControl(m1,m2,m3,m4);
    pc_command = '\0';
}
#endif

#ifdef DEBUG_PRINT
void debug_printf(const char* format,...)
{
    va_list arg;
    va_start(arg, format);
    vprintf(format, arg);
    va_end(arg);
}
#endif