`voxel_min_points` parameter not working
Srijan221 opened this issue · comments
We observed "ghost points" from noise generated by depth cameras as seen in the images below. Ghost points are marked in blue, and it comes at random.
To mitigate this issue we looked into voxel_min_points
and set it to different values ranging from 5 to 50. But, this didn't have any effect as seen in the image below -
Here is the plugin param config -
enabled: true
voxel_decay: 20 #seconds if linear, e^n if exponential
decay_model: 0 #0=linear, 1=exponential, -1=persistent
voxel_size: 0.05 #meters
track_unknown_space: true #default space is unknown
observation_persistence: 0.0 #seconds
max_obstacle_height: 1.0 #meters
unknown_threshold: 15 #voxel height
mark_threshold: 0 #voxel height
update_footprint_enabled: true
combination_method: 1 #1=max, 0=override
obstacle_range: 3.0 #meters
origin_z: 0.0 #meters
publish_voxel_map: true # default off
transform_tolerance: 0.2 # seconds
mapping_mode: false # default off, saves map not for navigation
map_save_duration: 60 #default 60s, how often to autosave
observation_sources: rgbd1_clear rgbd1_mark
rgbd1_mark:
data_type: PointCloud2
topic: camera/depth_registered/points
marking: true
clearing: false
min_obstacle_height: 0.03 #default 0, meters
max_obstacle_height: 1.0 #defaule 3, meters
expected_update_rate: 0.0 #default 0, if not updating at this rate at least, 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 laser scans
clear_after_reading: true #default false, clear the buffer after the layer gets readings from it
filter: "voxel" #default passthrough, apply "voxel", "passthrough", or no filter to sensor data, recommended to have at one filter on
voxel_min_points: 10 #default 0, minimum points per voxel for voxel filter
rgbd1_clear:
enabled: true #default true, can be toggled on/off with associated service call
data_type: PointCloud2
topic: camera/depth_registered/points
marking: false
clearing: true
min_z: 0 #default 0, meters
max_z: 7.0 #default 10, meters
vertical_fov_angle: 0.7 #default 0.7, radians
horizontal_fov_angle: 1.04 #default 1.04, radians
decay_acceleration: 500 #default 0, 1/s^2. If laser scanner MUST be 0
model_type: 0 #default 0 (depth camera). Use 1 for 3D Lidar
Kindly suggest a workaround for removing ghost points and why changing the voxel_min_points
param doesn't work in our case
What version of this software are you using and is it actually released in that distribution?
I see these "plus sign" items in the costmap but that's not what I'm seeing in the visualized STVL grid. What's going on there?
Hello Steve,
We are using Melodic-devel Ros1 Distribution and download the software from binaries.
The camera used is Intel Realsense D455 and whole plugin is run on a Jetson Xavier NX.
The plus signs are the ghost points which comes at random locations and there is no object corresponding to it in the real world. Also the STVL grid only makes a cube voxel for every plus sign which I am not sure the reason it happens.
I was just wondering can voxel_min_points
parameter fix this plus sign issue by maybe not assigning a voxel to these ghost points?
Also the STVL grid only makes a cube voxel for every plus sign which I am not sure the reason it happens.
That doesn't seem related to STVL, I'm not sure what that relates to though. I've never seen anything like that before unless you've made your parameters really wacky.
Print before this line the value of the min voxel size https://github.com/SteveMacenski/spatio_temporal_voxel_layer/blob/melodic-devel/src/measurement_buffer.cpp#L164. If you get a non-zero number, then your gripe is with pcl. If you get a zero-value, I can look into it.
I was just wondering can voxel_min_points parameter fix this plus sign issue by maybe not assigning a voxel to these ghost points?
I don't know what / how you managed to get those plus signs (other costmap layers after this?) so I doubt that's in any way related.
This is an issue with PCL. The original Voxel Filter implementation used the original XYZ pointcloud message format and worked with the min_points
parameter. With the transition to the PointCloud2 format, the parameter was left there exposed but it doesn't do anything. If it ever gets fixed in PCL, then it will automagically work with STVL (and would be very handy indeed).
Print before this line the value of the min voxel size https://github.com/SteveMacenski/spatio_temporal_voxel_layer/blob/melodic-devel/src/measurement_buffer.cpp#L164. If you get a non-zero number, then your gripe is with pcl. If you get a zero-value, I can look into it.
Moreover, we have used the default pointcloud from the ros realsense wrapper and no other costmap layers are added in our implementation.
I tried printing, but the code doesn't seem to enter that block, it doesn't print any value (zero / non-zero), not even any static string written in that line.
Those plus signs, in my opinion are due to the lighting conditions in the room, maybe due to reflections.
I have tried using two different Realsense - Realsense D415 and D455,
Below are some errors observed with Realsense d455 -
As you can see in the image above, the reflection due to the sunlight causes a random voxel to appear in the map and it is marked onto the costmap with an inflation which should not happen in a general case.
And, ghost points appear at locations that aren't in the field of view of camera as you can see above.
I am just looking for voxel_min_points
to somehow remove these unwanted voxels to appear or mark in the costmap altogether.