Adapted VersaVIS software to use with PrisMAV using a VN100 IMU. Build and installed like it is described below (with some fixes, see GDrive). And then copied the folder into PrisMAV workspace structure.
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.
- Basler (not open-source) tested with acA1920-155uc
- MatrixVision tested with Bluefox 2 MLC200WG, needs adaption for new format
- PointGrey/Flir tested with Chameleon 3, Blackfly S
- CamBoard tested with CamBoard pico monstar
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.
cd ~/catkin_ws/src/
git clone [email protected]:ethz-asl/versavis.git --recursive
catkin build versavis
cd versavis/firmware
./setup.sh
If ./setup.sh gives an error in the beginning, change setup."$shell" in setup.sh file to setup.sh (or your equivalent shell) or make a new shell variable
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.
Adapt the configuration file to your setup needs. Also check the datasheet for how to configure the hardware switches.
- Install the arduino IDE from here. Use version 1.8.2! (Issue in the install file, see issues github)
- 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)
, andTools -> Board -> VersaVIS
. - Compile using the Verify menu option
- Flash using the Upload menu option
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.
- Adapt
versavis/launch/run_versavis.launch
to your needs. - Run with
roslaunch versavis run_versavis.launch
- Wait for successfull 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 frequencyf_init
if necessairy.
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!
This is normal during initialization as no IMU messages are published. Check Inintialization issues for further info.
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.
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.
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.