diff --git a/perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/debugger.hpp b/perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/debugger.hpp index afb1f8a729567..d338580d95418 100644 --- a/perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/debugger.hpp +++ b/perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/debugger.hpp @@ -24,9 +24,6 @@ #include #include -#include -#include - namespace obstacle_pointcloud_based_validator { class Debugger diff --git a/perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp b/perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp index 47685dec7dbdc..a16bb63fd0c87 100644 --- a/perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp +++ b/perception/detected_object_validation/include/detected_object_validation/obstacle_pointcloud_based_validator/obstacle_pointcloud_based_validator.hpp @@ -75,6 +75,8 @@ class Validator const autoware_perception_msgs::msg::DetectedObject & object) = 0; size_t getThresholdPointCloud(const autoware_perception_msgs::msg::DetectedObject & object); virtual pcl::PointCloud::Ptr getDebugNeighborPointCloud() = 0; + + virtual ~Validator() = default; }; class Validator2D : public Validator