Luxonis OAK-D¶
This article explains how to setup a Luxonis OAK-D camera for use with ArduPilot as a substitude for a GPS allowing position control modes like Loiter, PosHold, RTL, Auto to work. This solution is based on HKUST Aerial Robotics Group’s VINS-Fusion and Sara Lucia Contreras Ojeda’s thesis “Robot pose calculation based on Visual Odometry using Optical flow and Depth map”
What to Buy¶
Hardware Setup¶
Connect the OAK-D to one of the RPI’s blue USB3 ports
Connect the RPI’s UART port to autopilot’s Telem1
Software Setup¶
On RPI’s terminal
git clone https://github.com/chobitsfan/VINS-Fusion.git
git checkout -t origin/apm_wiki
#follow instructions in README.md to build
git clone https://github.com/chobitsfan/oak_d_vins_cpp.git
git checkout -t origin/apm_wiki
#follow instructions in README.md to build
git clone https://github.com/chobitsfan/mavlink-udp-proxy.git
git checkout -t origin/apm_wiki
#follow instructions in README.md to build
Configure ArduPilot¶
SERIAL1_PROTOCOL = 2 (MAVLink2).
SERIAL1_BAUD = 1500 (1500000 baud)
VISO_TYPE = 1
VISO_DELAY_MS = 50
EK3_SRC1_POSXY = 6 (ExternalNav)
EK3_SRC1_VELXY = 6 (ExternalNav)
EK3_SRC1_POSZ = 1 (Baro which is safer)
EK3_SRC1_VELZ = 0 (you can set it to 6 if 1st flight test looks good)
EK3_SRC1_YAW = 6 (ExternalNav)
COMPASS_USE = 0, COMPASS_USE2 = 0, COMPASS_USE3 = 0 to disable all compasses
How to run¶
Open 3 terminals on RPI On 1st terminal
cd oak_d_vins_cpp
./feature_tracker
On 2nd terminal
cd VINS-Fusion/vins_estimator
./vins_fusion oak_d.yaml
On 3rd terminal
cd mavlink-udp-proxy
./mavlink_udp
[Optional]Verify pose estimation¶
On a PC with ROS Noetic installed (WSL will do)
git clone https://github.com/chobitsfan/my_udp_ros.git
#follow instructions in README.md to build & run
red = front, green = left and blue = up
Flight Test¶
For your first flight:
Takeoff in Stabilize or Alt-Hold, check that the vehicle is stable.
Move the vehicle around and observe the position on Mission Planner to see if tracking is stable.
Switch to Loiter, but always ready to switch back to Stabilize/Alt-Hold if anything goes awry.
Otherwise, the vehicle should hover stably and able to keep its position.
Move the vehicle around (translate, rotate) at varying speed, always ready to switch back to Stabilize/Alt-Hold.
If everything works as expected, next time you can arm and takeoff in Loiter mode.
EKF3 Source Transitions with OpticalFlow¶
If switching between this and OpticalFlow is desired, see ExternalNAV/Optical Flow Transitions