rp-vio icon indicating copy to clipboard operation
rp-vio copied to clipboard

night city case problem

Open ZhouXiner opened this issue 3 years ago • 5 comments

Hi, sorry to bother. I try to run the city_night in the code, And I use the config from the raw git https://github.com/kminoda/VIODE/blob/master/calibration_files/cam0_pinhole.yaml But The performance is bad, do you know I did any thing wrong? Thanks Here is my config

%YAML:1.0

#common parameters imu_topic: "/imu0" image_topic: "/cam0/image_raw" mask_topic: "/cam0/segmentation" output_path: "/home/zhouxin/output/"

#camera calibration model_type: PINHOLE camera_name: camera image_width: 752 image_height: 480 distortion_parameters: k1: 0 k2: 0 p1: 0 p2: 0 projection_parameters: fx: 376.0 fy: 376.0 cx: 376.0 cy: 240.0

estimate_extrinsic: 0 #Rotation from camera frame to imu frame, imu^R_cam extrinsicRotation: !!opencv-matrix rows: 3 cols: 3 dt: d data: [1,0,0,0,1,0,0,0,1]

#Translation from camera frame to imu frame, imu^T_cam extrinsicTranslation: !!opencv-matrix rows: 3 cols: 1 dt: d data: [0,0,0]

#feature traker paprameters max_cnt: 120 # max feature number in feature tracking min_dist: 30 # min distance between two features freq: 10 # frequence (Hz) of publish tracking result. At least 10Hz for good estimation. If set 0, the frequence will be same as raw image F_threshold: 1.0 # ransac threshold (pixel) show_track: 1 # publish tracking image as topic flow_back: 1 # perform forward and backward optical flow to improve feature tracking accuracy

#optimization parameters max_solver_time: 0.04 # max solver itration time (ms), to guarantee real time max_num_iterations: 8 # max solver itrations, to guarantee real time keyframe_parallax: 10.0 # keyframe selection threshold (pixel)

#imu parameters The more accurate parameters you provide, the better performance acc_n: 0.2 # accelerometer measurement noise standard deviation. gyr_n: 0.05 # gyroscope measurement noise standard deviation.
acc_w: 0.02 # accelerometer bias random work noise standard deviation.
gyr_w: 4.0e-5 # gyroscope bias random work noise standard deviation.
g_norm: 9.81007 # gravity magnitude

#unsynchronization parameters estimate_td: 0
td: 0.0 # initial value of time offset. unit s. readed image clock + td = real image clock (IMU clock)

#rolling shutter parameters rolling_shutter: 0 # 0: global shutter camera, 1: rolling shutter camera rolling_shutter_tr: 0 # unit: s. rolling shutter read out time per frame (from data sheet).

#visualization parameters save_image: 1 # save image in pose graph for visualization prupose; you can close this function by setting 0 visualize_imu_forward: 0 # output imu forward propogation to achieve low latency and high frequence results visualize_camera_size: 0.4 # size of camera marker in RVIZ

ZhouXiner avatar Jul 29 '21 17:07 ZhouXiner

Hi,

The config file that we used for our VIODE experiments is provided here - https://github.com/karnikram/rp-vio/blob/semantic-viode/config/viode_config.yaml Two important differences from your file are the planesRGB param (RGB values of plane instance masks) and max_cnt (which is 250).

As an aside, we'd like to note that the IMU noise params provided in VIODE are hand-tuned for VINS-Mono and are not the true IMU noise params. When we used the true params (mentioned here) we got an even better result. But to avoid confusion we have only reported the results using the provided VIODE params.

karnikram avatar Jul 30 '21 05:07 karnikram

Cool! Thanks for reply. I will try with it. Thanks a lot

ZhouXiner avatar Jul 30 '21 05:07 ZhouXiner

Also remember to use the semantic-viode branch of the code as mentioned here.

karnikram avatar Jul 30 '21 05:07 karnikram

Ok, I see. For the other cases, is it necessary to change the branch?

ZhouXiner avatar Jul 30 '21 05:07 ZhouXiner

There are three branches: main is the single plane version of RP-VIO that was used for RP-VIO-Sim, OpenLORIS, ADVIO (Camera + IMU + plane mask inputs) rp-vio-multi is the multiple plane version that was used for RP-VIO-Sim (Camera + IMU + plane mask inputs) semantic-viode is the single plane version used for VIODE (Camera + IMU + semantic label inputs)

karnikram avatar Jul 30 '21 08:07 karnikram