SteveMacenski / spatio_temporal_voxel_layer

A new voxel layer leveraging modern 3D graphics tools to modernize navigation environmental representations
http://wiki.ros.org/spatio_temporal_voxel_layer
GNU Lesser General Public License v2.1
644 stars 189 forks source link

Questions about Parameters #302

Closed HappySamuel closed 3 months ago

HappySamuel commented 3 months ago

Hi

I am curious what are the difference between these parameters min/max_obstacle_height and min/max_z ??? Are there any difference for these parameters when using 3d lidar vs rgbd camera

Also, must _mark having marking: true | clearing: false and _clear having marking: false | clearing: true separated into two different observation_sources? Why?

Best Samuel

SteveMacenski commented 3 months ago

Height is the height off of the map frame and min/max z are ranges - since usually that's the way the pointclouds from depth cameras and lidars are oriented. I can appreciate the confusion though, I could have made that named more clearly.

A layer can have both marking and clearing, I forget why off hand we have them separated in the default examples. I think I might have the settings slightly different (or could be a simplified version of a file I was using at a company at the time I stripped back to just 1 sensor)

HappySamuel commented 3 months ago

Hi @SteveMacenski

Thanks for the explanation about those parameters.

Now understood that min/max_obstacle_height is refer to the z-axis of the frame. But is it fixed to /map frame or global_frame of the costmap? For example, local_costmap is using /odom, while global_costmap is using /map.

And the min/max_z are use to clip the range [m] from sensors' data. Do correct me if i understand wrongly.

Regarding the layer, is that mean we can have both marking: true & clearing: true defined together in one source for observation_sources? Below is my current configuration, not sure if is there anything else i need to change / take note? As i am using 3D lidar.

        lslidar:
          data_type: PointCloud2
          topic: /lslidar_c16/points
          marking: true
          clearing: true
          min_obstacle_height: -0.2 #[m]
          max_obstacle_height: 0.5  #[m]
          expected_update_rate: 0.0 #default 0, if not updating at least this rate, remove from buffer
          observation_persistence: 0.0 #default 0, use all measurements taken during now value, 0=latest
          inf_is_valid: false  #default false, for laserscan
          voxel_filter: true   #default off, apply voxel filter to sensor, recommend on
          voxel_min_points: 20 #default 0, min pts per voxel for voxel filter
          clear_after_reading: true #default false, clear the buffer after the layer gets readings from it
          max_z: 1.0 #[m]
          min_z: -0.5 #[m]
          vertical_fov_angle: 0.5236 #[rad]
          horizontal_fov_angle: 6.2832 #[rad]
          decay_acceleration: 10.0 #default 0, 1/s^2. If laserscan MUST be 0
          model_type: 1 #model type for frustum. 0=depth_camera , 1=3d_lidar

Best, Samuel

SteveMacenski commented 3 months ago

global_frame of the costmap

This :-)

is that mean we can have both marking: true & clearing: true defined together in one source for observation_sources

Yes :-)

HappySamuel commented 2 months ago

Hi @SteveMacenski

For example of my config of my front_cam on the stvl_layer below. I got them with ros2 param list

  stvl_layer.front_cam.clear_after_reading
  stvl_layer.front_cam.clearing
  stvl_layer.front_cam.data_type
  stvl_layer.front_cam.decay_acceleration
  stvl_layer.front_cam.enabled
  stvl_layer.front_cam.expected_update_rate
  stvl_layer.front_cam.filter
  stvl_layer.front_cam.horizontal_fov_angle
  stvl_layer.front_cam.inf_is_valid
  stvl_layer.front_cam.marking
  stvl_layer.front_cam.max_obstacle_height
  stvl_layer.front_cam.max_z
  stvl_layer.front_cam.min_obstacle_height
  stvl_layer.front_cam.min_z
  stvl_layer.front_cam.model_type
  stvl_layer.front_cam.observation_persistence
  stvl_layer.front_cam.obstacle_range
  stvl_layer.front_cam.sensor_frame
  stvl_layer.front_cam.topic
  stvl_layer.front_cam.vertical_fov_angle
  stvl_layer.front_cam.vertical_fov_padding
  stvl_layer.front_cam.voxel_min_points

What are the difference between min/max_z and obstacle_range ? Because when i change obstacle_range, actual detection range will change. However, min/max_z did nothing at all.

Another one is the filter , if i choose passthrough , what are the parameters to control this passthrough filter. If selecting voxel , it's controlled by voxel_min_points , right?

Best, Samuel