Skip to content

Commit

Permalink
fix(lidar_apollo_segmentation_tvm): add virtual destructor to lidar_a…
Browse files Browse the repository at this point in the history
…pollo_segmentation_tvm (#7762)

* fix(lidar_apollo_segmentation_tvm): add virtual destructor to lidar_apollo_segmentation_tvm

Signed-off-by: Y.Hisaki <[email protected]>

* small change

Signed-off-by: Y.Hisaki <[email protected]>

---------

Signed-off-by: Y.Hisaki <[email protected]>
  • Loading branch information
yhisaki authored Jul 3, 2024
1 parent 1069e18 commit 9289b35
Show file tree
Hide file tree
Showing 5 changed files with 4 additions and 18 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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<FeatureMapInterface> map_ptr_;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef LIDAR_APOLLO_SEGMENTATION_TVM__FEATURE_MAP_HPP_
#define LIDAR_APOLLO_SEGMENTATION_TVM__FEATURE_MAP_HPP_

#include <memory>
#include <cstdint>
#include <vector>

namespace autoware
Expand Down Expand Up @@ -45,6 +45,7 @@ struct FeatureMapInterface
virtual void initializeMap(std::vector<float> & map) = 0;
virtual void resetMap(std::vector<float> & 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.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<pcl::PointXYZI>::Ptr pcl_pointcloud_ptr_;
// Earliest supported model version.
const std::array<int8_t, 3> model_version_from{2, 0, 0};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<pcl::PointXYZI>),
PreP(std::make_shared<PrePT>(
config, range, use_intensity_feature, use_constant_feature, min_height, max_height)),
Expand Down

0 comments on commit 9289b35

Please sign in to comment.