A small VIO system using raspberry pi and arducam ov9281

A low cost VIO system can be carried by a 149mm quad

loiter flight test video and log

guided mode waypoint

@LuckyBird wrote a very good post integrating ardupilot and Intel realsense T265 camera. However with T265 discontinued, we need other VIO solution. The goal of this project is to build a small and low cost VIO system with common hardware.

This project is based on VINS-Mono, it is a real-time SLAM framework for Monocular Visual-Inertial Systems created by HKUST Aerial Robotics Group. Thanks a lot for their great work.

Hardware
Raspberry Pi 4
Arducam OV9281 global shutter camera

Software
Raspberry Pi OS (Bullseye)
ROS Noetic
a slightly modified VINS-Mono
a slightly modified Ardupilot
a slightly modified libcamera-apps
mavlink-udp-proxy

Enable OV9281
add

camera_auto_detect=0
dtoverlay=ov9281

to /boot/config.txt

Connect Pi serial port to FC
add

enable_uart=1
dtoverlay=disable-bt

to /boot/config.txt and sudo systemctl disable hciuart
remove console=serial0,115200 from /boot/cmdline.txt

Ardupilot parameters

SERIALx_BUAD = 921600
VISO_TYPE = 1
VISO_DELAY_MS = 50
EK3_SRC1_POSXY = 6
EK3_SRC1_YAW = 6
EK3_SRC1_VELXY = 6
EK3_SRC1_VELZ = 6

Start VINS-Mono
roslaunch vins_estimator chobits.launch

Start video
libcamera-apps/build/libcamera-hello --viewfinder-mode 640:400:8 --vflip --hflip --framerate 20 -t 0
There is no auto exposure control for ov9281, so you may need to adjust gain

Start mavlink-udp-proxy
just run mavlink_udp

6 Likes

Thanks for this excellent addition to the Visual Inertial Odometry navigation systems.

Are you planning on having the highres imu and time sync messages being merged in master?

I am curious on how you got the IMU parameters characterized into VINS-Mono. Did you used the standard specs or you made the full random walk with Kalibr?

What is the FC you are flying with (actually I am interested to know what is the IMU type that take part of the odometry)?

Best regards

Thank you :slight_smile:

are you planning on having the highres imu being merged in master?

Yes, I will create a PR after more tests done

Did you used the standard specs or you made the full random walk with Kalibr?

Actually, I just use the default values from comments in config file

What is the FC you are flying with (actually I am interested to know what is the IMU type that take part of the odometry)?

Kakute H7 (mpu6000)

1 Like

Very nice job!

Positioning is calculated in real time (latency similar to T265)?

Vins Mono manages to run on Pi compute, so you must have taken the 8GB? Is the computation process as greedy as this for a Pi Compute? Good news if so.

average latency ~ 50ms

Yes, I use pi4 8gb version. top show it cost about half cpu

1 Like

Point cloud generated by vins-mono sending to ego-planner for path planning. Both vins-mono and ego-planner running on pi 4

2 Likes

Hello @chobitsfan

I am planning to test with a Nvidia Xavier NX and based on my experience, there are some incompatibilities between packages. I would appreciate you provide us with the following versions:

  • ROS
  • OpenCV
  • Ceres
  • Eigen

For my tests , I used Eigen 3.3.9 , Ceres 1.14.0 and OpenCV 3.4.12 and had to recompile the ROS NOETIC cv_bridge from source in order to make it work.

Hi @ppoirier

OS: raspbian Debian GNU/Linux 11 (bullseye)
ROS: neotic (I am not sure, apt from Index of /debian, so rosversion -d shows Debian)
OpenCV: 4.5.1 (apt)
Cares: 1.14.0 (build from src)
Eigen: 3.3.9 (apt)

2 Likes

Hello, I’ve reviewed the Ardupilot code modifications you made, where you added the ‘highres_imu’ message to retrieve IMU data from the FCU. I’m curious, why didn’t you utilize the existing ‘raw_imu’ message? The only apparent difference seems to be the timestamp and accelerometer units.

@ppoirier once you test that can you post latency information. I am curious how Nvidia compares to Rpi.

1 Like

raw_imu is scaled & truncated

Why did you mention that the raw_imu accelerometer data is truncated? It’s simply divided by GRAVITY_MSS, converting it to units of ‘g.’ Afterward, the Raspberry Pi can perform the necessary transformations to obtain the original IMU data.

The IMU signal need to be generated from the FC as it provides minimal latency and correct usec timing (because of the real time OS ChiBios) thus allowing the correct pre-Integration and propagation of the IMU state within the estimator.

You may certainly work with Raw IMU and process within Raspian if you would like to compare accuracy and consistency of VINS.

gyro.x is a float, it is multiply by 1000 and truncated to int for sending in raw_imu

1 Like

Any progress to Pull Request the highres IMU ?
In the meantime I will build for Matek H743 = MPU6000

Would you mind taking a look at GCS_MAVLink: support HIGHRES_IMU by chobitsfan · Pull Request #24258 · ArduPilot/ardupilot · GitHub ? Thank you

Ok good, curiously I could not find with author name, anyway I wrote a comment and hopefully that will move forward. @rishabsingh3003 could you help pushing for this PR?

thank you, I got it.

Very nice indeed!

Do you mind sharing a power train details? I’m considering reproducing this with quite similar hardware, possibly designing a custom frame for the setup.

I would also like to try using RaspberryPi 5 with two cameras (since it has two camera MIPI ports now) and vins-stereo. Before Pi5, this was only possible using a special board multiplexing two cameras or using a compute module.

Hello,

I wonder if the RPI5 will allow camera sync … this is necessary for depth mapping.

Arducam has a “trick” to make it work

1 Like