使用PMW3901和VL53L1X 实现室内定点悬停

实现定点悬停,需要两个方向的传感器,水平方向和垂直方向。通常使用GPS进行水平方向定位,气压计进行垂直方向定位。但是因为室内没有GPS信号,所以水平方向需要使用光流传感器替代。

使用PMW3901 光流传感器进行水平方向定位

PX4源代码里已经有PMW3901的驱动程序,重新编译PX4源代码后就可以直接使用,无需另外开发,所以我们使用PMW3901替代GPS进行室内的水平定位。

Pixhawk连接PMW3901传感器

PixHawk和PMW3901传感器的接线如下:

Pixhawk SPI 接口 (从左到右)PMW3901 光流传感器
VCCVCC
SCKCLK
MISOMISO
MOSIMOSI
CS1无需连接
CS2CS
GNDGND

PX4源代码加入PMW3901驱动后重新编译

  1. Pixhawk飞控要求,使用光流传感器模块,需要Pixhawk支持2M内存,早期的Pixhawk 1仅有1M内存,Pixhawk 2以后的版本都有2M内存。
  2. 开发环境准备 ,准备一台装有Ubuntu Linux LTS 18.04 (Bionic Beaver)操作系统的PC。
    我们使用PX4 1.11版本的源代码。
下载PX4源代码
$ cd ~/
$ git clone https://github.com/PX4/PX4-Autopilot.git --recursive
$ git submodule update --init --recursive
$ git checkout v1.11.3
$ make distclean

执行开发环境初始化脚本
$ bash ./PX4-Autopilot/Tools/setup/ubuntu.sh

检查是否初始化成功
$ arm-none-eabi-gcc --version

有如下显示,表示初始化成功
 arm-none-eabi-gcc (GNU Tools for Arm Embedded Processors 7-2017-q4-major) 7.2.1 20170904 (release) [ARM/embedded-7-branch revision 255204]
 Copyright (C) 2017 Free Software Foundation, Inc.
 This is free software; see the source for copying conditions.  There is NO
 warranty; not even for MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.

重启PC,完成初始化。
重启后安装ROS。注意一下,raw.githubusercontent.com 需要翻墙才能访问到。

下载安装脚本
$ wget https://raw.githubusercontent.com/PX4/Devguide/master/build_scripts/ubuntu_sim_ros_melodic.sh

执行脚本
$ bash ubuntu_sim_ros_melodic.sh

把PMW3901模块的驱动加入到代码编译中。

打开 fmu-v3中的default.cmake配置文件
$ cd ~/PX4-Autopilot/boards/px4/fmu-v3/
$ vim default.cmake

找到DRIVES下面的optical_flow,把这行前面的#去掉,并且修改为optical_flow/pmw3901

DRIVERS
		#optical_flow # all available optical flow drivers
		optical_flow/pmw3901
  1. 编译代码并更新飞控固件
在PC开发机上
$ cd ~/PX4-Autopilot
$ make px4_fmu-v3_default

使用USB连接PC开发机到PixHawk飞控
$ make px4_fmu-v4_default upload

有如下显示表示,固件更新成功
Erase  : [====================] 100.0%
Program: [====================] 100.0%
Verify : [====================] 100.0%
Rebooting.

[100%] Built target upload

编译中可能会遇到的错误以及解决方案

  • 一般的错误,可以尝试清理环境后重新编译
$ cd ~/PX4-Autopilot
$ git submodule update --recursive
$ make distclean
$ make px4_fmu-v3_default
$ make px4_fmu-v4_default upload

QGroundControl中的配置

使用QGroundControl连接PixHawk飞控,并且修改飞控参数。

  • 修改SENS_EN_PMW3901为1,使传感器可用
  • 修改 EKF2_AID_MASK为3,当GPS不可用时,自动使用PMW3901光流传感器进行水平位置定位
  • 修改SENS_FLOW_ROT,根据传感器的水平方向相对于飞控的角度,传感器垂直方向向下
  • 修改EKF2_OF_POS_X,EKF2_OF_POS_Y,EKF2_OF_POS_Z的参数,根据传感器相对于飞行器重心的位置

重启飞控使参数生效

使用气压计和VL53L1X进行垂直方向定位

  1. PixHawk飞控自带气压计,不用单独设置,我们只需要增加VL53L1X模块即可,VL53L1X垂直向下安装
  2. 修改 fmu-v3中的default.cmake配置文件
打开 fmu-v3中的default.cmake配置文件
$ cd ~/PX4-Autopilot/boards/px4/fmu-v3/
$ vim default.cmake

找到DRIVES下面的distance_sensor,把这行前面的#去掉,并且修改为distance_sensor/VL53L1X

DRIVERS
		#distance_sensor # all available distance sensor drivers
		distance_sensor/VL53L1X

重新编译,并且更新PixHawk的固件

在PC开发机上
$ cd ~/PX4-Autopilot
$ make px4_fmu-v3_default

使用USB连接PC开发机到PixHawk飞控
$ make px4_fmu-v4_default upload

有如下显示表示,固件更新成功
Erase  : [====================] 100.0%
Program: [====================] 100.0%
Verify : [====================] 100.0%
Rebooting.

[100%] Built target upload
  1. 使用QGroundControl连接PixHawk飞控,并且修改飞控参数。

修改参数SENS_EN_VL53L1X为1,使VL53L1X可用。
修改参数EKF2_HGT_MODE为0,EKF2_RNG_AID为enable,表示同时使用气压计和距离传感器VL53L1X测量垂直距离。

重启飞控使参数生效

使用QGroundControl调试

上述参数修改完成后,在QGroundControl中打开 Analyze | MAVLink Inspector 就可以看到光流传感器PMW3901和距离传感器VL53L1X的数据。

  • 5
    点赞
  • 21
    收藏
    觉得还不错? 一键收藏
  • 9
    评论
pmw3901是一款光流传感器,适用于机器人、无人机等应用中的姿态估计和导航。它能够通过感知周围环境中的光流变化来计算出自身的运动状态。 在使用stm32进行pmw3901的开发过程中,一般需要进行以下几个步骤: 1. 硬件连接: 首先,将pmw3901与stm32芯片进行连接。pmw3901一般通过SPI接口与stm32进行通信,因此需要将其MISO、MOSI、SCK、CS等引脚与stm32相连。此外,还需要为pmw3901提供适当的电源供电。 2. 驱动程序: 接下来,需要编写相应的驱动程序实现pmw3901的通信。可以使用stm32提供的SPI库函数来进行SPI通信,通过读写寄存器来配置pmw3901的参数和获取传感器数据。根据pmw3901的数据手册和官方提供的驱动代码,可以实现pmw3901的基本控制和数据读取。 3. 数据处理: 获取到pmw3901传感器的数据后,需要对其进行处理和解析。根据pmw3901的数据格式和数据手册中的说明,可以计算出光流的位移和速度等信息。可以使用滤波算法对数据进行平滑处理,以提高精度和稳定性。 4. 应用开发: 最后,根据具体的应用需求,可以将pmw3901的数据应用到相应的算法或控制中。比如,在机器人导航中,可以使用pmw3901的数据来实现姿态估计和位置控制,从而实现自主导航。 以上是使用stm32进行pmw3901开发的基本步骤。在实际开发过程中,还需要根据具体情况进行调试和优化。同时,也可以参考其他开源项目或社区中的相关资源来加快开发进度。

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 9
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值