cartographer-project / cartographer_ros

Provides ROS integration for Cartographer.
Apache License 2.0
1.64k stars 1.2k forks source link

cartogtapher subscribes to two 2d lidars data as expected, but uses ONLY ONE to build a map #1390

Closed artemiialessandrini closed 4 years ago

artemiialessandrini commented 4 years ago

I am using two 2 Omron lidars, creating two different nodes with topics named scan_1 ans scan_2, successfully echo-ing them. I want to merge them to use cartographer 2d. Cartographer subscribes to two lidars, but still builds the map only with one.

Here's the rviz vizualisation

.lua file if the following:

options = {
  map_builder = MAP_BUILDER,
  trajectory_builder = TRAJECTORY_BUILDER,
  map_frame = "map",
  tracking_frame = "imu_link",
  published_frame = "odom",
  odom_frame = "odom",
  provide_odom_frame = false,
  publish_frame_projected_to_2d = false,
  -- use_pose_extrapolator = true,
  use_odometry = true,
  use_nav_sat = false,
  use_landmarks = false,
  num_laser_scans = 2,
  num_multi_echo_laser_scans = 0,
  num_subdivisions_per_laser_scan = 10,
  num_point_clouds = 0,
  lookup_transform_timeout_sec = 0.2,
  submap_publish_period_sec = 0.3,
  pose_publish_period_sec = 5e-3,
  trajectory_publish_period_sec = 30e-3,
  rangefinder_sampling_ratio = 1.,
  odometry_sampling_ratio = 1.,
  fixed_frame_pose_sampling_ratio = 1.,
  imu_sampling_ratio = 1.,
  landmarks_sampling_ratio = 1.,
}

MAP_BUILDER.use_trajectory_builder_2d = true
TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 10
TRAJECTORY_BUILDER_2D.min_z = 0.05
TRAJECTORY_BUILDER_2D.max_z = 0.45
TRAJECTORY_BUILDER_2D.min_range = 0.1
TRAJECTORY_BUILDER_2D.max_range = 20.0
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.occupied_space_weight = 1.
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight = 40.
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 40.
TRAJECTORY_BUILDER_2D.use_imu_data = true

How to make two lidars get merged successfully?

artemiialessandrini commented 4 years ago

SOLVED. Calibration parameters _min_z, maxz taken from some .lua file had to be commended as such:

-- TRAJECTORY_BUILDER_2D.min_z = 0.05
-- TRAJECTORY_BUILDER_2D.max_z = 0.45

I had one lidar much closer to the ground in URDF and didn't notice that in rviz, since config used is top-plane.

Anyway, it solved the problem:)