Skip to content

Commit

Permalink
Merge branch 'develop' into feat/prediction-evaluation
Browse files Browse the repository at this point in the history
  • Loading branch information
ktro2828 authored Dec 21, 2022
2 parents dec21ea + 15f147f commit 59633ed
Show file tree
Hide file tree
Showing 10 changed files with 66 additions and 14 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/build-and-test-mock.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ on:

jobs:
test-mock:
runs-on: ubuntu-latest
runs-on: ubuntu-20.04
continue-on-error: true
strategy:
matrix:
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/build-and-test.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ on:

jobs:
build-and-test:
runs-on: ubuntu-latest
runs-on: ubuntu-20.04
continue-on-error: true
strategy:
matrix:
Expand Down
7 changes: 7 additions & 0 deletions docs/ja/release_note.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,13 @@

## Release for main branch

### v1.0.2

- <https://github.com/tier4/autoware_perception_evaluation/pull/22>
- 【feat】Sensing 評価時にフレーム毎で評価条件を変更できる機能の追加
- <https://github.com/tier4/autoware_perception_evaluation/pull/19>
- 【fix】PerceptionPerformanceAnalyzer の DataFrame に正しいフレーム番号が適用されるように修正

### v1.0.1

- <https://github.com/tier4/autoware_perception_evaluation/pull/9>
Expand Down
1 change: 1 addition & 0 deletions docs/ja/sensing/design.md
Original file line number Diff line number Diff line change
Expand Up @@ -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内で検出されるべき最低限の点群数の閾値
Expand Down
2 changes: 1 addition & 1 deletion perception_eval/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>perception_eval</name>
<version>1.0.1</version>
<version>1.0.2</version>
<description>Autoware Perception Evaluator</description>
<maintainer email="[email protected]">Satoshi Tanaka</maintainer>
<maintainer email="[email protected]">Kotaro Uetake</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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


Expand Down Expand Up @@ -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] = {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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]
Expand All @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,13 +13,15 @@
# limitations under the License.

from typing import List
from typing import Optional
from typing import Tuple

import numpy as np
from perception_eval.common.dataset import FrameGroundTruth
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

Expand Down Expand Up @@ -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.
Expand All @@ -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(
Expand All @@ -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(
Expand All @@ -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(
Expand Down
11 changes: 11 additions & 0 deletions perception_eval/test/sensing_lsim.py
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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)
Expand Down
2 changes: 1 addition & 1 deletion pyproject.toml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
[tool.poetry]
name = "perception_eval"
version = "1.0.1"
version = "1.0.2"
description = ""
authors = ["Satoshi Tanaka <[email protected]>", "Kotaro Uetake <[email protected]>", "Shunsuke Miura <[email protected]>", "Shintaro Tomie <[email protected]>"]
license = "Apache V2"
Expand Down

0 comments on commit 59633ed

Please sign in to comment.