Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Run kaist dataset with ONE camera and it diverges #127

Closed
JaySlamer opened this issue Dec 26, 2020 · 10 comments
Closed

Run kaist dataset with ONE camera and it diverges #127

JaySlamer opened this issue Dec 26, 2020 · 10 comments
Labels
bug Something isn't working dataset Dataset issue request or issue

Comments

@JaySlamer
Copy link

JaySlamer commented Dec 26, 2020

Stereo worked perfectly. Then I changed max_cameras to 1, and use_stereo to false, and ran it again. The result was horrible. Is it possible to run kaist with monocular vio?if yes, how can I do it?
Recently, i am trying to add wheel encoder to monocular msckf and i'd like to do it based on a well-built msckf codebase like open-vins. So I wanna make sure there is nothing wrong with the monoculr msckf code and its kaist configuration

@WoosikLee2510
Copy link
Member

Hi, I have experience running kaist dataset mono. Have you tried the camera pixel nosise as 2? Also, if this still not work, can you share your launch file?

@JaySlamer
Copy link
Author

JaySlamer commented Dec 26, 2020

Hi, I have experience running kaist dataset mono. Have you tried the camera pixel nosise as 2? Also, if this still not work, can you share your launch file?

<!-- imu starting thresholds -->
<arg name="init_window_time"  default="0.75" />
<arg name="init_imu_thresh"   default="0.12" />

<!-- saving trajectory path and timing information -->
<arg name="dosave"      default="false" />
<arg name="dotime"      default="false" />
<arg name="path_est"    default="/tmp/traj_estimate.txt" />
<arg name="path_time"   default="/tmp/traj_timing.txt" />


<!-- MASTER NODE! -->
<node name="run_subscribe_msckf" pkg="ov_msckf" type="run_subscribe_msckf" output="screen" clear_params="true" required="true">

    <!-- bag topics -->
    <param name="topic_imu"      type="string" value="/imu/data_raw" />
    <param name="topic_camera0"  type="string" value="/stereo/left/image_raw" />
    <param name="topic_camera1"  type="string" value="/stereo/right/image_raw" />
    <rosparam param="stereo_pairs">[0, 1]</rosparam>

    <!-- world/filter parameters -->
    <param name="use_fej"                type="bool"   value="true" />
    <param name="use_imuavg"             type="bool"   value="true" />
    <param name="use_rk4int"             type="bool"   value="true" />
    <param name="use_stereo"             type="bool"   value="false" />
    <param name="calib_cam_extrinsics"   type="bool"   value="true" />
    <param name="calib_cam_intrinsics"   type="bool"   value="true" />
    <param name="calib_cam_timeoffset"   type="bool"   value="true" />
    <param name="calib_camimu_dt"        type="double" value="0.0" />
    <param name="max_clones"             type="int"    value="15" />
    <param name="max_slam"               type="int"    value="50" />
    <param name="max_slam_in_update"     type="int"    value="25" /> <!-- 25 seems to work well -->
    <param name="max_msckf_in_update"    type="int"    value="40" />
    <param name="max_cameras"            type="int"    value="1" />
    <param name="dt_slam_delay"          type="double" value="3" />
    <param name="init_window_time"       type="double" value="$(arg init_window_time)" />
    <param name="init_imu_thresh"        type="double" value="$(arg init_imu_thresh)" />
    <rosparam param="gravity">[0.0,0.0,9.81]</rosparam>
    <param name="feat_rep_msckf"         type="string" value="ANCHORED_MSCKF_INVERSE_DEPTH" />
    <param name="feat_rep_slam"          type="string" value="ANCHORED_MSCKF_INVERSE_DEPTH" />
    <param name="feat_rep_aruco"         type="string" value="ANCHORED_MSCKF_INVERSE_DEPTH" />

    <!-- zero velocity update parameters -->
    <param name="try_zupt"               type="bool"   value="true" />
    <param name="zupt_chi2_multipler"    type="int"    value="1" />
    <param name="zupt_max_velocity"      type="double" value="0.25" />
    <param name="zupt_noise_multiplier"  type="double" value="10" />

    <!-- timing statistics recording -->
    <param name="record_timing_information"   type="bool"   value="$(arg dotime)" />
    <param name="record_timing_filepath"      type="string" value="$(arg path_time)" />

    <!-- tracker/extractor properties -->
    <param name="use_klt"            type="bool"   value="true" />
    <param name="num_pts"            type="int"    value="400" />
    <param name="fast_threshold"     type="int"    value="10" />
    <param name="grid_x"             type="int"    value="10" />
    <param name="grid_y"             type="int"    value="5" />
    <param name="min_px_dist"        type="int"    value="8" />
    <param name="knn_ratio"          type="double" value="0.70" />
    <param name="downsample_cameras" type="bool"   value="false" />
    <param name="multi_threading"    type="bool"   value="true" />

    <param name="fi_max_dist"        type="double" value="100" />
    <param name="fi_max_baseline"    type="double" value="500" />
    <param name="fi_max_cond_number" type="double" value="18000" />

    <!-- aruco tag/mapping properties -->
    <param name="use_aruco"        type="bool"   value="false" />
    <param name="num_aruco"        type="int"    value="1024" />
    <param name="downsize_aruco"   type="bool"   value="true" />

    <!-- sensor noise values / update -->
    <param name="up_msckf_sigma_px"            type="double"   value="1" />
    <param name="up_msckf_chi2_multipler"      type="double"   value="1" />
    <param name="up_slam_sigma_px"             type="double"   value="1" />
    <param name="up_slam_chi2_multipler"       type="double"   value="1" />
    <param name="up_aruco_sigma_px"            type="double"   value="1" />
    <param name="up_aruco_chi2_multipler"      type="double"   value="1" />
    <param name="gyroscope_noise_density"      type="double"   value="1.6968e-04" />
    <param name="gyroscope_random_walk"        type="double"   value="1.9393e-05" />
    <param name="accelerometer_noise_density"  type="double"   value="1.0000e-3" />
    <param name="accelerometer_random_walk"    type="double"   value="3.0000e-3" />

    <!-- camera intrinsics -->
    <rosparam param="cam0_wh">[1280, 560]</rosparam>
    <rosparam param="cam1_wh">[1280, 560]</rosparam>
    <param name="cam0_is_fisheye" type="bool" value="true" />
    <param name="cam1_is_fisheye" type="bool" value="true" />
    <rosparam param="cam0_k">[8.1690378992770002e+02,8.1156803828490001e+02,6.0850726281690004e+02,2.6347599764440002e+02]</rosparam>
    <rosparam param="cam0_d">[-5.6143027800000002e-02,1.3952563200000001e-01,-1.2155906999999999e-03,-9.7281389999999998e-04]</rosparam>
    <rosparam param="cam1_k">[8.1378205539589999e+02,8.0852165574269998e+02,6.1386419539320002e+02,2.4941049348650000e+02]</rosparam>
    <rosparam param="cam1_d">[-5.4921981799999998e-02,1.4243657430000001e-01,7.5412299999999996e-05,-6.7560530000000001e-04]</rosparam>

    <!-- camera extrinsics -->
    <rosparam param="T_C0toI">
    [
    -0.00413,-0.01966,0.99980,1.73944,
    -0.99993,-0.01095,-0.00435,0.27803,
    0.01103,-0.99975,-0.01962,-0.08785,
    0.00000,0.00000,0.00000,1.00000
    ]
    </rosparam>
    <rosparam param="T_C1toI">
    [
    -0.00768,-0.01509,0.99986,1.73376,
    -0.99988,-0.01305,-0.00788,-0.19706,
    0.01317,-0.99980,-0.01499,-0.08271,
    0.00000,0.00000,0.00000,1.00000
    ]
    </rosparam>


</node>

<!-- record the trajectory if enabled -->
<group if="$(arg dosave)">
    <node name="recorder_estimate" pkg="ov_eval" type="pose_to_file" output="screen" required="true">
        <param name="topic"      type="str" value="/ov_msckf/poseimu" />
        <param name="topic_type" type="str" value="PoseWithCovarianceStamped" />
        <param name="output"     type="str" value="$(arg path_est)" />
    </node>
</group>

@JaySlamer
Copy link
Author

JaySlamer commented Dec 26, 2020

Hi, I have experience running kaist dataset mono. Have you tried the camera pixel nosise as 2? Also, if this still not work, can you share your launch file?

I changed up_msckf_sigma_px to 2 and up_slam_sigma_px to 2, it became even worse. My data was kaist urban 28.

Thanks a lot WoosikLee2510, is it convient for you to share your successful configuration?

@goldbattle goldbattle added debugging Might be a bug, looking into the issue question Theory or implementation question labels Dec 27, 2020
@goldbattle
Copy link
Member

I have only had experience running it with the stereo configuration (see original pr #79). You might need to play with a few parameters and the initialization of the system is likely very sensitive. These datasets will also run into scale issues with monocular for constant velocity / acceleration (see this paper for details).

@JaySlamer
Copy link
Author

JaySlamer commented Dec 28, 2020

I have only had experience running it with the stereo configuration (see original pr #79). You might need to play with a few parameters and the initialization of the system is likely very sensitive. These datasets will also run into scale issues with monocular for constant velocity / acceleration (see this paper for details).

I changed the value of cam0_is_fisheye to false, now it runs much better. the configuration file of urban 28 says its plumb_bob distortion model, which is just another name for radtan. In pgeneva_ros_kaist.launch file cam0_is_fisheye and cam1_is_fisheye were both set to true. I believe this is a mistake. However the stereo vio still some how survives this wrong configuration.

Now it still can NOT finish urban 28 because it fails to detect zero velocity at the location as shown in the picture below and finally diverges
图片

@JaySlamer
Copy link
Author

Increase max_clones from 15 to 20, now it can finish urban 28
图片

@JaySlamer
Copy link
Author

summary:

  1. start from stereo launch file pgeneva_ros_kaist.launch
  2. change max_cameras to 1;
  3. change cam0_is_fisheye to false;
  4. increase max_clone from 15 to 20;

@JaySlamer
Copy link
Author

I have only had experience running it with the stereo configuration (see original pr #79). You might need to play with a few parameters and the initialization of the system is likely very sensitive. These datasets will also run into scale issues with monocular for constant velocity / acceleration (see this paper for details).

I was thinking maybe a launch file should be provided specificly for running monocular open-vins on kaist urban dataset according to the results of this issue because running monocular vio on approximately 2d-motion datasets requires trickier tuning.
And maybe the parameter cam0_is_fisheye and cam1_is_fisheye in stereo configuration file should be changed to false because both cameras are calibrated by plumb_bob model according to the calibration file in kaist 28

@goldbattle goldbattle added bug Something isn't working and removed debugging Might be a bug, looking into the issue question Theory or implementation question labels Jan 7, 2021
@goldbattle
Copy link
Member

I will keep this open till I get time to fix this and take another look.
Thanks again for points that out, sounds like something that I need to fix, thanks!

@goldbattle
Copy link
Member

I did correct the distortion issue, but was unable to get it to run with monocular on the urban39. The mono only does work for the beginning segment, but once it gets on the main street there are far too many dynamic objects which cause the system to diverge slowly, but it looks like you have some parameters that seem to work for you that others can reference.

@goldbattle goldbattle added the dataset Dataset issue request or issue label Jun 9, 2021
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working dataset Dataset issue request or issue
Projects
None yet
Development

No branches or pull requests

3 participants