MIT-SPARK / Kimera-Multi

Index repo for Kimera-Multi system
350 stars 40 forks source link

[Bug] kimera_vio_ros_node was killed after playing the rosbag #31

Closed LimHyungTae closed 3 months ago

LimHyungTae commented 3 months ago

After fixing some errors in #30, now launch file doesn't show any errors.

But before running the multi-robot scenario, I tested the kimera_vio_jackal.launch file to check whether a single robot's odometry was successfully estimated.

However, once, I play rosbag file, it still outputs an unexpected error:


** Trial 1

roslaunch kimera_multi kimera_vio_jackal.launch robot_name:="acl_jackal2" robot_id:=0 use_d455:=true multirobot:=false lcd_no_optimize:=true use_external_odom:=true replay:=true should_use_sim_time:=true

(In another terminal)
rosbag play 10_14_acl_jackal2.bag --clock

** Trial 2

roslaunch kimera_multi kimera_vio_jackal.launch robot_name:="acl_jackal2" robot_id:=0 use_d455:=true multirobot:=false lcd_no_optimize:=true use_external_odom:=true replay:=true should_use_sim_time:=true

(In another terminal)
rosbag play 10_14_acl_jackal2.bag --clock

** Trial 3

CATKIN_WS=/home/shapelim/hydra_ws DATA_PATH="/media/shapelim/Extreme_SSD/SPARK/kimera-multi-original/campus_outdoor_1014_public" LOG_DIR="/media/shapelim/Extreme_SSD/SPARK/kimera-multi-original/campus_outdoor_1014_public" roslaunch kimera_multi kimera_vio_jackal.launch robot_name:="acl_jackal2" robot_id:=4 use_d455:=true multirobot:=false lcd_no_optimize:=true use_external_odom:=true replay:=true should_use_sim_time:=true

(In another terminal)
rosbag play 10_14_acl_jackal2.bag --clock

Error Message

All the trials outputs errors as follows once I play rosbag (I used 10_14_acl_jackal2.bag):

... logging to /home/shapelim/.ros/log/e8f4c314-5ccf-11ef-8b10-89c894c2eed9/roslaunch-shapelim-183775.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://shapelim:34419/

SUMMARY
========

PARAMETERS
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/base_link_frame_id: acl_jackal2/reals...
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/bow_batch_size: 10
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/bow_skip_num: 2
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/force_same_image_timestamp: True
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/image_transport: raw
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/left_cam_frame_id: acl_jackal2/forwa...
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/log_gt_data: True
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/map_frame_id: acl_jackal2/map
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/mono_ransac_threshold: 30
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/odom_frame_id: acl_jackal2/odom
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/online_run: True
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/params_folder_path: /home/shapelim/ki...
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/position_det_threshold: 0.3
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/publish_vlc_frames: True
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/right_cam_frame_id: acl_jackal2/forwa...
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/robot_id: 0
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/sensor_params_folder_path: 
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/stereo_ransac_threshold: 20
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/use_external_odom: True
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/use_lcd: True
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/use_lcd_registration_server: False
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/use_rviz: True
 * /acl_jackal2/kimera_vio_ros/kimera_vio_ros_node/velocity_det_threshold: 0.1
 * /acl_jackal2/kimera_vio_ros/posegraph_viewer/frame_id: acl_jackal2/map
 * /acl_jackal2/use_sim_time: True
 * /rosdistro: noetic
 * /rosversion: 1.16.0

NODES
  /acl_jackal2/
    base_to_realsense (tf2_ros/static_transform_publisher)
    left_img_decompress (image_transport/republish)
    right_img_decompress (image_transport/republish)
  /acl_jackal2/kimera_vio_ros/
    kimera_vio_ros_node (kimera_vio_ros/kimera_vio_ros_node)
    posegraph_viewer (pose_graph_tools_ros/visualizer_node)

ROS_MASTER_URI=http://localhost:11311

process[acl_jackal2/kimera_vio_ros/kimera_vio_ros_node-1]: started with pid [183842]
process[acl_jackal2/kimera_vio_ros/posegraph_viewer-2]: started with pid [183843]
process[acl_jackal2/base_to_realsense-3]: started with pid [183844]
process[acl_jackal2/left_img_decompress-4]: started with pid [183846]
[ INFO] [1724019434.318642659]: Initializing pose graph visualizer
process[acl_jackal2/right_img_decompress-5]: started with pid [183851]
[ INFO] [1724019434.421055853]: BoW vector batch size: 10
[ INFO] [1724019434.421392953]: BoW vector skip num: 2
[ INFO] [1724019434.421414956]: Publish VLC frames: 1
I0818 18:17:14.422672 183842 LoopClosureDetector.cpp:70] LoopClosureDetector:: Loading vocabulary from /home/shapelim/kimera_multi_ws/src/kimera_multi_lcd/vocab/mit_voc.yml
I0818 18:17:16.635140 183842 LoopClosureDetector.cpp:73] Loaded vocabulary with 593637 visual words.
I0818 18:17:16.636036 183842 Logger.cpp:59] Opening output file: traj_gt.csv
I0818 18:17:16.652153 183842 RegularVioBackend.cpp:115] Using Regular VIO Backend.
I0818 18:17:16.726106 183842 PipelineModule.h:451] MISO Pipeline Module: Display has no output queue registered.
I0818 18:17:16.728583 183842 Pipeline.cpp:352] Pipeline Modules launched (parallel_run set to 1).
I0818 18:17:16.729216 183928 Pipeline.cpp:102] Spinning Kimera-VIO.
W0818 18:17:19.820802 183928 DataProviderModule.cpp:62] Asking for data before start of IMU stream:  1.66577e+09[s] to  1.66577e+09[s]
I0818 18:17:19.829326 183842 KimeraVioRos.cpp:205] Statistics
-----------                                        #    log hz  {avg +- std}    [min, max]  last
data_provider_left_frame_queue Size [#]              2  0.6 {1.0 +- 0.0}    [1.0, 1.0]  1.0
data_provider_right_frame_queue Size [#]             2  0.6 {1.5 +- 0.7}    [1.0, 2.0]  2.0
W0818 18:17:19.848309 183928 DataProviderModule.cpp:62] Asking for data before start of IMU stream:  1.66577e+09[s] to  1.66577e+09[s]
I0818 18:17:19.924507 183922 VioBackend.h:182] ------------------- Initialize Pipeline: timestamp = 1665774561803958416--------------------
W0818 18:17:19.924552 183922 InitializationFromImu.cpp:25] InitializationFromImu: assumes that the vehicle is stationary and upright along some axis,and gravity vector is along a single axis!
================================================================================REQUIRED process [acl_jackal2/kimera_vio_ros/kimera_vio_ros_node-1] has died!
process has died [pid 183842, exit code -11, cmd /home/shapelim/kimera_multi_ws/devel/lib/kimera_vio_ros/kimera_vio_ros_node --use_lcd=true --vocabulary_path=/home/shapelim/kimera_multi_ws/src/kimera_multi_lcd/vocab/mit_voc.yml --flagfile=/home/shapelim/kimera_multi_ws/src/kimera_multi/params/D455/flags/Mesher.flags --flagfile=/home/shapelim/kimera_multi_ws/src/kimera_multi/params/D455/flags/VioBackend.flags --flagfile=/home/shapelim/kimera_multi_ws/src/kimera_multi/params/D455/flags/RegularVioBackend.flags --flagfile=/home/shapelim/kimera_multi_ws/src/kimera_multi/params/D455/flags/Visualizer3D.flags --use_external_odometry=true --do_coarse_imu_camera_temporal_sync=false --do_fine_imu_camera_temporal_sync=false --lcd_no_optimize=true --lcd_no_detection=false --depth_image_mask= --logtostderr=1 --colorlogtostderr=1 --log_prefix=1 --minloglevel=0 --v=0 --log_output=false --log_euroc_gt_data=false --output_path=/home/shapelim/kimera_multi_ws/src/Kimera-VIO-ROS/output_logs/ --lcd_disable_stereo_match_depth_check=true --no_incremental_pose=true --viz_type=2 --visualize=true left_cam/image_raw:=/acl_jackal2/forward/infra1/image_rect_raw left_cam/image_raw/compressed:=/acl_jackal2/forward/infra1/image_rect_raw/compressed right_cam/image_raw:=/acl_jackal2/forward/infra2/image_rect_raw right_cam/image_raw/compressed:=/acl_jackal2/forward/infra2/image_rect_raw/compressed imu:=/acl_jackal2/forward/imu external_odom:=/acl_jackal2/jackal_velocity_controller/odom reinit_flag:=reinit_flag reinit_pose:=reinit_pose odometry:=odometry resiliency:=resiliency imu_bias:=imu_bias optimized_trajectory:=optimized_trajectory pose_graph:=pose_graph mesh:=mesh frontend_stats:=frontend_stats debug_mesh_img/image_raw:=debug_mesh_img/image_raw feature_tracks/image_raw:=feature_tracks/image_raw time_horizon_pointcloud:=time_horizon_pointcloud __name:=kimera_vio_ros_node __log:=/home/shapelim/.ros/log/e8f4c314-5ccf-11ef-8b10-89c894c2eed9/acl_jackal2-kimera_vio_ros-kimera_vio_ros_node-1.log].
log file: /home/shapelim/.ros/log/e8f4c314-5ccf-11ef-8b10-89c894c2eed9/acl_jackal2-kimera_vio_ros-kimera_vio_ros_node-1*.log
Initiating shutdown!
================================================================================
[acl_jackal2/right_img_decompress-5] killing on exit
[acl_jackal2/left_img_decompress-4] killing on exit
[acl_jackal2/base_to_realsense-3] killing on exit
[acl_jackal2/kimera_vio_ros/posegraph_viewer-2] killing on exit
[acl_jackal2/kimera_vio_ros/kimera_vio_ros_node-1] killing on exit
shutting down processing monitor...
... shutting down processing monitor complete
done

image


Note that I used a decompressed Rosbag file, so I don't think decompression is a solution to this issue.

yuluntian commented 3 months ago

@LimHyungTae Were you able to obtain more insights? I wasn't able to reproduce this error on Kimera-VIO yet. Until this issue is resolved, an alternative could be to try the docker image from #32.

LimHyungTae commented 3 months ago

It was hard to solve, but I nailed it!

For the following researchers (or developer), I'd like to put some checklists as follows:

  1. Make sure whether glog is installed your local environment by typing dpkg -L libgoogle-glog-dev.
  2. If there are some issues in glog, it might be conflict between your glog in the local environment and that from glog_catkin. If so, just remove all the glog by
    sudo apt-get purge libgoogle-glog-dev
    # Also remove remaining files clearly
    sudo find /usr -type d -name "*glog*"
    sudo rm -rf /usr/local/include/glog /usr/local/lib/cmake/glog /usr/local/lib/libglog* /usr/local/lib/cmake/glog

And then, reinstall it by using sudo apt-get install libgoogle-glog-dev.

and re-build everything after catkin clean.

  1. (Aug. 21, 2024) In MIT SPARK, we use the 4.28a or 4.29a version of GTSAM. Please check your GTSAM version.

  2. Don't forget to set catkin config as follows:

    catkin config -a --cmake-args -DCMAKE_BUILD_TYPE=RelWithDebInfo -DGTSAM_TANGENT_PREINTEGRATION=OFF -DGTSAM_BUILD_WITH_MARCH_NATIVE=OFF -DOPENGV_BUILD_WITH_MARCH_NATIVE=OFF
    catkin build -DGTSAM_USE_SYSTEM_EIGEN=ON --continue -s