diff --git a/nav2_costmap_2d/src/costmap_2d_ros.cpp b/nav2_costmap_2d/src/costmap_2d_ros.cpp index 046b9d48dc..0699469320 100644 --- a/nav2_costmap_2d/src/costmap_2d_ros.cpp +++ b/nav2_costmap_2d/src/costmap_2d_ros.cpp @@ -868,7 +868,7 @@ void Costmap2DROS::getCostsCallback( pose_transformed.pose.position.y, mx, my); if (!in_bounds) { - response->costs.push_back(LETHAL_OBSTACLE); + response->costs.push_back(NO_INFORMATION); continue; } // Get the cost at the map coordinates