Skip to content

Commit

Permalink
fix(autoware_surround_obstacle_checker): fix unusedFunction (autoware…
Browse files Browse the repository at this point in the history
…foundation#8774)

fix:unusedFunction

Signed-off-by: kobayu858 <yutaro.kobayashi@tier4.jp>
  • Loading branch information
kobayu858 committed Sep 6, 2024
1 parent eda5011 commit 6bcde92
Show file tree
Hide file tree
Showing 2 changed files with 0 additions and 13 deletions.
10 changes: 0 additions & 10 deletions planning/autoware_surround_obstacle_checker/src/debug_marker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -236,14 +236,4 @@ PolygonStamped SurroundObstacleCheckerDebugNode::boostPolygonToPolygonStamped(
return polygon_stamped;
}

void SurroundObstacleCheckerDebugNode::updateFootprintMargin(
const std::string & object_label, const double front_distance, const double side_distance,
const double back_distance)
{
object_label_ = object_label;
surround_check_front_distance_ = front_distance;
surround_check_side_distance_ = side_distance;
surround_check_back_distance_ = back_distance;
}

} // namespace autoware::surround_obstacle_checker
Original file line number Diff line number Diff line change
Expand Up @@ -66,9 +66,6 @@ class SurroundObstacleCheckerDebugNode
bool pushObstaclePoint(const geometry_msgs::msg::Point & obstacle_point, const PointType & type);
void publish();
void publishFootprints();
void updateFootprintMargin(
const std::string & object_label, const double front_distance, const double side_distance,
const double back_distance);

private:
rclcpp::Publisher<MarkerArray>::SharedPtr debug_viz_pub_;
Expand Down

0 comments on commit 6bcde92

Please sign in to comment.