Skip to content

Navigation Menu

Sign in
Appearance settings

Search code, repositories, users, issues, pull requests...

Provide feedback

We read every piece of feedback, and take your input very seriously.

Saved searches

Use saved searches to filter your results more quickly

Appearance settings
Discussion options

Parts of the map never update:
Even flying around for a while, parts of the map never get any voxels
image

With the following config:

general:
  world_frame: "map"
  logging_level: info
  allow_reset_map_service: true

map:
  type: hashed_chunked_wavelet_octree
  min_cell_width: { meters: 0.2 }

map_operations:
  - type: threshold_map
    once_every: { seconds: 2.0 }
  - type: prune_map
    once_every: { seconds: 10.0 }
  - type: publish_map
    once_every: { seconds: 0.1 }

measurement_integrators:
  ouster_os0_low_res:
    projection_model:
      type: spherical_projector
      elevation:
        num_cells: 64
        min_angle: { degrees: -45.73 }
        max_angle: { degrees: 46.27 }
      azimuth:
        num_cells: 512
        min_angle: { degrees: -180.0 }
        max_angle: { degrees: 180.0 }
    measurement_model:
      type: continuous_beam
      angle_sigma: { degrees: 0.1}
      range_sigma: { meters: 0.05 }
      scaling_free: 0.5
      scaling_occupied: 0.5
    integration_method:
      type: hashed_chunked_wavelet_integrator
      min_range: { meters: 0.3 }
      max_range: { meters: 5 }
      max_update_resolution: { meters: 0.2 }

inputs:
  - type: pointcloud_topic
    topic_name: "/scan_registration_node/preprocessed_cloud_tte"
    topic_type: PointCloud2
    measurement_integrator_names: ouster_os0_low_res
    undistort_motion: false
    topic_queue_length: 1
    max_wait_for_pose: { seconds: 1.0 }

I'm guessing this is due to the center of the cell being further behind the wall than range sigma. So should range_sigma >= max_update_resolution/2?

Doubling range sigma solves this, but has the following problem:

Ghost voxels around robot:
If I increase the range sigma to 0.1, then occupied voxels appear around the drone, even though there are no points in the pointcloud here
image

Reducing range sigma to 0.05 resolves the issue:
image

The problem persists if I switch to continuous_ray with angle_sigma 0.1
image

** Parts of obstacles not represented**
With angle sigma 0.1, and range sigma 0.1
image

We see that a part of a thin wall that is clearly seen by the lidar is marked as free-space

Here we are looking at a long and flap lamp. Parts of the reflection are outside of the voxels,
image

Reducing run-time:
I tried solving this by using multiple integrator with different ranges:

general:
  world_frame: "map"
  logging_level: info
  allow_reset_map_service: true

map:
  type: hashed_chunked_wavelet_octree
  min_cell_width: { meters: 0.05 }

map_operations:
  - type: threshold_map
    once_every: { seconds: 2.0 }
  - type: prune_map
    once_every: { seconds: 10.0 }
  - type: publish_map
    once_every: { seconds: 0.1 }

measurement_integrators:
  ouster_os0_short:
    projection_model:
      type: spherical_projector
      elevation:
        num_cells: 64
        min_angle: { degrees: -45.73 }
        max_angle: { degrees: 46.27 }
      azimuth:
        num_cells: 512
        min_angle: { degrees: -180.0 }
        max_angle: { degrees: 180.0 }
    measurement_model:
      type: continuous_ray
      range_sigma: { meters: 0.025 }
      scaling_free: 0.5
      scaling_occupied: 0.5
    integration_method:
      type: hashed_chunked_wavelet_integrator
      min_range: { meters: 0.5 }
      max_range: { meters: 1 }
      max_update_resolution: { meters: 0.05 }

  ouster_os0_mid:
    projection_model:
      type: spherical_projector
      elevation:
        num_cells: 64
        min_angle: { degrees: -45.73 }
        max_angle: { degrees: 46.27 }
      azimuth:
        num_cells: 512
        min_angle: { degrees: -180.0 }
        max_angle: { degrees: 180.0 }
    measurement_model:
      type: continuous_ray
      range_sigma: { meters: 0.05 }
      scaling_free: 0.5
      scaling_occupied: 0.5
    integration_method:
      type: hashed_chunked_wavelet_integrator
      min_range: { meters: 1.0 }
      max_range: { meters: 3.0 }
      max_update_resolution: { meters: 0.1 }

  ouster_os0_long:
    projection_model:
      type: spherical_projector
      elevation:
        num_cells: 64
        min_angle: { degrees: -45.73 }
        max_angle: { degrees: 46.27 }
      azimuth:
        num_cells: 512
        min_angle: { degrees: -180.0 }
        max_angle: { degrees: 180.0 }
    measurement_model:
      type: continuous_ray
      range_sigma: { meters: 0.1 }
      scaling_free: 0.5
      scaling_occupied: 0.5
    integration_method:
      type: hashed_chunked_wavelet_integrator
      min_range: { meters: 3.0 }
      max_range: { meters: 5.0 }
      max_update_resolution: { meters: 0.2 }

inputs:
  - type: pointcloud_topic
    topic_name: "/scan_registration_node/preprocessed_cloud_tte"
    topic_type: PointCloud2
    measurement_integrator_names: [ouster_os0_short, ouster_os0_mid, ouster_os0_long]
    undistort_motion: false
    topic_queue_length: 1
    max_wait_for_pose: { seconds: 1.0 }

This greatly improved the map, but used too much CPU.
Do you have any tips on how to reduce the CPU requirements?

You must be logged in to vote

Replies: 1 comment · 2 replies

Comment options

And more generally, could you elaborate on how the config should be formatted when the main goal of the occupancy map is to do collision checking for real-time anti collision?

I think the following priorities would be ideal

  • All lidar reflections from a new scan are part of a voxel. Which means that you should not need to see an obstacle multiple times before its marked as occupied, and that each point should be connected to a voxel that will be marked as occupied.
  • Rather too conservative than too liberal wrt free space, but not too much free space should be marked as occupied. Which means that we would rather have a too large voxel than a too small, and that we can require multiple free space observations before marking a voxel as empty.
  • Run time should be kept low to ensure that new obstacle maps can be sent to the anti collision node at 10hz
You must be logged in to vote
2 replies
@victorreijgwart
Comment options

Hi @sverrevr,

Setting a high range_sigma shouldn't cause the map to become occupied at the robot position (what you referred to as ghost voxels). I'm currently on holiday, but I'll look into what could be causing this once I get back.

In the meantime, could you try setting integration_method/min_range to a value >=6*range_sigma and let me know if this solves the issue?

Regarding the tuning recommendations, you should be able to achieve what you want by setting scaling_occupied to a high value relative to scaling_free. Additionally, you could tune map/min_log_odds and/or map/max_log_odds. Setting them closer to 0 reduces the map's maximum confidence on free/occupied space, which reduces the time it takes for objects to fade in/out of the map when they move or are first observed.

@victorreijgwart
Comment options

And could you try the ouster_projector projection model? This should yield some efficiency improvements when working with Ouster LiDARs.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Category
🙏
Q&A
Labels
None yet
2 participants
Morty Proxy This is a proxified and sanitized view of the page, visit original site.