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

[Bug] Missing parameter: pose_recovery_type error #29

Closed
LimHyungTae opened this issue Aug 17, 2024 · 2 comments · Fixed by #30
Closed

[Bug] Missing parameter: pose_recovery_type error #29

LimHyungTae opened this issue Aug 17, 2024 · 2 comments · Fixed by #30

Comments

@LimHyungTae
Copy link
Member

LimHyungTae commented Aug 17, 2024

Problem

After building the workspace, I conducted unit test as follows:

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

Yet, it outputs an error message as follows:

F0817 16:48:32.307374 4048116 YamlParser.h:44] Check failed: file_handle.type() != cv::FileNode::NONE (0 vs. 0) **Missing parameter: pose_recovery_type in file: /home/shapelim/kimera_multi_ws/src/kimera_multi/params/D455/LcdParams.yaml**
*** Check failure stack trace: ***
    @     0x7fd8360d0703  google::LogMessage::Fail()
    @     0x7fd8360d54ab  google::LogMessage::SendToLog()
    @     0x7fd8360d03ff  google::LogMessage::Flush()
    @     0x7fd8360d0c2f  google::LogMessageFatal::~LogMessageFatal()
    @     0x7fd830fcd52d  VIO::YamlParser::getYamlParam<>()
    @     0x7fd83111e2f5  VIO::LoopClosureDetectorParams::parseYAML()
    @     0x7fd8310e6b94  VIO::parsePipelineParams<>()
    @     0x7fd8310e0b02  VIO::VioParams::parseYAML()
    @     0x7fd8310e251f  VIO::VioParams::VioParams()
    @     0x7fd8310e2e6a  VIO::VioParams::VioParams()
    @     0x7fd835e5704a  VIO::KimeraVioRos::KimeraVioRos()
    @     0x5620c07fc9c1  main
    @     0x7fd83552c083  __libc_start_main
    @     0x5620c07fca4e  _start
================================================================================REQUIRED process [acl_jackal2/kimera_vio_ros/kimera_vio_ros_node-1] has died!
process has died [pid 4048116, exit code -6, 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

@LimHyungTae
Copy link
Member Author

Bebugging

To check what parts are updated, I run diff kimera_vio/params/D455/LcdParams.yaml kimera_multi/params/D455/LcdParams.yaml and it outputs:

4c4
< alpha: 0.2
---
> alpha: 0.4
19c19
< nfeatures: 1000
---
> nfeatures: 700
60,63c60
< # pose_recovery_type options:
< #   0: 3d3d (Arun)
< #   1: PnP (opengv)
< pose_recovery_type: 0
---
> use_pnp_pose_recovery: 0

Q1. Is there a reason to change the parameter to use_pnp_pose_recovery? I think it's wrong, because all the codes still use pose_recovery_type as follows:


Input in the command

grep -r "use_pnp_pose_recovery" .

Output lines

./kimera_multi/params/D455/LcdParams.yaml:use_pnp_pose_recovery: 0

(i.e., there's nowhere that use_pnp_pose_recovery is used!)


Input in the command

grep -r "pose_recovery_type" . 

Output lines

./kimera_vio/params/KinectAzure/LcdParams.yaml:# pose_recovery_type options:
./kimera_vio/params/KinectAzure/LcdParams.yaml:pose_recovery_type: 0
./kimera_vio/params/uHumans1/LcdParams.yaml:# pose_recovery_type options:
./kimera_vio/params/uHumans1/LcdParams.yaml:pose_recovery_type: 0
./kimera_vio/params/EurocMono/LcdParams.yaml:# pose_recovery_type options:
./kimera_vio/params/EurocMono/LcdParams.yaml:pose_recovery_type: 2
./kimera_vio/params/uHumans2/LcdParams.yaml:# pose_recovery_type options:
./kimera_vio/params/uHumans2/LcdParams.yaml:pose_recovery_type: 0
./kimera_vio/params/Euroc/LcdParams.yaml:# pose_recovery_type options:
./kimera_vio/params/Euroc/LcdParams.yaml:pose_recovery_type: 0
./kimera_vio/params/D455/LcdParams.yaml:# pose_recovery_type options:
./kimera_vio/params/D455/LcdParams.yaml:pose_recovery_type: 0
./kimera_vio/params/RealSenseIR/LcdParams.yaml:# pose_recovery_type options:
./kimera_vio/params/RealSenseIR/LcdParams.yaml:pose_recovery_type: 0
./kimera_vio/tests/testLoopClosureDetector.cpp:  lcd_params_.pose_recovery_type_ = PoseRecoveryType::kPnP;
./kimera_vio/tests/testLoopClosureDetector.cpp:  lcd_params_.pose_recovery_type_ = PoseRecoveryType::kPnP;
./kimera_vio/tests/testLoopClosureDetector.cpp:  lcd_params_.pose_recovery_type_ = PoseRecoveryType::k5ptRotOnly;
./kimera_vio/tests/testLoopClosureDetector.cpp:  lcd_params_.pose_recovery_type_ = PoseRecoveryType::kPnP;
./kimera_vio/tests/testLoopClosureDetector.cpp:  lcd_params_.pose_recovery_type_ = PoseRecoveryType::kPnP;
./kimera_vio/tests/data/ForLoopClosureDetector/testLCDParameters.yaml:# pose_recovery_type options:
./kimera_vio/tests/data/ForLoopClosureDetector/testLCDParameters.yaml:pose_recovery_type: 0
./kimera_vio/tests/data/EurocParams/LcdParams.yaml:# pose_recovery_type options:
./kimera_vio/tests/data/EurocParams/LcdParams.yaml:pose_recovery_type: 0
./kimera_vio/include/kimera-vio/loopclosure/LoopClosureDetectorParams.h:  PoseRecoveryType pose_recovery_type_ = PoseRecoveryType::k3d3d;
./kimera_vio/src/loopclosure/LoopClosureDetectorParams.cpp:  int pose_recovery_type;
./kimera_vio/src/loopclosure/LoopClosureDetectorParams.cpp:  yaml_parser.getYamlParam("pose_recovery_type", &pose_recovery_type);
./kimera_vio/src/loopclosure/LoopClosureDetectorParams.cpp:  pose_recovery_type_ = static_cast<PoseRecoveryType>(pose_recovery_type);
./kimera_vio/src/loopclosure/LoopClosureDetectorParams.cpp:                        "pose_recovery_type_",
./kimera_vio/src/loopclosure/LoopClosureDetectorParams.cpp:                        static_cast<unsigned int>(pose_recovery_type_),
./kimera_vio/src/loopclosure/LoopClosureDetectorParams.cpp:         (pose_recovery_type_ == lp2.pose_recovery_type_) &&
./kimera_vio/src/loopclosure/LoopClosureDetector.cpp:      if (lcd_params_.pose_recovery_type_ == PoseRecoveryType::kPnP ||
./kimera_vio/src/loopclosure/LoopClosureDetector.cpp:          lcd_params_.pose_recovery_type_ == PoseRecoveryType::k5ptRotOnly) {
./kimera_vio/src/loopclosure/LoopClosureDetector.cpp:    if (lcd_params_.pose_recovery_type_ == PoseRecoveryType::k5ptRotOnly) {
./kimera_vio/src/loopclosure/LoopClosureDetector.cpp:  switch (lcd_params_.pose_recovery_type_) {
./kimera_vio/src/loopclosure/LoopClosureDetector.cpp:                 << static_cast<unsigned int>(lcd_params_.pose_recovery_type_)
./kimera_vio/src/loopclosure/LoopClosureDetector.cpp:  switch (lcd_params_.pose_recovery_type_) {
./kimera_vio/src/loopclosure/LoopClosureDetector.cpp:                 << static_cast<unsigned int>(lcd_params_.pose_recovery_type_)

@yuluntian
Copy link
Collaborator

Thanks for investigating this! I think this was inherited from older kimera vio settings, and I created a PR to fix this issue.

@yunzc yunzc closed this as completed in #30 Aug 18, 2024
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging a pull request may close this issue.

2 participants