cartographer-project / cartographer

Cartographer is a system that provides real-time simultaneous localization and mapping (SLAM) in 2D and 3D across multiple platforms and sensor configurations.
Apache License 2.0
7.18k stars 2.26k forks source link

Can't set TRAJECTORY_BUILDER_3D.use_intensities = true #1955

Open jvavrek opened 8 months ago

jvavrek commented 8 months ago

I'm trying to improve my SLAM results by including intensities:

TRAJECTORY_BUILDER_3D.use_intensities = true

but this quickly leads to

F0307 00:21:22.564245    83 local_trajectory_builder_3d.cc:134] Check failed: unsynchronized_data.ranges.size() == unsynchronized_data.intensities.size() (3706 vs. 0) Passed point cloud has inconsistent number of intensities and ranges.

(I can run SLAM when the flag is set to false, but the loop closure is not ideal.)

However, I can tell that my bag file contains a velodyne lidar "intensity" field:

rostopic echo /velodyne/velodyne_points data.bag
...
is_dense: True
header: 
  seq: 16
  stamp: 
    secs: 1709064083
    nsecs: 888649000
  frame_id: "velodyne"
height: 1
width: 3700
fields: 
  - 
    name: "x"
    offset: 0
    datatype: 7
    count: 1
  - 
    name: "y"
    offset: 4
    datatype: 7
    count: 1
  - 
    name: "z"
    offset: 8
    datatype: 7
    count: 1
  - 
    name: "intensity"
    offset: 16
    datatype: 7
    count: 1
  - 
    name: "ring"
    offset: 20
    datatype: 4
    count: 1
is_bigendian: False
point_step: 32
...

and I can also use the "intensity" field in the .h5 file we end up saving to disk further down the processing chain.

Is this feature not supported, or might I have misconfigured something?

jvavrek commented 8 months ago

This doesn't seem to be documented anywhere else, but in the config files I found the following:

  -- When setting use_intensities to true, the intensity_cost_function_options_0
  -- parameter in ceres_scan_matcher has to be set up as well or otherwise
  -- CeresScanMatcher will CHECK-fail.

Will try it out and post back here later.

jvavrek commented 8 months ago

No luck. Adding

TRAJECTORY_BUILDER_3D.use_intensities = true
TRAJECTORY_BUILDER_3D.ceres_scan_matcher.intensity_cost_function_options_0.weight = 0.5
TRAJECTORY_BUILDER_3D.ceres_scan_matcher.intensity_cost_function_options_0.huber_scale = 0.3
TRAJECTORY_BUILDER_3D.ceres_scan_matcher.intensity_cost_function_options_0.intensity_threshold = 40

to my config file still results in

F0307 23:58:35.221518    83 local_trajectory_builder_3d.cc:134] Check failed: unsynchronized_data.ranges.size() == unsynchronized_data.intensities.size() (1626 vs. 0) Passed point cloud has inconsistent number of intensities and ranges.

(this is a smaller bag file so the length of unsynchronized_data.ranges is different than my original comment)

jvavrek commented 8 months ago

Looks like use_intensities = true was not actually tested in https://github.com/cartographer-project/cartographer/pull/1766 ?

mbed92 commented 6 months ago

@jvavrek I also encountered that issue. To me, it seems that the cartographer_ros do not pass intensities to the backend: see that line and that one - only points are passed. You can modify it by yourself and see what happens. I guess that's an issue more for cartographer_ros repo.