Closed bnavard closed 2 years ago
There are several parameters you should heed as described in the wiki of the MARS logger repo. Do scroll to the bottom of that page.
Also the latest version of vio_common/python/kalibr_bagcreater does not downsample an image by default. So you do not need to halve the focal length and image center. I will update the wiki page as soon as possible.
I replaced values in "euro_config" file in VINS Mono accordingly to what has been reflected in "movie_metadata". It did not work again. Here are the screenshot from the config file and movie_metadata file respectively. I followed the tutorial. Also, I have set "estimate_extrinsic" to 1.
And this is the meta_data file
I changed IMU rotation extrinsic parameter (3 by 3 matrix) and it solved the problem. The problem with that matrix in the euroc_config file was the elements with the following index (row, column) in the below matrix: (2,1), (3,3). The absolute values are correct though. They all approximate 1 and 0. But because of the sign, even though that I changed the estimate_extrinsic to 1 (having initial guess but tuning it over time) or even 2 (having no guess), VINS-MONO could not generate trajectory because of the incorrect initial guess.
extrinsicRotation: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [0.0148655429818, -0.999880929698, 0.00414029679422,
0.999557249008, 0.0149672133247, 0.025715529948,
-0.0257744366974, 0.00375618835797, 0.999660727178]
However, I just replaced them with the suggested values which happened to be the correct initial guess. Moreover, I changed the translation to all zero as well. And it worked. Generated Trajectories are correct now.
extrinsicRotation: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [0, -1, 0,
-1, 0, 0,
0, 0, -1]
Regarding your second point, I figured out the image size from the info section in the app when I wanted to collect the data. They were already correct. However, I could not find a source for having initial guess for distortion parameters, and I just left them as what they were.
Thanks!
Good job. I would recommend you to check the image size in the rosbag with the examination tool for sure, because the previous bagcreater downscaled the images. Indeed, the distortion parameters can be left to zeros, because the smartphone rear cameras usually have wide angle lens (< 120deg FOV) with negligible distortion. If you want better accuracy, try calibrate the camera intrinsics with Kalibr. To this end, we have released a tool to find out the stationary images in a video clip which are not distorted by the rolling shutter effect, so Kalibr can estimate the intrinsics as precisely as with a global shutter camera.
Hi, I am using an Android mobile phone, Xiaomi Redmi Note8, for collecting a dataset. I wonder what specific changes I should make to the (and also to which) config file when using VINS-Mono to generate trajectories out of ".bag" files. Because, when I use the software on the data I collected with my phone, the software does not generate the correct trajectory. It logs messages like, "not enough features, move slowly" or "not enough parallax". However, the software just works fine with other datasets, Worthwhile to mention, I have tried different ways for collecting the dataset like holding the camera horizontally or vertically, moving slower etc. Therefore, I am suspecting that the config files are wrong.
Below you can find screenshots from the VINS-MONO software.
And as you are seeing in the below image, "loop_match_image" section is empty. However, when I use other dataset there are images in it.