Robot is leaving obstacle marks while mapping manually

Hi @Raffaello,

I wanted to do a manual mapping using slam_toolbox as it is the same method to do mapping in Nova Carter Bringup package (nova_carter/nova_carter_bringup/launch/lidar_mapping.launch.py at 7e44644c21809d7a8c68aad6a7219e3f4c41c9f0 · NVIDIA-ISAAC-ROS/nova_carter · GitHub). I know Isaac Sim is already providing this map from within Isaac Sim Util > Occupancy Map but I wanted to do it manually.

However, when I start the slam_toolbox with ros2 launch slam_toolbox online_async_launch.py and manually teleoperate the robot around the scene in Isaac Sim using my keyboard, the Nova Carter robot leaves regular obstacle marks behind as it moves.

These black marks show up as obstacles when I spin up the Nav2 stack right after I create the map:

Why would this happen? I’m already using Nova Carter’s params yaml file provided here: IsaacSim-ros_workspaces/humble_ws/src/navigation/carter_navigation/params/carter_navigation_params.yaml at d686d155dd5878a448fd253966bdc8427a5b4734 · isaac-sim/IsaacSim-ros_workspaces · GitHub

Thanks in advance.

Hey @Raffaello, it would be great to hear your opinions on this. Thanks.

I think I understand the problem now. I just saw this imaginary \_/ shaped obstacle right behind the front_2d_lidar in Rviz visualization.

When I check the simulation frame, it looks like the very same shape of the Carter’s top enclosure right under the Hesai Lidar (\_/):

  back_2d_lidar
       /‾\
Carter Top Enclosure
       \_/
  front_2d_lidar

What is the correct way to disregard some of the angles from the front_2d_lidar in Isaac ROS applications? Especially when integrating them with third-party ROS packages.

Hey @dsonmez! According to your information, it seems to be related to the parameters you use in slam_toolbox. Could you please attach the config file you use for slam_toolbox? I suspect it is related to the min_laser_range(link).

Hey @zhengwang, thank you for your interest. You’re right, I also played with that value but it appears it doesn’t care what value I put for the min_laser_range. You can find my modified mapper_params_online_async.yaml file here (yaml file upload is not permitted):

slam_toolbox:
  ros__parameters:

    # Plugin params
    solver_plugin: solver_plugins::CeresSolver
    ceres_linear_solver: SPARSE_NORMAL_CHOLESKY
    ceres_preconditioner: SCHUR_JACOBI
    ceres_trust_strategy: LEVENBERG_MARQUARDT
    ceres_dogleg_type: TRADITIONAL_DOGLEG
    ceres_loss_function: None

    # ROS Parameters
    odom_frame: odom
    map_frame: map
    base_frame: base_link # Changed this for the Isaac Sim odometry topic name
    scan_topic: /scan
    use_map_saver: true
    mode: mapping #localization

    # if you'd like to immediately start continuing a map at a given pose
    # or at the dock, but they are mutually exclusive, if pose is given
    # will use pose
    #map_file_name: test_steve
    # map_start_pose: [0.0, 0.0, 0.0]
    #map_start_at_dock: true

    debug_logging: false
    throttle_scans: 1
    transform_publish_period: 0.02 #if 0 never publishes odometry
    map_update_interval: 5.0
    resolution: 0.05
    min_laser_range: 5.0
    max_laser_range: 20.0 #for rastering images
    minimum_time_interval: 0.5
    transform_timeout: 0.2
    tf_buffer_duration: 30.
    stack_size_to_use: 40000000 #// program needs a larger stack size to serialize large maps
    enable_interactive_mode: true

    # General Parameters
    use_scan_matching: true
    use_scan_barycenter: true
    minimum_travel_distance: 0.5
    minimum_travel_heading: 0.5
    scan_buffer_size: 10
    scan_buffer_maximum_scan_distance: 10.0
    link_match_minimum_response_fine: 0.1  
    link_scan_maximum_distance: 1.5
    loop_search_maximum_distance: 3.0
    do_loop_closing: true 
    loop_match_minimum_chain_size: 10           
    loop_match_maximum_variance_coarse: 3.0  
    loop_match_minimum_response_coarse: 0.35    
    loop_match_minimum_response_fine: 0.45

    # Correlation Parameters - Correlation Parameters
    correlation_search_space_dimension: 0.5
    correlation_search_space_resolution: 0.01
    correlation_search_space_smear_deviation: 0.1 

    # Correlation Parameters - Loop Closure Parameters
    loop_search_space_dimension: 8.0
    loop_search_space_resolution: 0.05
    loop_search_space_smear_deviation: 0.03

    # Scan Matcher Parameters
    distance_variance_penalty: 0.5      
    angle_variance_penalty: 1.0    

    fine_search_angle_offset: 0.00349     
    coarse_search_angle_offset: 0.349   
    coarse_angle_resolution: 0.0349        
    minimum_angle_penalty: 0.9
    minimum_distance_penalty: 0.5
    use_response_expansion: true

There is also this file nova_carter/nova_carter_navigation/params/nova_carter_navigation.yaml at main · NVIDIA-ISAAC-ROS/nova_carter · GitHub used for the slam_toolbox as the configuration file in the Nova Carter ROS package. However, even though I tried to use this one by aligning my published topics, I’m not able to get a correct mapping in the Rviz.

I even used the pointcloud_to_laserscan ROS package to publish /front_3d_lidar/scan topic, but it didn’t work.

Do you have any ideas on which parts can be used from nova_carter_navigation.yaml in this case? I see the robot’s footprint is on that configuration but not the min_laser_range, so it has to be something different.

Have you tried launching lidar_mapping.launch.py (link)?

In this launch file, it uses the params/nova_carter_navigation.yaml as the param file. But in params/nova_carter_navigation.yaml, the min_laser_range is not specified so you need to add it into that file yourself. Otherwise, it will just use a default value.
You can also pass an argument for lidar_mapping_parameters_path with the param file created by yourself when you launch lidar_mapping.

Hi @zhengwang, sorry for the late reply. I just gave it another shot using the nova_carter_bringup package. Here is the path I took:

  1. Started the Isaac Sim 4.0.0 and got the following topics published:

  2. Run the pointcloud_to_laserscan package to publish /front_3d_lidar/scan topic:

  3. I’ve included min_laser_range: 0.0 setting to the nova_carter_navigation/params/nova_carter_navigation.yaml and launched lidar_mapping.launch.py with mode:=simulation argument:

  4. Started the Rviz with ros2 run rviz2 rviz2 -d carter_navigation/rviz2/carter_navigation.rviz:


With all these, I’m able to get a 3D model of the Nova Carter on the Rviz but I can not get the mapping areas except those weird black and white dots left behind the robot.