【first_try】audupilot串口收发数据

固件版本:ardupilot Plane4.1。
创建一个单独收发数据的线程与函数,直接调用串口来收发数据,非mavlink格式。
实现过程使用SK-100激光测距仪与minipix飞控板进行通信实验。

创建串口收发函数与线程

创建函数:

void Plane::receive_from_serial(void)
{/********************数据发送***********************/
    start_ska100[0]=0xaa;
    start_ska100[1]=0x00;
    start_ska100[2]=0x00;
    start_ska100[3]=0x20;
    start_ska100[4]=0x00;
    start_ska100[5]=0x01;
    start_ska100[6]=0x00;
    start_ska100[7]=0x04;
    start_ska100[8]=0x25;
    if(received_ska100_data)
    {
        hal.serial(2)->write(start_ska100,9);
    }
/**************************************************/


/********************数据接收***********************/
    const uint8_t num_read = hal.serial(2)->read(&serial_try_buffer[try_buffer_used], ARRAY_SIZE(serial_try_buffer)-try_buffer_used);
   
    try_buffer_used += num_read;
   
    if (try_buffer_used == 0) {
        //hal.serial(0)->printf("there no data \n");
        return ;
    }

    if (serial_try_buffer[0] != 0xAA &&
        !find_signature_in_buffer(1)) {
        hal.serial(0)->printf("no buffer_start \n");
        return ;
    }

    if (try_buffer_used < ARRAY_SIZE(serial_try_buffer)) {
        hal.serial(0)->printf("size not correct \n");
        return ;
    }

    uint8_t sum = 0;
    for (uint8_t i=1; i<13; i++) {
        sum += serial_try_buffer[i];
    }
    
    if (serial_try_buffer[13] != sum) {
        find_signature_in_buffer(1);
        hal.serial(0)->printf("sum not correct \n");
        return ;
    }
    
    if(serial_try_buffer[13] == sum && serial_try_buffer[0] == 0xaa)
    {
        received_ska100_data = 0;
        hal.serial(0)->printf("already start ska100!!!\n");
    }

    try_data = serial_try_buffer[6] << 24 | serial_try_buffer[7] << 16 | serial_try_buffer[8] << 8 | serial_try_buffer[9];
    hal.serial(0)->printf("distance from ska100 :   %lu\n",try_data);
    try_buffer_used = 0;
/**************************************************/
}
bool Plane::find_signature_in_buffer(uint8_t start)
{//包头检验函数
    for (uint8_t i=start; i<try_buffer_used; i++) {
        if (serial_try_buffer[i] == 0xAA) {
            memmove(&serial_try_buffer[0], &serial_try_buffer[i], try_buffer_used-i);
            try_buffer_used -= i;
            return true;
        }
    }
    // header byte not in buffer
    try_buffer_used = 0;
    return false;
}

创建线程:

SCHED_TASK(receive_from_serial,    10,    100)

变量定义

plane.h中进行相关变量的定义:

    void receive_from_serial(void);
    bool find_signature_in_buffer(uint8_t start);
    uint8_t serial_try_buffer[13];
    uint8_t try_buffer_used;
    uint32_t try_data;
    bool received_ska100_data = 1; //检测是否收到完整数据,用于停止发送 打开激光测距指令
    uint8_t start_ska100 [9];

添加自定义串口类型

AP_SerialManager.h中添加自定义

SerialProtocol_other_tool = 43

// other serial
#define AP_SERIALMANAGER_other_BUFSIZE_RX     128
#define AP_SERIALMANAGER_other_BUFSIZE_TX     128
#define AP_SERIALMANAGER_other_BAUD           19200

AP_SerialManager.cpp中添加case:

    case SerialProtocol_other_tool:
    //other_serial  baud=115200  zdx_try
         state[i].baud = AP_SERIALMANAGER_other_BAUD  /  1000;
         uart->begin(map_baudrate(state[i].baud),
                                  AP_SERIALMANAGER_other_BUFSIZE_RX,
                                  AP_SERIALMANAGER_other_BUFSIZE_TX);
         hal.serial(0)->printf("serial %d opened\n",i);
         break;

地面站操作

打开地面站,调整相应串口protocol为43,波特率为19200即可。

  • 3
    点赞
  • 11
    收藏
    觉得还不错? 一键收藏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值