From 83de2dc50fea08b852c8a6864185d323d847e650 Mon Sep 17 00:00:00 2001 From: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> Date: Tue, 13 Dec 2022 04:10:32 +0900 Subject: [PATCH 1/3] feat(sensing_evaluation): add support of specifying evaluation conditions per one frame (#22) Signed-off-by: ktro2828 Signed-off-by: ktro2828 --- docs/ja/sensing/design.md | 1 + .../config/sensing_evaluation_config.py | 11 +++--- .../sensing/sensing_frame_config.py | 6 ++++ .../manager/sensing_evaluation_manager.py | 36 +++++++++++++++---- perception_eval/test/sensing_lsim.py | 11 ++++++ 5 files changed, 55 insertions(+), 10 deletions(-) diff --git a/docs/ja/sensing/design.md b/docs/ja/sensing/design.md index 13faebcd..612f1856 100644 --- a/docs/ja/sensing/design.md +++ b/docs/ja/sensing/design.md @@ -69,6 +69,7 @@ ```txt Arguments: + target_uuids (List[str]): フィルタリング対象となるGTのuuidのリスト bbox_scale_0m (float): 0m地点でのBounding boxのスケーリング係数 bbox_scale_100m (float): 100m地点でのBounding boxのスケーリング係数 min_points_threshold (int): bounding box内で検出されるべき最低限の点群数の閾値 diff --git a/perception_eval/perception_eval/config/sensing_evaluation_config.py b/perception_eval/perception_eval/config/sensing_evaluation_config.py index 5944b69d..1cbb955c 100644 --- a/perception_eval/perception_eval/config/sensing_evaluation_config.py +++ b/perception_eval/perception_eval/config/sensing_evaluation_config.py @@ -17,8 +17,6 @@ from typing import List from typing import Tuple -from perception_eval.evaluation.sensing.sensing_frame_config import SensingFrameConfig - from ._evaluation_config_base import _EvaluationConfigBase @@ -75,13 +73,18 @@ def __init__( evaluation_config_dict=evaluation_config_dict, ) self.filtering_params, self.metrics_params = self._extract_params(evaluation_config_dict) - self.sensing_frame_config: SensingFrameConfig = SensingFrameConfig(**self.metrics_params) def _extract_params( self, evaluation_config_dict: Dict[str, Any], ) -> Tuple[Dict[str, Any], Dict[str, Any]]: - """""" + """Extract parameters. + Args: + evaluation_config_dict (Dict[str, Any]): Configuration as dict. + Returns: + f_params (Dict[str, Any]): Parameters for filtering. + m_params (Dict[str, Any]): Parameters for metrics. + """ e_cfg: Dict[str, Any] = evaluation_config_dict.copy() f_params: Dict[str, Any] = {"target_uuids": e_cfg.get("target_uuids", None)} m_params: Dict[str, Any] = { diff --git a/perception_eval/perception_eval/evaluation/sensing/sensing_frame_config.py b/perception_eval/perception_eval/evaluation/sensing/sensing_frame_config.py index 9c0b6af0..c84c3e95 100644 --- a/perception_eval/perception_eval/evaluation/sensing/sensing_frame_config.py +++ b/perception_eval/perception_eval/evaluation/sensing/sensing_frame_config.py @@ -12,6 +12,9 @@ # See the License for the specific language governing permissions and # limitations under the License. +from typing import List +from typing import Optional + class SensingFrameConfig: """[summary] @@ -25,16 +28,19 @@ class SensingFrameConfig: def __init__( self, + target_uuids: Optional[List[str]], box_scale_0m: float, box_scale_100m: float, min_points_threshold: int, ) -> None: """[summary] Args: + target_uuids (Optional[List[str]]): List of target uuids to be filtered. box_scale_0m (float): Scale factor for bounding box at 0m. box_scale_100m (float): Scale factor for bounding box at 100m. min_points_threshold (int): The minimum number of points should be detected in bounding box. """ + self.target_uuids: Optional[List[str]] = target_uuids self.box_scale_0m: float = box_scale_0m self.box_scale_100m: float = box_scale_100m self.min_points_threshold: int = min_points_threshold diff --git a/perception_eval/perception_eval/manager/sensing_evaluation_manager.py b/perception_eval/perception_eval/manager/sensing_evaluation_manager.py index 28b1af9b..dd03ee3e 100644 --- a/perception_eval/perception_eval/manager/sensing_evaluation_manager.py +++ b/perception_eval/perception_eval/manager/sensing_evaluation_manager.py @@ -13,6 +13,7 @@ # limitations under the License. from typing import List +from typing import Optional from typing import Tuple import numpy as np @@ -20,6 +21,7 @@ from perception_eval.common.point import crop_pointcloud from perception_eval.config.sensing_evaluation_config import SensingEvaluationConfig from perception_eval.evaluation.matching.objects_filter import filter_objects +from perception_eval.evaluation.sensing.sensing_frame_config import SensingFrameConfig from perception_eval.evaluation.sensing.sensing_frame_result import SensingFrameResult from perception_eval.util.math import get_bbox_scale @@ -56,6 +58,7 @@ def add_frame_result( ground_truth_now_frame: FrameGroundTruth, pointcloud: np.ndarray, non_detection_areas: List[List[Tuple[float, float, float]]], + sensing_frame_config: Optional[SensingFrameConfig] = None, ) -> SensingFrameResult: """[summary] Get sensing result at current frame. @@ -67,12 +70,22 @@ def add_frame_result( pointcloud (np.ndarray): Observed pointcloud. non_detection_area (List[List[Tuple[float, float, float]]]): List of non-detection areas. + sensing_frame_config (Optional[SensingFrameConfig]): Evaluation config for one frame. + If not specified, parameters of metrics config will be used. Defaults to None. Returns: result (SensingFrameResult) """ - ground_truth_objects: List[DynamicObject] = self._filter_objects(ground_truth_now_frame) - frame_name: str = ground_truth_now_frame.frame_name + if sensing_frame_config is None: + sensing_frame_config = SensingFrameConfig( + **self.evaluator_config.filtering_params, + **self.evaluator_config.metrics_params, + ) + + ground_truth_objects: List[DynamicObject] = self._filter_objects( + ground_truth_now_frame, + sensing_frame_config, + ) # Crop pointcloud for non-detection area pointcloud_for_non_detection: np.ndarray = self.crop_pointcloud( @@ -82,9 +95,9 @@ def add_frame_result( ) result = SensingFrameResult( - sensing_frame_config=self.evaluator_config.sensing_frame_config, + sensing_frame_config=sensing_frame_config, unix_time=unix_time, - frame_name=frame_name, + frame_name=ground_truth_now_frame.frame_name, ) result.evaluate_frame( @@ -96,13 +109,24 @@ def add_frame_result( return result - def _filter_objects(self, frame_ground_truth: FrameGroundTruth) -> List[DynamicObject]: + def _filter_objects( + self, + frame_ground_truth: FrameGroundTruth, + sensing_frame_config: SensingFrameConfig, + ) -> List[DynamicObject]: + """Filter ground truth objects + Args: + frame_ground_truth (FrameGroundTruth): FrameGroundTruth instance. + sensing_frame_config (SensingFrameConfig): SensingFrameConfig instance. + Returns: + List[DynamicObject]: Filtered ground truth objects + """ return filter_objects( frame_id=self.evaluator_config.frame_id, objects=frame_ground_truth.objects, is_gt=True, + target_uuids=sensing_frame_config.target_uuids, ego2map=frame_ground_truth.ego2map, - **self.evaluator_config.filtering_params, ) def crop_pointcloud( diff --git a/perception_eval/test/sensing_lsim.py b/perception_eval/test/sensing_lsim.py index c0312467..bcb8d878 100644 --- a/perception_eval/test/sensing_lsim.py +++ b/perception_eval/test/sensing_lsim.py @@ -22,6 +22,7 @@ import numpy as np from perception_eval.common.dataset import FrameGroundTruth from perception_eval.config.sensing_evaluation_config import SensingEvaluationConfig +from perception_eval.evaluation.sensing.sensing_frame_config import SensingFrameConfig from perception_eval.evaluation.sensing.sensing_frame_result import SensingFrameResult from perception_eval.manager.sensing_evaluation_manager import SensingEvaluationManager from perception_eval.util.logger_config import configure_logger @@ -85,12 +86,22 @@ def callback( FrameGroundTruth ] = self.evaluator.get_ground_truth_now_frame(unix_time=unix_time) + # Evaluation config for one frame. + # If not specified, params of SensingEvaluationConfig will be used. + sensing_frame_config = SensingFrameConfig( + target_uuids=None, + box_scale_0m=1.0, + box_scale_100m=1.0, + min_points_threshold=1, + ) + if ground_truth_now_frame is not None: frame_result: SensingFrameResult = self.evaluator.add_frame_result( unix_time=unix_time, ground_truth_now_frame=ground_truth_now_frame, pointcloud=pointcloud, non_detection_areas=non_detection_areas, + sensing_frame_config=sensing_frame_config, ) self.visualize(frame_result) From febabce346828da67c3f69263eea8ef702dc9d50 Mon Sep 17 00:00:00 2001 From: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> Date: Tue, 13 Dec 2022 09:50:22 +0900 Subject: [PATCH 2/3] chore(release): releasev1.0.2 (#24) Signed-off-by: ktro2828 Signed-off-by: ktro2828 --- docs/ja/release_note.md | 7 +++++++ perception_eval/package.xml | 2 +- pyproject.toml | 2 +- 3 files changed, 9 insertions(+), 2 deletions(-) diff --git a/docs/ja/release_note.md b/docs/ja/release_note.md index 893910bc..7927e9f1 100644 --- a/docs/ja/release_note.md +++ b/docs/ja/release_note.md @@ -6,6 +6,13 @@ ## Release for main branch +### v1.0.2 + +- + - 【feat】Sensing 評価時にフレーム毎で評価条件を変更できる機能の追加 +- + - 【fix】PerceptionPerformanceAnalyzer の DataFrame に正しいフレーム番号が適用されるように修正 + ### v1.0.1 - diff --git a/perception_eval/package.xml b/perception_eval/package.xml index 094a2bd8..cfc9581a 100644 --- a/perception_eval/package.xml +++ b/perception_eval/package.xml @@ -2,7 +2,7 @@ perception_eval - 1.0.1 + 1.0.2 Autoware Perception Evaluator Satoshi Tanaka Kotaro Uetake diff --git a/pyproject.toml b/pyproject.toml index 98143e9d..1459dc1a 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -1,6 +1,6 @@ [tool.poetry] name = "perception_eval" -version = "1.0.1" +version = "1.0.2" description = "" authors = ["Satoshi Tanaka ", "Kotaro Uetake ", "Shunsuke Miura ", "Shintaro Tomie "] license = "Apache V2" From 15f147fc806163c52c34a6557b444c2c2e774861 Mon Sep 17 00:00:00 2001 From: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> Date: Wed, 21 Dec 2022 11:11:24 +0900 Subject: [PATCH 3/3] ci: specify update-20.04 (#27) Signed-off-by: ktro2828 Signed-off-by: ktro2828 --- .github/workflows/build-and-test-mock.yaml | 2 +- .github/workflows/build-and-test.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build-and-test-mock.yaml b/.github/workflows/build-and-test-mock.yaml index a877a207..a373a997 100644 --- a/.github/workflows/build-and-test-mock.yaml +++ b/.github/workflows/build-and-test-mock.yaml @@ -15,7 +15,7 @@ on: jobs: test-mock: - runs-on: ubuntu-latest + runs-on: ubuntu-20.04 continue-on-error: true strategy: matrix: diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 5f407696..2778e90f 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -15,7 +15,7 @@ on: jobs: build-and-test: - runs-on: ubuntu-latest + runs-on: ubuntu-20.04 continue-on-error: true strategy: matrix: