From 9289b35cafc87dd1d31977bf09b341e774426b58 Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Wed, 3 Jul 2024 10:19:09 +0900 Subject: [PATCH] fix(lidar_apollo_segmentation_tvm): add virtual destructor to lidar_apollo_segmentation_tvm (#7762) * fix(lidar_apollo_segmentation_tvm): add virtual destructor to lidar_apollo_segmentation_tvm Signed-off-by: Y.Hisaki * small change Signed-off-by: Y.Hisaki --------- Signed-off-by: Y.Hisaki --- .../lidar_apollo_segmentation_tvm/feature_generator.hpp | 2 -- .../include/lidar_apollo_segmentation_tvm/feature_map.hpp | 3 ++- .../lidar_apollo_segmentation_tvm.hpp | 5 ----- .../src/feature_generator.cpp | 5 +---- .../src/lidar_apollo_segmentation_tvm.cpp | 7 +------ 5 files changed, 4 insertions(+), 18 deletions(-) diff --git a/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/feature_generator.hpp b/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/feature_generator.hpp index 5cecda966d198..84cf7957d2e7e 100644 --- a/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/feature_generator.hpp +++ b/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/feature_generator.hpp @@ -37,8 +37,6 @@ namespace lidar_apollo_segmentation_tvm class LIDAR_APOLLO_SEGMENTATION_TVM_LOCAL FeatureGenerator { private: - const bool use_intensity_feature_; - const bool use_constant_feature_; const float min_height_; const float max_height_; std::shared_ptr map_ptr_; diff --git a/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/feature_map.hpp b/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/feature_map.hpp index 349dfc7f1f0ad..f78f11c8aed56 100644 --- a/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/feature_map.hpp +++ b/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/feature_map.hpp @@ -15,7 +15,7 @@ #ifndef LIDAR_APOLLO_SEGMENTATION_TVM__FEATURE_MAP_HPP_ #define LIDAR_APOLLO_SEGMENTATION_TVM__FEATURE_MAP_HPP_ -#include +#include #include namespace autoware @@ -45,6 +45,7 @@ struct FeatureMapInterface virtual void initializeMap(std::vector & map) = 0; virtual void resetMap(std::vector & map) = 0; explicit FeatureMapInterface(int32_t _channels, int32_t _width, int32_t _height, int32_t _range); + virtual ~FeatureMapInterface() {} }; /// \brief FeatureMap with no extra feature channels. diff --git a/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/lidar_apollo_segmentation_tvm.hpp b/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/lidar_apollo_segmentation_tvm.hpp index 7f8c5f51f73a6..044f319c4d335 100644 --- a/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/lidar_apollo_segmentation_tvm.hpp +++ b/perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/lidar_apollo_segmentation_tvm.hpp @@ -164,12 +164,7 @@ class LIDAR_APOLLO_SEGMENTATION_TVM_PUBLIC ApolloLidarSegmentation tvm_utility::Version version_check() const; private: - const int32_t range_; - const float score_threshold_; const float z_offset_; - const float objectness_thresh_; - const int32_t min_pts_num_; - const float height_thresh_; const pcl::PointCloud::Ptr pcl_pointcloud_ptr_; // Earliest supported model version. const std::array model_version_from{2, 0, 0}; diff --git a/perception/lidar_apollo_segmentation_tvm/src/feature_generator.cpp b/perception/lidar_apollo_segmentation_tvm/src/feature_generator.cpp index edf8276065163..fd038efc60ffb 100644 --- a/perception/lidar_apollo_segmentation_tvm/src/feature_generator.cpp +++ b/perception/lidar_apollo_segmentation_tvm/src/feature_generator.cpp @@ -35,10 +35,7 @@ inline float normalizeIntensity(float intensity) FeatureGenerator::FeatureGenerator( const int32_t width, const int32_t height, const int32_t range, const bool use_intensity_feature, const bool use_constant_feature, const float min_height, const float max_height) -: use_intensity_feature_(use_intensity_feature), - use_constant_feature_(use_constant_feature), - min_height_(min_height), - max_height_(max_height) +: min_height_(min_height), max_height_(max_height) { // select feature map type if (use_constant_feature && use_intensity_feature) { diff --git a/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp b/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp index e78cd57b3a4a1..9d41770eb5331 100644 --- a/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp +++ b/perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp @@ -109,12 +109,7 @@ ApolloLidarSegmentation::ApolloLidarSegmentation( int32_t range, float score_threshold, bool use_intensity_feature, bool use_constant_feature, float z_offset, float min_height, float max_height, float objectness_thresh, int32_t min_pts_num, float height_thresh, const std::string & data_path) -: range_(range), - score_threshold_(score_threshold), - z_offset_(z_offset), - objectness_thresh_(objectness_thresh), - min_pts_num_(min_pts_num), - height_thresh_(height_thresh), +: z_offset_(z_offset), pcl_pointcloud_ptr_(new pcl::PointCloud), PreP(std::make_shared( config, range, use_intensity_feature, use_constant_feature, min_height, max_height)),