@@ -94,14 +94,14 @@ class Validator2D : public Validator
94
94
95
95
pcl::PointCloud<pcl::PointXYZ>::Ptr convertToXYZ (
96
96
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
98
98
{
99
99
return convertToXYZ (neighbor_pointcloud_);
100
100
}
101
101
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 ;
105
105
std::optional<size_t > getPointCloudWithinObject (
106
106
const autoware_perception_msgs::msg::DetectedObject & object,
107
107
const pcl::PointCloud<pcl::PointXY>::Ptr neighbor_pointcloud);
@@ -115,13 +115,13 @@ class Validator3D : public Validator
115
115
116
116
public:
117
117
explicit Validator3D (PointsNumThresholdParam & points_num_threshold_param);
118
- inline pcl::PointCloud<pcl::PointXYZ>::Ptr getDebugNeighborPointCloud ()
118
+ inline pcl::PointCloud<pcl::PointXYZ>::Ptr getDebugNeighborPointCloud () override
119
119
{
120
120
return neighbor_pointcloud_;
121
121
}
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 ;
125
125
std::optional<size_t > getPointCloudWithinObject (
126
126
const autoware_perception_msgs::msg::DetectedObject & object,
127
127
const pcl::PointCloud<pcl::PointXYZ>::Ptr neighbor_pointcloud);
0 commit comments