中継機能つけた受け取りオムニ

Dependencies:   mbed MultiSerial

main.cpp

Committer:
bousiya03
Date:
2014-10-04
Revision:
24:37a17b7c6201
Parent:
23:54fddee73c88

File content as of revision 24:37a17b7c6201:

/*
 * 4WD_OMNI_simple  by Tomoki Hokida
 * Simple Type
 *
 * motor pins piar
 * motor(p13,p14):motor(p15,p16)
 * motor(p17,p18):motor(p19,p20)
 *
 * Serial Pins
 * packet.arm[0]:arm
 * packet.leg[1]:omni
 * reset 0
 */

#include "mbed.h"
#include "MultiSerial.h"

#define DATA_NUM 2 //DATA_NUM[byte]通信 この値はmemcpy使ってるんでxbee_packet構造体のメモリ数といい感じに合わせるようにしてください
#define XBEE_KEY 0xAA //keycode
#define ARM_KEY 0xAA

#define PWM 0.5

#define PWM_L 0.5
#define PWM_R 0.5
#define PWM_U 0.5
#define PWM_D 0.5

#define R 0x4
#define L 0x1
#define U 0x2
#define D 0x8

#define R_t 0x10
#define L_t 0x40

#define TIME 0

BusOut check(LED1,LED2,LED3,LED4);
BusOut motors(p13,p14,p15,p16,p17,p18,p19,p20);
PwmOut pwm[4]= {p21,p22,p23,p24};

Serial pc(USBTX,USBRX);

MultiSerial xbee(p28,p27);
MultiSerial arm_mbed(p9,p10);



/* data structure */
typedef struct {

    uint8_t arm[1];
    uint8_t leg;

} xbee_packet;

xbee_packet packet;

uint8_t get_data[DATA_NUM]= {0};

uint8_t check_data[2]={0};

int counter=0;


/* Out put PC stdout function */
void pc_print()
{
    static int count=0;

    if(count==10e3) {
        pc.printf(" arm = %d" ,packet.arm[0]);
        pc.printf(" leg = %d" ,packet.leg);
        count=0;
    }
    count++;
}

uint8_t readable_ratio(){
    
    int check = 0;
    
    for(int i=0;i>=100;i++){
        
        if(xbee.readable_check()==1){check++;}
        
        wait_ms(1.0);        
        }
        
    return check;
    }

void connect_check(void)
{
    xbee.start_read();
    xbee.read_data(check_data,XBEE_KEY);
    
    check = 0x01;    
    
    while(readable_ratio()>=50);
    
    check = 0x03;
    
    while(readable_ratio()<=50);

    check = 0x07;
    
    xbee.stop_read();
    xbee.start_write();

    check_data[0]=0xCC;

    xbee.write_data(check_data,XBEE_KEY);

    wait_ms(10);

    xbee.stop_write();
}

void move_slowly(int count)
{   

        float i=(count/10e3)*PWM; //mirisec -->> sec

        pwm[0] = i;
        pwm[1] = i;
        pwm[2] = i;
        pwm[3] = i;

        //wait_ms(1.0); //count value * 0.01 sec
    
    //check = 0;
}

void safety_mode()
{
    xbee.stop_read();
    arm_mbed.stop_write();
    
    for(;;) {

        motors = 0;

        check = 0xA;
        wait(0.5);
        check != 0xF;
        wait(0.5);

        if(xbee.readable_check()==1) {

            xbee.start_read();
            arm_mbed.start_write();
            return;

        }
    }
}

int main()
{



    xbee_packet *pt_packet=&packet;

    //connect_check();
    
    xbee.start_read();
    xbee.read_data(get_data,XBEE_KEY);
        
    arm_mbed.start_write();
    arm_mbed.write_data(pt_packet->arm,ARM_KEY);
    
    counter=0;
    
    int radio_check=0;

    for(;;) {
        
        if(xbee.readable_check() == 0) {
            
            radio_check++;

            if(radio_check>=500) {
                safety_mode();
            }
        }else{
            
        radio_check = 0;
        
        }
        
        wait_ms(0.5);


        packet.arm[0] = get_data[1];
        packet.leg = get_data[0];

        //check = get_data[1];
        
        check = 0xFF;
        if(packet.leg!=0){
            
            check = packet.leg;
            }

        /* Stop */
    if(packet.leg==0x0) {
            
            for(;counter>=0;counter--){
                
            //if(counter>=0){counter--;} //cunter init
            
            move_slowly(counter);
            wait_ms(0.1);
            
            }           

        }else{

            if(counter<=10e3){
                counter++;
            }
                
            move_slowly(counter);
    }

        /* Direction of movement */
        if(packet.leg&R) motors = 0x55; //01010101 R 接続に気をつけること
        if(packet.leg&L) motors = 0xAA; //10101010 L 多分モータードライバの信号線をそれぞれ逆にすればOKかな
        if(packet.leg&U) motors = 0x5A; //01011010 U
        if(packet.leg&D) motors = 0xA5; //10100101 D

        /* Turn circling */
        if(packet.leg&R_t) motors = 0x66; //01100110
        if(packet.leg&L_t) motors = 0x99; //10011001

        pc_print();
    }
}