Skip to content

Commit 9289b35

Browse files
authored
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 <yhisaki31@gmail.com> * small change Signed-off-by: Y.Hisaki <yhisaki31@gmail.com> --------- Signed-off-by: Y.Hisaki <yhisaki31@gmail.com>
1 parent 1069e18 commit 9289b35

File tree

5 files changed

+4
-18
lines changed

5 files changed

+4
-18
lines changed

perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/feature_generator.hpp

-2
Original file line numberDiff line numberDiff line change
@@ -37,8 +37,6 @@ namespace lidar_apollo_segmentation_tvm
3737
class LIDAR_APOLLO_SEGMENTATION_TVM_LOCAL FeatureGenerator
3838
{
3939
private:
40-
const bool use_intensity_feature_;
41-
const bool use_constant_feature_;
4240
const float min_height_;
4341
const float max_height_;
4442
std::shared_ptr<FeatureMapInterface> map_ptr_;

perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/feature_map.hpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@
1515
#ifndef LIDAR_APOLLO_SEGMENTATION_TVM__FEATURE_MAP_HPP_
1616
#define LIDAR_APOLLO_SEGMENTATION_TVM__FEATURE_MAP_HPP_
1717

18-
#include <memory>
18+
#include <cstdint>
1919
#include <vector>
2020

2121
namespace autoware
@@ -45,6 +45,7 @@ struct FeatureMapInterface
4545
virtual void initializeMap(std::vector<float> & map) = 0;
4646
virtual void resetMap(std::vector<float> & map) = 0;
4747
explicit FeatureMapInterface(int32_t _channels, int32_t _width, int32_t _height, int32_t _range);
48+
virtual ~FeatureMapInterface() {}
4849
};
4950

5051
/// \brief FeatureMap with no extra feature channels.

perception/lidar_apollo_segmentation_tvm/include/lidar_apollo_segmentation_tvm/lidar_apollo_segmentation_tvm.hpp

-5
Original file line numberDiff line numberDiff line change
@@ -164,12 +164,7 @@ class LIDAR_APOLLO_SEGMENTATION_TVM_PUBLIC ApolloLidarSegmentation
164164
tvm_utility::Version version_check() const;
165165

166166
private:
167-
const int32_t range_;
168-
const float score_threshold_;
169167
const float z_offset_;
170-
const float objectness_thresh_;
171-
const int32_t min_pts_num_;
172-
const float height_thresh_;
173168
const pcl::PointCloud<pcl::PointXYZI>::Ptr pcl_pointcloud_ptr_;
174169
// Earliest supported model version.
175170
const std::array<int8_t, 3> model_version_from{2, 0, 0};

perception/lidar_apollo_segmentation_tvm/src/feature_generator.cpp

+1-4
Original file line numberDiff line numberDiff line change
@@ -35,10 +35,7 @@ inline float normalizeIntensity(float intensity)
3535
FeatureGenerator::FeatureGenerator(
3636
const int32_t width, const int32_t height, const int32_t range, const bool use_intensity_feature,
3737
const bool use_constant_feature, const float min_height, const float max_height)
38-
: use_intensity_feature_(use_intensity_feature),
39-
use_constant_feature_(use_constant_feature),
40-
min_height_(min_height),
41-
max_height_(max_height)
38+
: min_height_(min_height), max_height_(max_height)
4239
{
4340
// select feature map type
4441
if (use_constant_feature && use_intensity_feature) {

perception/lidar_apollo_segmentation_tvm/src/lidar_apollo_segmentation_tvm.cpp

+1-6
Original file line numberDiff line numberDiff line change
@@ -109,12 +109,7 @@ ApolloLidarSegmentation::ApolloLidarSegmentation(
109109
int32_t range, float score_threshold, bool use_intensity_feature, bool use_constant_feature,
110110
float z_offset, float min_height, float max_height, float objectness_thresh, int32_t min_pts_num,
111111
float height_thresh, const std::string & data_path)
112-
: range_(range),
113-
score_threshold_(score_threshold),
114-
z_offset_(z_offset),
115-
objectness_thresh_(objectness_thresh),
116-
min_pts_num_(min_pts_num),
117-
height_thresh_(height_thresh),
112+
: z_offset_(z_offset),
118113
pcl_pointcloud_ptr_(new pcl::PointCloud<pcl::PointXYZI>),
119114
PreP(std::make_shared<PrePT>(
120115
config, range, use_intensity_feature, use_constant_feature, min_height, max_height)),

0 commit comments

Comments
 (0)