3

阿木币

0

精华

183 小时

在线时间

技术大V

Rank: 4

发表于 2020-12-2 09:41:46 5849 浏览 1 回复

[入门教程] Ardupilot中的串口调试以及example学习

本帖最后由 chasing 于 2020-12-2 09:42 编辑

Ardupilot代码提供了丰富的学习历程,方便新手入门。官方网站已经给出了具体的实验步骤,我这里只是重复做了一下。
首先,可以通过  `./waf list|grep 'examples'` 查看对应的examples都有哪些。然后将对应的example 编译到板子之中即可。执行指令如下:


  1. ./waf configure --board=Pixhawk1
  2. ./waf build --target examples/UART_test --upload
复制代码

也可以通过sitl的方式来查看,具体如下:


  1. ./waf configure --board=sitl
  2. ./waf build --target examples/UART_test
复制代码

如果是sitl则可以直接执行查看结果,操作如下:


  1. ./build/sitl/example/UART_test -M heli -C

复制代码

注:
1. ardupilot中的串口设备是和bootloader中的serial顺序相关的,按照bootloader中顺序给定串口serial 1,2,3(程序中给的是uart A,B ,C ,D)
2. 在每个机型的文件里面都有一个wscript文件,里面包含有编译时候需要编译的文件内容。例如 `/ardupilot/Arudcopter/wscript`

下面给出一个示例程序:


  1. #include <AP_HAL/AP_HAL.h>

  2. void setup();
  3. void loop();

  4. const AP_HAL::HAL& hal= AP_HAL::get_HAL();

  5. static void uart_setup(AP_HAL::UARTDriver *uart, const char *name)
  6. {
  7.     if(uart ==nullptr)
  8.     {
  9.         return;
  10.     }
  11.     uart->begin(57600);
  12. }

  13. void setup()
  14. {
  15.     hal.scheduler->delay(1000);
  16.     uart_setup(hal.uartA,"helloA");
  17.     uart_setup(hal.uartB,"helloB");
  18.     uart_setup(hal.uartC,"helloC");

  19. }

  20. static void uart_test(AP_HAL::UARTDriver *uart, const char* name)
  21. {
  22.     if(uart == nullptr)
  23.     {
  24.         return;
  25.     }
  26.     uart->printf("%s at the time %.3f\n", name, AP_HAL::millis()*0.001f);

  27. }

  28. void loop()
  29. {
  30.     hal.scheduler->delay(300);
  31.     uart_test(hal.uartA,"helloA");
  32.     uart_test(hal.uartB,"helloB");
  33.     uart_test(hal.uartC,"helloC");
  34. }
  35. AP_HAL_MAIN();
复制代码

程序运行结果如下图所示:

                               
登录/注册后可看大图




扫一扫浏览分享
回复

使用道具 举报

578

阿木币

1

精华

1451 小时

在线时间

管理员

Rank: 9Rank: 9Rank: 9

发表于 2020-12-2 10:08:00
回复

使用道具 举报

返回列表
您需要登录后才可以回帖 登录 | 立即注册

本版积分规则

快速回复 返回顶部 返回列表