From 7bf0f7f99647ba8cbc6b7c8add1bcc4a501de887 Mon Sep 17 00:00:00 2001 From: Autumn60 <37181352+Autumn60@users.noreply.github.com> Date: Sun, 8 Sep 2024 01:10:49 +0900 Subject: [PATCH] Update costmap_generator.cpp --- .../booars_costmap_generator/src/costmap_generator.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/aichallenge/workspace/src/aichallenge_submit/costmap/booars_costmap_generator/src/costmap_generator.cpp b/aichallenge/workspace/src/aichallenge_submit/costmap/booars_costmap_generator/src/costmap_generator.cpp index 60b34007..a4d182b3 100644 --- a/aichallenge/workspace/src/aichallenge_submit/costmap/booars_costmap_generator/src/costmap_generator.cpp +++ b/aichallenge/workspace/src/aichallenge_submit/costmap/booars_costmap_generator/src/costmap_generator.cpp @@ -80,14 +80,14 @@ void CostmapGenerator::update() // Fill the costmap data { + PointStamped global_point; + global_point.header.frame_id = map_frame_; + global_point.header.stamp = costmap_time; + global_point.point.z = 0.0; for (int i = 0; i < costmap_parameters_->grid_num(); i++) { Point2d local_point = index_to_point_table_[i]; - PointStamped global_point; - global_point.header.frame_id = map_frame_; - global_point.header.stamp = costmap_time; global_point.point.x = local_point[0] + costmap_center_position.x; global_point.point.y = local_point[1] + costmap_center_position.y; - global_point.point.z = 0.0; costmap_->data[i] = multi_layered_costmap_->is_occupied(global_point) ? 100 : 0; } }