开源视觉导航飞行平台
硬件 Hardware
- Raspberry Pi 3b+
- RPi Camera (G), Fisheye Lens
- Pixhawk
- FS-i6
- PC Desktop
软件 Software
实验步骤
-
下载树莓派镜像,然后用Etcher烧录到SD
-
用
camera_calibration
标定鱼眼相机,标定结果:image_width: 320 image_height: 240 camera_name: raspicam camera_matrix: rows: 3 cols: 3 data: [165.234351, 0.000000, 160.874331, 0.000000, 164.607285, 117.146707, 0.000000, 0.000000, 1.000000] distortion_model: plumb_bob distortion_coefficients: rows: 1 cols: 5 data: [-0.295531, 0.070424, -0.000707, -0.000872, 0.000000] rectification_matrix: rows: 3 cols: 3 data: [1.000000, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000, 0.000000, 0.000000, 1.000000] projection_matrix: rows: 3 cols: 4 data: [119.307640, 0.000000, 160.228617, 0.000000, 0.000000, 132.523483, 115.096171, 0.000000, 0.000000, 0.000000, 1.000000, 0.000000]
-
用地面站给飞控刷
px4fmu-v2_lpe.px4
固件 -
用地面站配置飞控参数
Flight Controller Setup: * LPE_FUSION = 28 * ATT_W_MAG = 0 * ATT_W_EXT_HDG = 0.5 * ATT_EXT_HDG_M = 2 * LPE_VIS_DELAY = 0 * LPE_VIS_XY = 0.1 * LPE_VIS_Z = 0.15 * COM_DISARM_LAND = 1 * LNDMC_ROT_MAX = 45 * LNDMC_THR_RANGE = 0.5 * LNDMC_Z_VEL_MAX = 1
-
校准飞控、遥控器
-
设置遥控器5通道(SWC)、6通道(SWA)KILL SWITCH——用于紧急停止所有电机!
-
打印地图
-
先用 FS-i6 遥控器测试效果
-
再运行基于
OFFBOARD
模式下的脚本test.py
import rospy import time from clever import srv from std_srvs.srv import Trigger rospy.init_node('foo') navigate = rospy.ServiceProxy('navigate', srv.Navigate) land = rospy.ServiceProxy('land', Trigger) navigate(x=0.0, y=0.0, z=1.0, speed=0.5, frame_id='fcu_horiz', update_frame = False, auto_arm=True) time.sleep(2) navigate(x=0.5, y=0.5, z=1.0, speed=0.5, frame_id='aruco_map', update_frame = True, auto_arm=False) time.sleep(3) navigate(x=0.5, y=0.5, z=2.0, speed=0.5, frame_id='aruco_map', update_frame = True, auto_arm=False) time.sleep(3) navigate(x=0.0, y=0.0, z=2.0, speed=0.5, frame_id='aruco_map', update_frame = True, auto_arm=False) time.sleep(3) navigate(x=0.5, y=0.5, z=1.0, speed=0.5, frame_id='aruco_map', update_frame = True, auto_arm=False) time.sleep(3) land()
Tips
- 用浏览器查看地图 192.168.11.1:8080/snapshot?topic=/aruco_pose/map_image
- 运行
test.py
前需要保证相机初始状态正对ArUco地图,否则可能导致无法起飞,并提示错误message: "No local position"
。
飞行机器人学习资料
- Autonomous Navigation for Flying Robots
- Micro Aerial Vehicles (MAVs)
- tum_ardrone
- Robotics: Dynamics and Control
- Robotics and Perception Group
- Control and Robotic Systems (CRS)
- Fall 2018 - Vision Algorithms for Mobile Robotics
- World’s Smartest Precision Landing Solution
- Track and control a drone using ArUco markers and an Arduino
- Autonomous hovering of a Crazyflie 2.0 using ArUco markers
- A ROS package offering autonomous flying with a quadrocopter using ArUco markers