/versavis

An Open Versatile Multi-Camera Visual-Inertial Sensor Suite

Primary LanguageC++OtherNOASSERTION

VersaVIS -- An Open Versatile Multi-Camera Visual-Inertial Sensor Suite

Build Test

https://youtu.be/bsvSZJq76Mc

VersaVIS provides a complete, open-source hardware, firmware and software bundle to perform time synchronization of multiple cameras with an IMU featuring exposure compensation, host clock translation and independent and stereo camera triggering.

News

  • Enjoy our new trailer video explaining the main conecpt behind VersaVIS.
  • VersaVIS runs on Ubuntu 20.04 focal fossa / ROS Noetic now, look at this issue.

Supported camera drivers

Citing

Please cite the following paper when using VersaVIS for your research:

@article{Tschopp2020,
author = {Tschopp, Florian and Riner, Michael and Fehr, Marius and Bernreiter, Lukas and Furrer, Fadri and Novkovic, Tonci and Pfrunder, Andreas and Cadena, Cesar and Siegwart, Roland and Nieto, Juan},
doi = {10.3390/s20051439},
journal = {Sensors},
number = {5},
pages = {1439},
publisher = {Multidisciplinary Digital Publishing Institute},
title = {{VersaVIS—An Open Versatile Multi-Camera Visual-Inertial Sensor Suite}},
url = {https://www.mdpi.com/1424-8220/20/5/1439},
volume = {20},
year = {2020}
}

Additional information can be found here.

Install

Clone and build

cd ~/catkin_ws/src/
git clone git@github.com:ethz-asl/versavis.git --recursive
catkin build versavis
cd versavis/firmware
./setup.sh

Setup udev rule

Add yourself to dialout group

sudo adduser <username> dialout

Copy udev rule file to your system:

sudo cp firmware/98-versa-vis.rules /etc/udev/rules.d/98-versa-vis.rules

Afterwards, use the following commands to reload the rules

sudo udevadm control --reload-rules
sudo udevadm trigger
sudo ldconfig

Note: You might have to reboot your computer for this to take effect. You can check by see whether a /dev/versavis is available and pointing to the correct device.

Configure

Adapt the configuration file to your setup needs. Also check the datasheet for how to configure the hardware switches.

Flash firmware on the VersaVIS board

  • Install the arduino IDE from here. Use version 1.8.2!
    • Note that a small modification of the install script (install.sh) might be required. In particular you may need to change the line RESOURCE_NAME=cc.arduino.arduinoide to RESOURCE_NAME=arduino-arduinoide as per the issue here.
  • Open firmware/versavis/versavis.ino in the IDE
  • Go to File -> Preferences
  • Change Sketchbook location to versavis/firmware/
  • Install board support:
    • For AVI 2.1 (the green one): Tools -> Boards -> Boards Manager -> Arduino SAMD Boards (32-bits ARM Cortex-M0+) -> Use version 1.6.20!
    • For VersaVIS 1.0 (the black one): Check here
  • Set Tools -> Port -> tty/ACM0 (Arduino Zero), and Tools -> Board -> VersaVIS.
  • Compile using the Verify menu option
  • Flash using the Upload menu option

Calibration

Typically, a VI Setup needs to be carefully calibrated for camera intrinsics and camera-camera extrinsics and camera-imu extrinsics. Refer to Kalibr for a good calibration framework. Note: To enable a good calibration, a high-quality calibration target needs to be available. Furthermore, a good and uniform light source is needed in order to reduce motion blur, especially during camera-imu calibration.

Usage

  • Adapt versavis/launch/run_versavis.launch to your needs.
  • Run with
roslaunch versavis run_versavis.launch
  • Wait for successfull initialization.

Troubleshooting

My sensor is stuck at initialization

Main symptoms are:

  • No IMU message published.
  • Cameras are not triggered or only very slowly (e.g. 1 Hz).

Troubleshooting steps:

  • Check that your camera receives a triggering signal by checking the trigger LED (Note: As the trigger pulse is very short, look for a dim flicker.).
  • Check that all topics are correctly set up and connected.
  • If the USB3 blackfly is powered over the Hirose plug, there seems to be a longer delay (0.2s+) until the image arrives on the host computer. Initialization does not succeed because it only allows successful synchronization if the image message is not older than 0.1s compared to the time message coming from the triggering board. With power over USB things seem to work fine. One can increase the threshold kMaxImageDelayThreshold but keep in mind that kMaxImageDelayThreshold >> 1/f_init. Decrease initialization frequency f_init if necessairy.

The board is not doing what I expect / How can I enter debug mode

Easiest way to debug is to enable DEBUG mode in firmware/libraries/versavis/versavis_configuration.h and check the debug output using the Arduino Serial Monitor or screen /dev/versavis. Note: In debug mode, ROS/rosserial communication is deactivated!

I don't get any IMU messages on /versavis/imu

This is normal during initialization as no IMU messages are published. Check Inintialization issues for further info.

After uploading a new firmware, I am unable to communicate with the VersaVIS board

This is most likely due to an infinite loop in the code in an error case. Reset the board by double clicking the reset button and upload your code in DEBUG mode. Then check your debug output.

IMU shows strange data or spikes

To decrease the bandwidth between VersaVIS and host but keep all information, only the IMu raw data is transferred and later scaled. If there is a scale offset, adapt the scale/sensitivity parameters in your launch file.

Depending on the IMU, recursive data grabbing is implemented with a CRC or temperature check. If this fails multiple time, the latest message is used. Check your IMU if this persists.

It looks like my exposure time is not correctly compensated

Check whether your board can correctly detect your exposure time in the debug output. Troubleshooting steps:

  • Enable exposure/strobe output on your camera.
  • Check that all dip switches are set according to the datasheet.
  • Check that the exposure LED on the board flashes with exposure time.

I receive errors on the host computer

Time candidate overflow

[ WARN] [1619791310.834852014]: /versavis/camO/tmage_raw: Time candidates buffer overflow at 1025.
...

Means that the synchronizer receives more timestamps than images. Double check if the camera is actually triggering with every pulse it receives. A typical problem is when the exposure time is higher than the measurement period.

Image candidate overflow

[ WARN] [1619791310.834852014]: /versavis/camO/tmage_raw: Image candidates buffer overflow at 1025.
...

Means that the synchronizer receives more iamges than timestamps. Double check if the camera is actually triggering and not free running.