direct_visual_lidar_calibration icon indicating copy to clipboard operation
direct_visual_lidar_calibration copied to clipboard

iVox parameters hardcoded?

Open themightyoarfish opened this issue 1 year ago • 2 comments

https://github.com/koide3/direct_visual_lidar_calibration/blob/105ca482e7ebfb4efcb4ee07662987a9470b9374/src/vlcal/preprocess/dynamic_point_cloud_integrator.cpp#L38

Should this line not use the params passed to the constructor? If yes, they also look to be in the wrong order according to the parameter names in the iVox constructor.

themightyoarfish avatar Dec 05 '24 15:12 themightyoarfish

I had applied this diff here, but this completely breaks the fusion of the ouster sample data

diff --git a/src/vlcal/preprocess/dynamic_point_cloud_integrator.cpp b/src/vlcal/preprocess/dynamic_point_cloud_integrator.cpp
index 1e4f32e..b7d3763 100644
--- a/src/vlcal/preprocess/dynamic_point_cloud_integrator.cpp
+++ b/src/vlcal/preprocess/dynamic_point_cloud_integrator.cpp
@@ -35,7 +35,7 @@ DynamicPointCloudIntegrator::DynamicPointCloudIntegrator(const DynamicPointCloud
   last_T_odom_lidar_begin = gtsam::Pose3();
   last_T_odom_lidar_end = gtsam::Pose3();

-  target_ivox.reset(new iVox(1.0, 0.05, 100));
+  target_ivox.reset(new iVox(params.voxel_resolution, params.min_distance, 100));

What am I missing here?

themightyoarfish avatar Dec 21 '24 15:12 themightyoarfish

It's my bad. Here params.voxel_resolution is the voxel resolution for final downsampling (e.g., 0.05) while the first argument for iVox is the voxel resolution for data association (e.g., 1.0).

koide3 avatar Dec 29 '24 20:12 koide3