A VIO system using OAK-D & Raspberry Pi


The goal of this project is to build a small, affordable and easy to setup VIO system which can be carried by small drone. Usually, powerful CPU or GPU is required for a VIO system because of image processing and feature tracking jobs. In this project, I will offload computer vision jobs to OAK-D and let Raspberry Pi focus on pose estimation. It is inspired by Sara Lucia Contreras Ojeda’s thesis “Robot pose calculation based on Visual Odometry using Optical flow and Depth map” and SLAM with OAK from Luxonis web site.

Hardware:
Luxonis OAK-D (I think OAK-D Lite is lighter and cheaper therefore more suitable, but I only got a second-hand OAK-D here)
Raspberry Pi 4

Software
ArduCopter 4.4.4 is used here
Slight modified VINS-Fusion
A small programm processing feature tracking result from OAK-D

Another small program sending VIO data to ardupilot

Hardware wiring

Software architecture

Installation

  1. install depthai-core
  2. install ROS Noetic
  3. clone & build GitHub - chobitsfan/VINS-Fusion at oak_d
  4. clone & build GitHub - chobitsfan/oak_d_vins_cpp
  5. clone & build GitHub - chobitsfan/mavlink-udp-proxy at oak_d

Ardupilot setup
SERIAL1_PROTOCOL 2
SERIAL1_BAUD 1500
EK3_SRC1_POSXY 6
EK3_SRC1_VELXY 6
EK3_SRC1_VELZ 0 (you can set it to 6 after testing result stable enough)
EK3_SRC1_POSZ 1
EK3_SRC1_YAW 6
VISO_TYPE 1
VISO_POS_M_NSE 0.5 (you can lower it after testing result good enough)
VISO_VEL_M_NSE 0.5
VISO_YAW_M_NSE 0.3
VISO_DELAY_MS 60

on Pi 4, Run

  1. roscore
  2. oak_d_vins_cpp/feature_tracker
  3. mavlink-udp-proxy/mavlink_udp
  4. rosrun vins vins_node catkin_ws/src/VINS-Fusion/config/oak_d/conf.yaml

Loiter test flight video

vins-fusion rviz

log
17 2024-2-5 PM 03-57-12.bin

8 Likes

Hi @chobitsfan,

This is great! Thanks so much for sharing the details.

I’ve moved this post to a blog post to increase its visibility. I hope that’s OK.

Thanks again!

2 Likes

Hi @chobitsfan,

Thanks again for this, it’s very interesting. I think maybe we should consider putting this on the wiki as a alternative/replacement for the T265 support we have now that the T265 is no longer available.

One of the key issues of the T265 (and also the ModalAI VOXL) is they can behave very badly when they start losing their position estimate. Any opinions on how this system works when things go wrong?

I guess this uses the distances from the OAK-D camera meaning that it only work well if there are objects that it can track within about 15m or so?

BTW, I have been thinking about how to create a VIO system that works at high altitudes for cases where the GPS is lost. I have been thinking of using a downward facing camera gimbal (the Xacti in particular) and then run an optical flow algorithm (running on an RPI4/5) on the video. The idea of using segmentation or feature tracking to improve the optical flow had also crossed my mind. Any advice is greatly appreciated.

1 Like

Hi @rmackay9

I think maybe we should consider putting this on the wiki as a alternative/replacement for the T265 support we have now that the T265 is no longer available.

Thank you, I will try to improve this post.

One of the key issues of the T265 (and also the ModalAI VOXL) is they can behave very badly when they start losing their position estimate. Any opinions on how this system works when things go wrong?

I think it is due to T265 keep sending pose even when it lost vision feature tracking. I am trying to modify vins-fusion source code to avoid this problem

I guess this uses the distances from the OAK-D camera meaning that it only work well if there are objects that it can track within about 15m or so?

Yes.

BTW, I have been thinking about how to create a VIO system that works at high altitudes

something like VNS01 - Visual Navigation System | UAV Navigation ?

1 Like

Hi @chobitsfan,

Yes, that UAV Navigation system looks like a close source (perhaps non-AP compatible?) version of what I’m thinking of.

It has been directly superseded by the OAK-D-S2 offering more CCM options in a sleaker body. What is your opinion on S2 compatibility with the project?

Have you tried ROS 2 Humble? Any advice on using ROS 2?

What is your opinion on S2 compatibility with the project?

I think it should work with s2 (but I do not have one and therefore not tested)

I am very sorry that I forget to mention that this is based on VINS-Fusion from HKUST Aerial Robotics Group. Thanks a lot for their great work.

Hello @chobitsfan

Great job with the pose estimation, I’ve been following your previous works with VINS-Fusion and ArduCopter. Did you managed to somehow attenuate the episodes of the pose estimation losing track with changes in the source code?

I’m having trouble with eventual inconsistencies when using a Monocular Camera (20Hz) and RAW_IMU from APM at 100Hz. Perhaps the time synchronization or low imu frequency is affecting the system.

Any help/advice would be appreciated

I think maybe we should consider putting this on the wiki as a alternative/replacement for the T265 support we have now that the T265 is no longer available.

Hi @rmackay9 Would you be able to take a look at common: non-gps navigation with Luxonis OAK-D by chobitsfan · Pull Request #5867 · ArduPilot/ardupilot_wiki · GitHub ? Thank you very much

1 Like