Skip to content

Commit

Permalink
update booars_costmap_generator
Browse files Browse the repository at this point in the history
Signed-off-by: Autumn60 <[email protected]>
  • Loading branch information
Autumn60 committed Sep 2, 2024
1 parent af5a2f0 commit 3e972bd
Show file tree
Hide file tree
Showing 2 changed files with 18 additions and 7 deletions.
Original file line number Diff line number Diff line change
@@ -1,17 +1,28 @@
/**:
ros__parameters:
update_rate: 10.0
update_rate: 20.0
map_frame_id: "map"
costmap_center_frame_id: "base_link"
costmap_width: 20.0
costmap_resolution: 0.1
costmap_width: 50.0
costmap_resolution: 0.2
multi_layered_costmap:
layers:
- "lanelet_layer"
- "cached_lanelet_layer"
# - "lanelet_layer"
- "predicted_object_layer"
lanelet_layer:
type: "lanelet"
cached_lanelet_layer:
type: "cached_lanelet"
map_topic: "/map/vector_map"
costmap_topic: "~/debug/cached_costmap"
cached_costmap:
min_x: 89607.0
max_x: 89687.0
min_y: 43114.0
max_y: 43194.0
resolution: 0.1
# lanelet_layer:
# type: "lanelet"
# map_topic: "/map/vector_map"
predicted_object_layer:
type: "predicted_object"
predicted_objects_topic: "/perception/object_recognition/objects"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ CostmapGenerator::CostmapGenerator(const rclcpp::NodeOptions & options)
double costmap_width = this->declare_parameter("costmap_width", 10.0);
double costmap_resolution = this->declare_parameter("costmap_resolution", 0.1);
costmap_parameters_ =
OccupancyGridParameters::create_parameters(costmap_width, costmap_resolution);
OccupancyGridParameters::create_parameters(costmap_width, costmap_width, costmap_resolution);
index_to_point_table_ =
booars_utils::nav::occupancy_grid_utils::get_index_to_point_table(costmap_parameters_);
}
Expand Down

0 comments on commit 3e972bd

Please sign in to comment.