Skip to content

Commit 7e38b34

Browse files
committed
chore: Override functions in pcl_validator.hpp
Signed-off-by: Taekjin LEE <taekjin.lee@tier4.jp>
1 parent 1c7f628 commit 7e38b34

File tree

1 file changed

+8
-8
lines changed

1 file changed

+8
-8
lines changed

perception/detected_object_validation/src/obstacle_pointcloud/pcl_validator.hpp

+8-8
Original file line numberDiff line numberDiff line change
@@ -94,14 +94,14 @@ class Validator2D : public Validator
9494

9595
pcl::PointCloud<pcl::PointXYZ>::Ptr convertToXYZ(
9696
const pcl::PointCloud<pcl::PointXY>::Ptr & pointcloud_xy);
97-
inline pcl::PointCloud<pcl::PointXYZ>::Ptr getDebugNeighborPointCloud()
97+
inline pcl::PointCloud<pcl::PointXYZ>::Ptr getDebugNeighborPointCloud() override
9898
{
9999
return convertToXYZ(neighbor_pointcloud_);
100100
}
101101

102-
bool setKdtreeInputCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_cloud);
103-
bool validate_object(const autoware_perception_msgs::msg::DetectedObject & transformed_object);
104-
std::optional<float> getMaxRadius(const autoware_perception_msgs::msg::DetectedObject & object);
102+
bool setKdtreeInputCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_cloud) override;
103+
bool validate_object(const autoware_perception_msgs::msg::DetectedObject & transformed_object) override;
104+
std::optional<float> getMaxRadius(const autoware_perception_msgs::msg::DetectedObject & object) override;
105105
std::optional<size_t> getPointCloudWithinObject(
106106
const autoware_perception_msgs::msg::DetectedObject & object,
107107
const pcl::PointCloud<pcl::PointXY>::Ptr neighbor_pointcloud);
@@ -115,13 +115,13 @@ class Validator3D : public Validator
115115

116116
public:
117117
explicit Validator3D(PointsNumThresholdParam & points_num_threshold_param);
118-
inline pcl::PointCloud<pcl::PointXYZ>::Ptr getDebugNeighborPointCloud()
118+
inline pcl::PointCloud<pcl::PointXYZ>::Ptr getDebugNeighborPointCloud() override
119119
{
120120
return neighbor_pointcloud_;
121121
}
122-
bool setKdtreeInputCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_cloud);
123-
bool validate_object(const autoware_perception_msgs::msg::DetectedObject & transformed_object);
124-
std::optional<float> getMaxRadius(const autoware_perception_msgs::msg::DetectedObject & object);
122+
bool setKdtreeInputCloud(const sensor_msgs::msg::PointCloud2::ConstSharedPtr & input_cloud) override;
123+
bool validate_object(const autoware_perception_msgs::msg::DetectedObject & transformed_object) override;
124+
std::optional<float> getMaxRadius(const autoware_perception_msgs::msg::DetectedObject & object) override;
125125
std::optional<size_t> getPointCloudWithinObject(
126126
const autoware_perception_msgs::msg::DetectedObject & object,
127127
const pcl::PointCloud<pcl::PointXYZ>::Ptr neighbor_pointcloud);

0 commit comments

Comments
 (0)