ethz-asl / maplab

A Modular and Multi-Modal Mapping Framework
https://maplab.asl.ethz.ch
Apache License 2.0
2.58k stars 722 forks source link

Multi-camera map save issue #108

Open SertacKGit opened 5 years ago

SertacKGit commented 5 years ago

Hello,

I know that Multi-camera support of rovio is still experimental but i have been trying to use multi-camera feature. During run time with multi-cam, i do not see any problem. However, final map cannot be saved. I am getting the following error: "Map is empty; nothing will be saved.". Whenever i add an additional camera to ncamera config file, final map cannot be saved. Any suggestion about how to solve this issue?

cedros23 commented 5 years ago

Hi,

The same issue also with me. If I use the stereo example of the euroc dataset, the map is not saved both in the main release and march pre-release. When I check from the rostopic information Rovioli seems to subscribe to the second camera. Thanks in advance.

mfehr commented 5 years ago

Hi @SertacKGit & @cedros23

I tested the stereo map building with ROVIOLI on the following release candidate branches:

It worked fine for me. So here is what I did:

Step 1: create the following script run_rovioli (and chmod +x run_rovioli):

#!/usr/bin/env bash
LOCALIZATION_MAP_INPUT=$1
LOCALIZATION_MAP_OUTPUT=$2
ROSBAG=$3
REST=$@

rosrun rovioli rovioli \
  --alsologtostderr=1 \
  --v=1 \
  --ncamera_calibration=ncamera.yaml  \
  --imu_parameters_maplab=imu.yaml \
  --datasource_type="rosbag" \
  --optimize_map_to_localization_map=false \
  --vio_localization_map_folder=$LOCALIZATION_MAP_INPUT \
  --save_map_folder=$LOCALIZATION_MAP_OUTPUT \
  --map_builder_save_image_as_resources=false \
  --datasource_rosbag=$ROSBAG $REST

Step 2: get calibration files:

Step 3: run ROVIOLI:

./run_rovioli "" euroc_stereo_test MH_01_easy.bag

Verification: Open with maplab and the ms command shows if it really is a stereo map:

maplab <>:/$ load --map_folder euroc_stereo_test/
Progress: 0:100.0%  1:100.0%  2:100.0%  3:100.0%  4:100.0%  5:100.0%  6:100.0%                      
--->Complete!
I1026 16:30:56.761442 20379 vi-map-serialization.cc:421] Loaded VIMap from "euroc_stereo_test/".
maplab <euroc_stereo_test>:/$ ms
Mission statistics: 

Mission 0:                  53f50f89c92661150d00000000000000    Viwls
    NCamera Sensor:         412eab8e4058621f7036b5e765dfe812
    IMU Sensor:             c63aecb41bfdfd6b7e1fac37c7cbe7bf
    Vertices:               1838                     
    Landmarks:              193533                   
    Landmarks by first observer backlink:                            
    Camera 0:               96446 (g:22514 b:73932 u:0)
    Camera 1:               97087 (g:22833 b:74254 u:0)
    Observations:           2566011                  
    Num edges by type:                               
    IMU:                    1837                     
    Wheel-odometry:         0                        
    Loop-closure:           0                        
    Distance travelled [m]: 83.325545                
    Start to end time:      2014_06_24_21_02_59 to 2014_06_24_21_06_03
    T_G_M                   unknown                  

Debugging:

Hope this helps.

cedros23 commented 5 years ago

Hello mfehr

Thanks for helping, I have tested the march release as your proposal and Euroc dataset works fine as you pointed out. I will keep debug my side and let you know if there is something to fix/improve.

cedros23 commented 5 years ago

Hi again,

After digging our ros topic publishers, we have finally found out that you were right to point out synchronization of frames. Previous publishers were sending the camera images with different timestamps, now we publish both images in the same time stamp and yes, we can finally save the map.

Before closing the issue, I have one final question. Our primal goal is use rovioli for not stereo VIO mapping but non-overlapping multi-camera mapping. So, would it be feasible to expect good mapping performance while using let's say 3 cams, 1 for VIO, 2 others for mapping?

Thx again

mfehr commented 5 years ago

Hi @cedros23

Glad it worked.

Does maplab support multi-camera mapping? Yes, maplab supports map building and feature extraction, does loop closures and bundle adjustment with all cameras of a multi-camera system. ROVIOLI will use all the cameras to build the map, but the estimator that provides the initial poses for the pose-graph is only using the first camera. We've disabled ROVIOs multi-camera support since it was giving us some trouble while at the same time very little or no performance benefit. That being said, if you want to give it a try, it's just a matter of changing the settings and passing the stereo images to the underlying ROVIO framework.

Performance: So online you won't see any difference unless you re-enable ROVIOLI's multi-camera support. The resulting vi-map however will contain all the data and features of all cameras and there should be some benefit to loop closure and bundle adjustment, but that also depends a lot on the motion and environment. maplab doesn't have any assumptions regarding the overlap of the cameras, and also doesn't do cross-camera feature matching when building the map. So not having overlap isn't an issue. In fact we've had people experiencing trouble when localizing from a map that has been built by overlapping cameras, probably due to the missing stereo feature matching, but I guess for you this shouldn't happen.

let's say 3 cams, 1 for VIO, 2 others for mapping this part I didn't quite get, if you run ROVIOLI with 3 cameras, it will simply run the filter on the first and all three cameras will be used to create the pose-graph/vi-map.

would it be feasible to expect good mapping performance If it worked well with just using one of them, you will see the same performance online as before, but might get better maps after loop closure and optimization offline in maplab.

Regarding your sensor setup: synchronization (IMU-cam and cam-cam) and calibration are key to getting good performance. The fact that the camera images had different timestamps suggests that they are not triggered at the same time(?) Quoting from the maplab FAQ:

Maplab focuses on visual-inertial mapping, therefore, the minimum requirements are: a gray-scale (preferably fish-eye) camera with global shutter and an IMU with similar or better characteristics as the ones in the sensors above (e.g. ADIS16488 or BMX055). The second critical component is a solid time synchronization between camera and IMU, i.e. ideally both devices are triggered based on the same clock. And finally, you will need to properly calibrate your sensor as described here and here.

araujokth commented 5 years ago

Hi @mfehr , just wanted to make sure I got this right. The support for multiple cameras is for the case that the cameras are totally identical right? I mean, the case of having multiple different cameras (different scale/resolution/intrinsics) where one is used for building a map and the other for performing localization, or running multiple different cameras simultaneously where they both contribute to the same map and can localize on eachothers maps, would not really work if one would not solve the issues highlighted by @dymczykm in issue https://github.com/ethz-asl/maplab/issues/85 or? Thanks again for the help!

mfehr commented 5 years ago

The VIO (ROVIOLI) provides initial guesses for the vertices based on only the first camera, however the map that is built contains landmarks and camera models for all cameras even with different resolutions, etc. The issues highlighted in #85 are caused by the limitations of the currently used feature-tracking and localization/loop-closure algorithms, as they have a hard time finding good descriptor matches across cameras that are different, for the reasons mentioned by @dymczykm. Depending on how different the cameras are performance decreases to a point where you don't find loop closures anymore. As mentioned in #85 there are some things that can be adapted to improve performance.

Maybe an additional comment in addition to #85: The loop closure thresholds in maplab are very conservative, because we wanted the default loop closure behavior to be ''safe" such that it very rarely returns false loop closures. In our experience for cameras that are different but still reasonably close, loop closures can still found by relaxing those parameters.

araujokth commented 5 years ago

Thanks a lot for the clarifications and further inputs @mfehr. I will give it a try to work on the suggestions given by @dymczykm in https://github.com/ethz-asl/maplab/issues/85 and get back to you.

wangyuanbiubiubiu commented 4 years ago
* release-candidate-march

how can i use release-candidate-march? After I checkout, there will still be compilation problems. Do I need to change my maplab dependency?