lukasvst / dm-vio-ros

ROS wrapper for DM-VIO: Delayed Marginalization Visual-Inertial Odometry
GNU General Public License v3.0
120 stars 22 forks source link

Question on running own datasets in rosbag format #2

Closed wwtinwhu closed 2 years ago

wwtinwhu commented 2 years ago

Hello, @lukasvst ! I read the tips in the dm-vio pages for Running on your own datasets. Does the same apply to the Rosbag format? For example: For each image it must contain an IMU 'measurement' with exactly the same timestamp. Thanks!

lukasvst commented 2 years ago

When running with ROS you do not need an IMU measurement with the same timestamp as images. These will be automatically interpolated by the ROS wrapper.

The other points (camera calibration, IMU calibration) in the page "Running on your own datasets" can still be useful, but the points regarding files=..., the times.txt-file and the imu file don't apply as this information is taken from ROS topics.

wwtinwhu commented 2 years ago

When running with ROS you do not need an IMU measurement with the same timestamp as images. These will be automatically interpolated by the ROS wrapper.

The other points (camera calibration, IMU calibration) in the page "Running on your own datasets" can still be useful, but the points regarding files=..., the times.txt-file and the imu file don't apply as this information is taken from ROS topics.

When I run my own rosbag data, the terminal output this: WARNING: Not sending frame, because it does not have IMU data yet. So I check the code in IMUInteropolator.cpp https://github.com/lukasvst/dm-vio/blob/432b7af3ad35daff804a99175bc0498da4595130/src/live/IMUInterpolator.cpp#L280. So the rosbag data also need an imu timestamp with the same time as images. May I ask where I have not set it? @lukasvst

lukasvst commented 2 years ago

This warning you get should only be printed when no IMU data for the frame has been received yet. Are you sure that the ROS driver listens for IMU data on the correct topic and that it has timestamps (in the same time frame as the image timestamps)? You can put a print out here to see if it actually gets called: https://github.com/lukasvst/dm-vio-ros/blob/master/src/main.cpp#L220

(The IMU data with the same timestamp needed in IMUInterpolator#L280 will be generated / interpolated automatically by the IMUInterpolator once IMU data is received, you do not need to do this yourself).

wwtinwhu commented 2 years ago

This warning you get should only be printed when no IMU data for the frame has been received yet. Are you sure that the ROS driver listens for IMU data on the correct topic and that it has timestamps (in the same time frame as the image timestamps)? You can put a print out here to see if it actually gets called: https://github.com/lukasvst/dm-vio-ros/blob/master/src/main.cpp#L220

(The IMU data with the same timestamp needed in IMUInterpolator#L280 will be generated / interpolated automatically by the IMUInterpolator once IMU data is received, you do not need to do this yourself).

Thanks, @lukasvst . I find the problem. Due to the transmission delay of camera, image data is store behind the imu data (which close to the image in time) in rosbag. So I modify the maxIMUQueueSize to wait the image data as my IMU frenquency is relatively high. https://github.com/lukasvst/dm-vio/blob/432b7af3ad35daff804a99175bc0498da4595130/src/live/IMUInterpolator.h#L124

wwtinwhu commented 2 years ago

@lukasvst Hello, I met problem in Initilization. Here is the important output: By the way, image size tested is 2000+ x 1500+ , so the fps is around 2Hz. Is there a way to increase the speed?

SKIPPING 0 FRAMES! frames remaining in queue: 104 Scaling with rescaleFactor: 1.08153 Initialization: keep 1.1% (need 1000, have 94231)! INITIALIZE FROM INITIALIZER (1045 pts)! Frame history size: 8 Preparing keyframe: 7 Current mapping id: 7 create KF after: 7 Frames between KFs: 6 SPARSITY: MinActDist 2.100000 (need 1000 points, have 1045 points)! OPTIMIZE 1045 pts, 1045 active res, 0 lin res! Initial Error A(500926.949692)=(AV inf). Num: A(0) + M(0); ab 0.000000 0.000000! Dynamic weight: 0 STEPS: A 0.0; B 0.0; R 0.0; T 0.0. REJECT 0 (L -5.00, dir nan, ss 1.0): A(3514233.833862)=(AV 165.695). Num: A(16) + M(0); ab 0.000000 0.000000! Dynamic weight: 0.00233088 STEPS: A 0.2; B 4.8; R 4.5; T 7.8. REJECT 1 (L -3.00, dir 0.06, ss 1.0): A(3534486.335487)=(AV 166.172). Num: A(16) + M(0); ab 0.002015 -0.406944! Dynamic weight: 0.00233088 STEPS: A 0.1; B 3.9; R 0.4; T 0.6. ACCEPT 2 (L -1.00, dir 0.57, ss 1.0): A(3514180.225002)=(AV 165.694). Num: A(16) + M(0); ab 0.000654 -0.328881! Dynamic weight: 0.00233113 STEPS: A 2.0; B 16.8; R 0.8; T 0.9. ACCEPT 3 (L -1.60, dir -0.77, ss 1.0): A(3316650.475758)=(AV 26.621). Num: A(585) + M(0); ab -0.016629 1.098260! Dynamic weight: 0.090308 STEPS: A 2.4; B 24.0; R 1.7; T 1.3. ACCEPT 4 (L -2.20, dir 0.99, ss 1.0): A(3228271.436474)=(AV 26.287). Num: A(584) + M(0); ab -0.036790 3.134028! Dynamic weight: 0.0926217 STEPS: A 1.9; B 20.8; R 1.2; T 1.1. ACCEPT 5 (L -2.81, dir 1.00, ss 1.0): A(3183264.857426)=(AV 26.238). Num: A(578) + M(0); ab -0.052983 4.895933! Dynamic weight: 0.0929662 STEPS: A 1.4; B 14.9; R 1.5; T 1.7. ACCEPT 6 (L -3.41, dir 1.00, ss 1.0): A(3154833.985569)=(AV 26.098). Num: A(579) + M(0); ab -0.064908 6.156539! Dynamic weight: 0.0939663 STEPS: A 0.9; B 8.4; R 1.9; T 1.7. ACCEPT 7 (L -4.01, dir 0.99, ss 1.0): A(3135090.211493)=(AV 26.061). Num: A(577) + M(0); ab -0.072715 6.872343! Dynamic weight: 0.0942314 STEPS: A 0.6; B 6.8; R 0.8; T 1.0. ACCEPT 8 (L -4.61, dir 0.99, ss 1.0): A(3128176.334583)=(AV 26.055). Num: A(576) + M(0); ab -0.077937 7.449377! Dynamic weight: 0.094276 STEPS: A 0.7; B 9.4; R 1.1; T 1.2. ACCEPT 9 (L -5.00, dir 0.99, ss 1.0): A(3113096.310629)=(AV 26.060). Num: A(573) + M(0); ab -0.084196 8.251193! Dynamic weight: 0.0942393 STEPS: A 0.5; B 4.6; R 0.9; T 1.1. ACCEPT 10 (L -5.00, dir 0.98, ss 1.0): A(3104018.457140)=(AV 25.977). Num: A(575) + M(0); ab -0.088370 8.639544! Dynamic weight: 0.0948448 STEPS: A 0.0; B 1.0; R 1.0; T 1.0. ACCEPT 11 (L -5.00, dir -0.20, ss 1.0): A(3091124.629829)=(AV 25.878). Num: A(577) + M(0); ab -0.088418 8.554607! Dynamic weight: 0.0955717 STEPS: A 0.3; B 3.1; R 1.2; T 1.2. ACCEPT 12 (L -5.00, dir -0.09, ss 1.0): A(3075304.613695)=(AV 25.722). Num: A(581) + M(0); ab -0.091325 8.818785! Dynamic weight: 0.0967293 STEPS: A 0.4; B 4.9; R 1.1; T 1.0. ACCEPT 13 (L -5.00, dir 0.98, ss 1.0): A(3065508.279926)=(AV 25.659). Num: A(582) + M(0); ab -0.094875 9.231724! Dynamic weight: 0.0972054 STEPS: A 0.2; B 0.4; R 0.9; T 1.1. ACCEPT 14 (L -5.00, dir 0.71, ss 1.0): A(3058760.623926)=(AV 25.609). Num: A(583) + M(0); ab -0.096382 9.263564! Num BA Iterations done: 15 I THINK INITIALIZATINO FAILED! Resetting. LOG 7: 25.609 fine. Res: 583 A, 0 L, 0 M; (0 / 0) forceDrop. a=-0.096382, b=9.263564. Window 7 (2) RESETTING! destroyed ThreadReduce Switching to initializer state: RealtimeCoarseIMUInitState

lukasvst commented 2 years ago

I'm glad that you found the issue with the queue size!

This was just a failure of the visual initializer (no IMU data involved yet). Is it able to initialize successfully on other sequences (with slow and mostly translational movement)? Otherwise, this would suggest there is a problem with camera calibration.

Your image size is quite large, reducing it will make the system much faster and should have almost not impact on accuracy. I think you should be able to just adjust the output image size in the camera.txt file. One thing to note is that the visual initializer is still the same as in DSO, so it's expected to be slower than realtime, but after initialization the system should catch up quickly.

wwtinwhu commented 2 years ago

I'm glad that you found the issue with the queue size!

This was just a failure of the visual initializer (no IMU data involved yet). Is it able to initialize successfully on other sequences (with slow and mostly translational movement)? Otherwise, this would suggest there is a problem with camera calibration.

Your image size is quite large, reducing it will make the system much faster and should have almost not impact on accuracy. I think you should be able to just adjust the output image size in the camera.txt file. One thing to note is that the visual initializer is still the same as in DSO, so it's expected to be slower than realtime, but after initialization the system should catch up quickly.

Thanks, @lukasvst. I tried other sequences. There are a few cases that the system don't fail on the initializer. Map points are shown in the viewer. So camera calibration problem is excluded. However, I found that the CoarseIMUInit normalized error is quite large in the terminal. In this sequnence, the program switch to RealtimePGBAState with "CoarseIMUInit normalized error: 701.343 variance: 0.073787 scale: 21.5081" after a few seconds. What does CoarseIMUInit normalized error mean? And based on my test, it failed initialization in most cases with slow and mostly translational movement. Is this due to insufficient acceleration? Third, I found in some cases, the tracking point get fewer, however the movement is just walk forward, no big rotation. what is the reason for this? Thank you.

lukasvst commented 2 years ago

Yes, this is quite large. The CoarseIMUInit normalized error is the error in the IMU-initialization graph after optimization and should be below 1 usually. If the visual tracking was fine but this error is very large this is usually either:

The other problems you describe might also come from the same issue, I would suggest to first address it. You can also try to pass useimu=0 to make sure that the visual-only system works fine.

wwtinwhu commented 2 years ago

Yes, this is quite large. The CoarseIMUInit normalized error is the error in the IMU-initialization graph after optimization and should be below 1 usually. If the visual tracking was fine but this error is very large this is usually either:

  • The IMU noise values are too small. Are you using the provided t265_noise_tumvi.yaml?
  • Your IMU-camera calibration (camchain.yaml) is wrong.
  • There is an uncalibrated time offset between camera and IMU.
  • ... some other problem with the IMU data.

The other problems you describe might also come from the same issue, I would suggest to first address it. You can also try to pass useimu=0 to make sure that the visual-only system works fine.

Thanks, @lukasvst . Your suggestion is very useful!Thanks again for your patient answer! Looking forward to having the opportunity to cooperate with you on slam in the future.