室外飞行避障
注意:本教程适用于 Kerloud 600 Vision
室外飞行中的避障能力可以使无人机能够在任务规划期间绕行未预见到的障碍,这是监察和测绘等场景经常需要的功能。该功能是在机载计算机中作为独立软件实现的。 避障的官方库可以在 https://github.com/PX4/PX4-Avoidance 中找到,但由于该库已经很久没有更新,用户直接部署用于实际飞行并不现实。
环境设置
Kerloud 600 Vision配备了 Nvidia Jetson Nano 计算机和 Intel Realsense D435i 摄像头。避障软件预装在工作空间~/src/uav_space/catkinws_avoidance下。出厂期间我们会进行完整的代码测试,以确保整个套件能够正常运行。 支持的操作系统是带有 ROS Melodic 的 Ubuntu 18.04。
避障程序包在dev_kerlouduav分支中交付,因此请确保切换到该分支以避免潜在的软件错误。
如何使用
虚拟仿真测试
虚拟仿真测试只能在个人电脑上进行,不能在机载电脑上运行。 假设px4固件位于~/Firmware,默认版本为v1.10.0,用户可以使用以下命令启动模拟:
# Open a terminal, and build the sitl target for px4 firmware
sudo apt install ros-melodic-gazebo-ros* # necessary for gazebo ros interface
cd ~/Firmware
# This is necessary to prevent some Qt-related errors (feel free to try to omit it)
export QT_X11_NO_MITSHM=1
# Build and run simulation
make px4_sitl_default gazebo
然后可以通过以下方式启动本地规划器:
# open a terminal (terminal 1)
cd ~/src/uav_space/catkinws_avoidance
source devel/setup.bash
# add environment setting
. ~/Firmware/Tools/setup_gazebo.bash ~/Firmware ~/Firmware/build/px4_sitl_default
export ROS_PACKAGE_PATH=${ROS_PACKAGE_PATH}:~/Firmware
roslaunch local_planner local_planner_stereo.launch
# open another terminal to view image (terminal 2)
cd ~/src/uav_space/catkinws_avoidance
source devel/setup.bash
rosrun image_view stereo_view stereo:=/stereo image:=image_rect_color
# open another terminal (terminal 3)
rosrun mavros mavsys mode -c OFFBOARD
rosrun mavros mavsafety arm
然后,用户可以通过按 2D 导航按钮并双击 rviz 界面来设置导航目标。
全局规划器启动和本地规划器启动步骤相类似。
# open a terminal (terminal 1)
cd ~/src/uav_space/catkinws_avoidance
source devel/setup.bash
# add environment setting
. ~/Firmware/Tools/setup_gazebo.bash ~/Firmware ~/Firmware/build/px4_sitl_default
export ROS_PACKAGE_PATH=${ROS_PACKAGE_PATH}:~/Firmware
roslaunch global_planner global_planner_stereo.launch
# open another terminal (terminal 2)
rosrun mavros mavsys mode -c OFFBOARD
rosrun mavros mavsafety arm
Hint
本地规划器是官方指南推荐的,它支持比全局规划器(1.5m/s)更高的速度(3m/s)。