From 7fea75b9cc5441f8ba26246cc58cee7956161336 Mon Sep 17 00:00:00 2001 From: kobayu858 <129580202+kobayu858@users.noreply.github.com> Date: Tue, 27 Aug 2024 19:32:47 +0900 Subject: [PATCH] fix(autoware_costmap_generator): fix unusedFunction (#8641) fix:unusedFunction Signed-off-by: kobayu858 --- .../object_map_utils.hpp | 23 ------------------- .../object_map_utils.cpp | 19 --------------- 2 files changed, 42 deletions(-) diff --git a/planning/autoware_costmap_generator/include/autoware_costmap_generator/object_map_utils.hpp b/planning/autoware_costmap_generator/include/autoware_costmap_generator/object_map_utils.hpp index f4911cc428d36..55a032fc8bb5a 100644 --- a/planning/autoware_costmap_generator/include/autoware_costmap_generator/object_map_utils.hpp +++ b/planning/autoware_costmap_generator/include/autoware_costmap_generator/object_map_utils.hpp @@ -52,29 +52,6 @@ namespace object_map { -/*! - * Publishes in_gridmap using the specified in_publisher - * @param[in] in_gridmap GridMap object to publish - * @param[in] in_publisher Valid Publisher object to use - */ -void PublishGridMap( - const grid_map::GridMap & in_gridmap, - const rclcpp::Publisher::SharedPtr in_publisher); - -/*! - * Convert and publishes a GridMap layer to a standard Ros OccupancyGrid - * @param[in] in_gridmap GridMap object to extract the layer - * @param[in] in_publisher ROS Publisher to use to publish the occupancy grid - * @param[in] in_layer Name of the layer to convert - * @param[in] in_min_value Minimum value in the layer - * @param[in] in_max_value Maximum value in the layer - */ - -void PublishOccupancyGrid( - const grid_map::GridMap & in_gridmap, - const rclcpp::Publisher::SharedPtr in_publisher, - const std::string & in_layer, double in_min_value, double in_max_value, double in_height); - /*! * Projects the in_area_points forming the road, stores the result in out_grid_map. * @param[out] out_grid_map GridMap object to add the road grid diff --git a/planning/autoware_costmap_generator/nodes/autoware_costmap_generator/object_map_utils.cpp b/planning/autoware_costmap_generator/nodes/autoware_costmap_generator/object_map_utils.cpp index 4ce452814008c..f719f7a81cbf2 100644 --- a/planning/autoware_costmap_generator/nodes/autoware_costmap_generator/object_map_utils.cpp +++ b/planning/autoware_costmap_generator/nodes/autoware_costmap_generator/object_map_utils.cpp @@ -37,25 +37,6 @@ namespace object_map { -void PublishGridMap( - const grid_map::GridMap & in_gridmap, - const rclcpp::Publisher::SharedPtr in_publisher) -{ - auto message = grid_map::GridMapRosConverter::toMessage(in_gridmap); - in_publisher->publish(*message); -} - -void PublishOccupancyGrid( - const grid_map::GridMap & in_gridmap, - const rclcpp::Publisher::SharedPtr in_publisher, - const std::string & in_layer, double in_min_value, double in_max_value, double in_height) -{ - nav_msgs::msg::OccupancyGrid message; - grid_map::GridMapRosConverter::toOccupancyGrid( - in_gridmap, in_layer, in_min_value, in_max_value, message); - message.info.origin.position.z = in_height; - in_publisher->publish(message); -} void FillPolygonAreas( grid_map::GridMap & out_grid_map,