受け取り足

Dependencies:   mbed serial_extend

main.cpp

Committer:
bousiya03
Date:
2014-10-05
Revision:
2:7cd9f9cc2376
Parent:
0:f353f2d87281
Child:
3:26ae0e32030d

File content as of revision 2:7cd9f9cc2376:

/*
 * receibes_robot_wheel  by Tomoki Hokida
 *
 * 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 "serial_extend.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 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);

serial_extend xbee(p28,p27);
serial_extend 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};

/* 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++;
}

/*Safety Mode*/
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;

    /*Reception Start*/
    xbee.start_read();
    xbee.read_data(get_data,XBEE_KEY);
    
    /*Send Start*/
    arm_mbed.start_write();
    arm_mbed.write_data(pt_packet->arm,ARM_KEY);
    
    check = 0xFF;

    //int radio_check=0;

    for(;;) {

        /*PWM init*/

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

/*
        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 = packet.leg;


        /* Stop */
        if(packet.leg==0x0) {

            motors = 0x00;
        }

        /* 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();
    }
}