Skip to content

Commit

Permalink
fix(autoware_costmap_generator): fix unusedFunction (autowarefoundati…
Browse files Browse the repository at this point in the history
…on#8641)

fix:unusedFunction

Signed-off-by: kobayu858 <[email protected]>
  • Loading branch information
kobayu858 authored Aug 27, 2024
1 parent 1458bbc commit 7fea75b
Show file tree
Hide file tree
Showing 2 changed files with 0 additions and 42 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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<grid_map_msgs::msg::GridMap>::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<nav_msgs::msg::OccupancyGrid>::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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -37,25 +37,6 @@

namespace object_map
{
void PublishGridMap(
const grid_map::GridMap & in_gridmap,
const rclcpp::Publisher<grid_map_msgs::msg::GridMap>::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<nav_msgs::msg::OccupancyGrid>::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,
Expand Down

0 comments on commit 7fea75b

Please sign in to comment.