The costmap_generator Package
costmap_generator_node
This node reads PointCloud and/or DynamicObjectArray and creates an OccupancyGrid and GridMap. VectorMap(Lanelet2) is optional.
| Name | Type | Description | 
| ~input/objects | autoware_perception_msgs::DynamicObjectArray | predicted objects, for obstacles areas | 
| ~input/points_no_ground | sensor_msgs::PointCloud2 | ground-removed points, for obstacle areas which can't be detected as objects | 
| ~input/vector_map | autoware_lanelet2_msgs::MapBin | vector map, for drivable areas | 
| ~input/scenario | autoware_planning_msgs::Scenario | scenarios to be activated, for node activation | 
Output topics
| Name | Type | Description | 
| ~output/grid_map | grid_map_msgs::GridMap | - costmap as GridMap, values are from 0.0 to 1.0 | 
| ~output/occupancy_grid | nav_msgs::OccupancyGrid | - costmap as OccupancyGrid, values are from 0 to 100 | 
Output TFs
None
How to launch
- Write your remapping info in costmap_generator.launchor add args when executingroslaunch
- Run roslaunch costmap_generator costmap_generator.launch
Parameters
| Name | Type | Description | 
| update_rate | double | timer's update rate | 
| use_objects | bool | whether using ~input/objectsor not | 
| use_points | bool | whether using ~input/points_no_groundor not | 
| use_wayarea | bool | whether using wayareafrom~input/vector_mapor not | 
| costmap_frame | string | created costmap's coordinate | 
| vehicle_frame | string | vehicle's coordinate | 
| map_frame | string | map's coordinate | 
| grid_min_value | double | minimum cost for gridmap | 
| grid_max_value | double | maximum cost for gridmap | 
| grid_resolution | double | resolution for gridmap | 
| grid_length_x | int | size of gridmap for x direction | 
| grid_length_y | int | size of gridmap for y direction | 
| grid_position_x | int | offset from coordinate in x direction | 
| grid_position_y | int | offset from coordinate in y direction | 
| maximum_lidar_height_thres | double | maximum height threshold for pointcloud data | 
| minimum_lidar_height_thres | double | minimum height threshold for pointcloud data | 
| expand_rectangle_size | double | expand object's rectangle with this value | 
| size_of_expansion_kernel | int | kernel size for blurring effect on object's costmap | 
Flowchart
