autoware_probabilistic_occupancy_grid_map#
Purpose#
This package outputs the probability of having an obstacle as occupancy grid map.
References/External links#
Settings#
Occupancy grid map is generated on map_frame
, and grid orientation is fixed.
You may need to choose scan_origin_frame
and gridmap_origin_frame
which means sensor origin and gridmap origin respectively. Especially, set your main LiDAR sensor frame (e.g. velodyne_top
in sample_vehicle) as a scan_origin_frame
would result in better performance.
Parameters#
-
binary bayes filter updater
Name Type Description Default Range probability_matrix.occupied_to_occupied float Probability of transitioning from occupied to occupied state. 0.95 N/A probability_matrix.occupied_to_free float Probability of transitioning from occupied to free state. 0.05 N/A probability_matrix.free_to_occupied float Probability of transitioning from free to occupied state. 0.2 N/A probability_matrix.free_to_free float Probability of transitioning from free to free state. 0.8 N/A v_ratio float Ratio of the variance used in the filter. 0.1 N/A
-
grid map
Name Type Description Default Range type string The type of grid map visualization. occupancy_grid N/A params.layer string The layer of the grid map visualization. filled_free_to_farthest N/A params.data_min float The minimum data value for the visualization. 0.0 N/A params.data_max float The maximum data value for the visualization. 100.0 N/A
-
laserscan based occupancy grid map
Name Type Description Default Range use_height_filter boolean Flag to use height filter. 1 N/A min_height float Minimum height for the height filter. -1 N/A max_height float Maximum height for the height filter. 2 N/A
-
multi lidar pointcloud based occupancy grid map
Name Type Description Default Range use_height_filter boolean Flag to use height filter. 1 N/A min_height float Minimum height for the height filter. -1 N/A max_height float Maximum height for the height filter. 2 N/A
-
pointcloud based occupancy grid map
Name Type Description Default Range use_height_filter boolean Flag to use height filter. 1 N/A min_height float Minimum height for the height filter. -1 N/A max_height float Maximum height for the height filter. 2 N/A
-
synchronized grid map fusion
Name Type Description Default Range fusion_input_ogm_topics array List of fusion input occupancy grid map topics. ['topic1', 'topic2'] N/A input_ogm_reliabilities array Reliability of each sensor for fusion. [0.8, 0.2] N/A fusion_method string Method for occupancy grid map fusion. overwrite ['overwrite', 'log-odds', 'dempster-shafer'] match_threshold_sec float Time threshold for matching in seconds. 0.01 N/A timeout_sec float Timeout for synchronization in seconds. 0.1 N/A input_offset_sec array Offset for each input in seconds. [0.0, 0.0] N/A map_frame_ string The frame ID of the map. map N/A base_link_frame_ string The frame ID of the base link. base_link N/A grid_map_origin_frame_ string The frame ID of the grid map origin. base_link N/A fusion_map_length_x float The length of the fusion map in the x direction. 100.0 N/A fusion_map_length_y float The length of the fusion map in the y direction. 100.0 N/A fusion_map_resolution float The resolution of the fusion map. 0.5 N/A publish_processing_time_detail boolean True for showing detail of publish processing time. False N/A
Downsample input pointcloud(Optional)#
If you set downsample_input_pointcloud
to true
, the input pointcloud will be downsampled and following topics are also used. This feature is currently only for the pointcloud based occupancy grid map.
- pointcloud_based_occupancy_grid_map method
# downsampled raw and obstacle pointcloud
/perception/occupancy_grid_map/obstacle/downsample/pointcloud
/perception/occupancy_grid_map/raw/downsample/pointcloud
- multi_lidar_pointcloud_based_point_cloud
# downsampled raw and obstacle pointcloud
/perception/occupancy_grid_map/obstacle/downsample/pointcloud
/perception/occupancy_grid_map/<sensor_name>/raw/downsample/pointcloud
Test#
This package provides unit tests using gtest
.
You can run the test by the following command.
colcon test --packages-select autoware_probabilistic_occupancy_grid_map --event-handlers console_direct+
Test contains the following.
- Unit test for cost value conversion function
- Unit test for utility functions
- Unit test for occupancy grid map fusion functions
- Input/Output test for pointcloud based occupancy grid map