vprdb.metrics
Metrics allow to evaluate the quality of created databases, as well as to estimate the accuracy of various VPR systems.
1# Copyright (c) 2023, Ivan Moskalenko, Anastasiia Kornilova 2# 3# Licensed under the Apache License, Version 2.0 (the "License"); 4# you may not use this file except in compliance with the License. 5# You may obtain a copy of the License at 6# 7# http://www.apache.org/licenses/LICENSE-2.0 8# 9# Unless required by applicable law or agreed to in writing, software 10# distributed under the License is distributed on an "AS IS" BASIS, 11# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. 12# See the License for the specific language governing permissions and 13# limitations under the License. 14""" 15Metrics allow to evaluate the quality of created databases, 16as well as to estimate the accuracy of various VPR systems. 17""" 18from vprdb.metrics.frames_coverage_ import frames_coverage 19from vprdb.metrics.recall_ import recall 20from vprdb.metrics.spatial_coverage_ import spatial_coverage 21 22__all__ = ["frames_coverage", "recall", "spatial_coverage"]
def
frames_coverage( original_db: vprdb.core.database.Database, reduced_db: vprdb.core.database.Database, voxel_size: float = 0.3, num_of_threads: int = 2) -> list[float]:
22def frames_coverage( 23 original_db: Database, 24 reduced_db: Database, 25 voxel_size: float = 0.3, 26 num_of_threads: int = os.cpu_count(), 27) -> list[float]: 28 """ 29 The metric determines how well the frames from the original database 30 are covered by the frames from the reduced database 31 32 :param original_db: Original database 33 :param reduced_db: Reduced database 34 :param voxel_size: Voxel size for down sampling 35 :param num_of_threads: Number of threads to parallelize calculations 36 37 :return: A list of values indicating the level of coverage of a particular frame 38 """ 39 min_bounds, max_bounds = original_db.bounds 40 voxel_grid = VoxelGrid(min_bounds, max_bounds, voxel_size) 41 42 def find_best_coverage(pose, pcd_raw): 43 coverages_for_query = [] 44 for reduced_db_pose, reduced_db_pcd in zip( 45 reduced_db.trajectory, reduced_db.point_clouds 46 ): 47 pcd_query = pcd_raw.point_cloud.transform(pose) 48 pcd_db = reduced_db_pcd.point_cloud.transform(reduced_db_pose) 49 coverage = calculate_point_cloud_coverage(pcd_query, pcd_db, voxel_grid) 50 coverages_for_query.append(coverage) 51 return max(coverages_for_query) 52 53 coverages = Parallel(n_jobs=num_of_threads)( 54 delayed(find_best_coverage)(pose, pcd_raw) 55 for pose, pcd_raw in zip(original_db.trajectory, original_db.point_clouds) 56 ) 57 return coverages
The metric determines how well the frames from the original database are covered by the frames from the reduced database
Parameters
- original_db: Original database
- reduced_db: Reduced database
- voxel_size: Voxel size for down sampling
- num_of_threads: Number of threads to parallelize calculations
Returns
A list of values indicating the level of coverage of a particular frame
def
recall( source_db: vprdb.core.database.Database, test_db: vprdb.core.database.Database, matches: list[int], voxel_size: float = 0.3, threshold: float = 0.3) -> float:
20def recall( 21 source_db: Database, 22 test_db: Database, 23 matches: list[int], 24 voxel_size: float = 0.3, 25 threshold: float = 0.3, 26) -> float: 27 """ 28 The metric finds the number of correctly matched frames 29 30 :param source_db: Database for the VPR task 31 :param test_db: Database used as queries to the VPR system 32 :param matches: VPR system matches. 33 The i-th value from the list is the index of the frame from the database, 34 which will be matched with the i-th test frame 35 :param voxel_size: Voxel size for down sampling 36 :param threshold: The value of frame coverage, 37 below which the frame will be considered uncovered 38 39 :return: Recall value 40 """ 41 if len(test_db) != len(matches): 42 raise ValueError( 43 "The length of the matches and the test database must be the same" 44 ) 45 46 min_bounds_test, max_bounds_test = test_db.bounds 47 min_bounds_source, max_bounds_source = source_db.bounds 48 min_bounds = np.amin(np.row_stack((min_bounds_test, min_bounds_source)), axis=0) 49 max_bounds = np.amax(np.row_stack((max_bounds_test, max_bounds_source)), axis=0) 50 51 voxel_grid = VoxelGrid(min_bounds, max_bounds, voxel_size) 52 results = [] 53 for i, match in enumerate(matches): 54 pose_query = test_db.trajectory[i] 55 pcd_query = test_db.point_clouds[i].point_cloud.transform(pose_query) 56 57 pose_source = source_db.trajectory[match] 58 pcd_source = source_db.point_clouds[match].point_cloud.transform(pose_source) 59 60 coverage = calculate_point_cloud_coverage(pcd_query, pcd_source, voxel_grid) 61 results.append(coverage > threshold) 62 63 return sum(results) / len(results)
The metric finds the number of correctly matched frames
Parameters
- source_db: Database for the VPR task
- test_db: Database used as queries to the VPR system
- matches: VPR system matches. The i-th value from the list is the index of the frame from the database, which will be matched with the i-th test frame
- voxel_size: Voxel size for down sampling
- threshold: The value of frame coverage, below which the frame will be considered uncovered
Returns
Recall value
def
spatial_coverage( original_db: vprdb.core.database.Database, reduced_db: vprdb.core.database.Database, voxel_size: float = 0.3, down_sample_step: int = 100) -> float:
18def spatial_coverage( 19 original_db: Database, 20 reduced_db: Database, 21 voxel_size: float = 0.3, 22 down_sample_step: int = 100, 23) -> float: 24 """ 25 The metric determines how well the map from the original database is covered 26 by the map from the reduced database 27 28 :param original_db: Original database 29 :param reduced_db: Reduced database 30 :param voxel_size: Voxel size for down sampling 31 :param down_sample_step: Voxel down sampling step for reducing RAM usage 32 33 :return: the ratio of the number of points in the map from the reduced database 34 after down sampling to the number of points in the map from the original database 35 after down sampling 36 """ 37 min_bounds, max_bounds = original_db.bounds 38 voxel_grid = VoxelGrid(min_bounds, max_bounds, voxel_size) 39 original_map = original_db.build_sparse_map(voxel_grid, down_sample_step) 40 filtered_map = reduced_db.build_sparse_map(voxel_grid, down_sample_step) 41 return len(filtered_map.points) / len(original_map.points)
The metric determines how well the map from the original database is covered by the map from the reduced database
Parameters
- original_db: Original database
- reduced_db: Reduced database
- voxel_size: Voxel size for down sampling
- down_sample_step: Voxel down sampling step for reducing RAM usage
Returns
the ratio of the number of points in the map from the reduced database after down sampling to the number of points in the map from the original database after down sampling