Skip to content

Commit

Permalink
feat: all component test (#90)
Browse files Browse the repository at this point in the history
* feat: add all component setting

Signed-off-by: Hayato Mizushima <[email protected]>

* feat: all component evaluation uses record only mode

Signed-off-by: Hayato Mizushima <[email protected]>

* add record topic for all component test

Signed-off-by: MasatoSaeki <[email protected]>

---------

Signed-off-by: Hayato Mizushima <[email protected]>
Signed-off-by: MasatoSaeki <[email protected]>
Co-authored-by: MasatoSaeki <[email protected]>
  • Loading branch information
hayato-m126 and MasatoSaeki authored Feb 20, 2025
1 parent 882ba04 commit b00f537
Show file tree
Hide file tree
Showing 2 changed files with 48 additions and 2 deletions.
43 changes: 43 additions & 0 deletions driving_log_replayer_v2/driving_log_replayer_v2/launch/all.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,43 @@
# Copyright (c) 2025 TIER IV.inc
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from launch.actions import DeclareLaunchArgument

RECORD_TOPIC = """^/diagnostics$\
|^/sensing/lidar/concatenated/pointcloud$\
|^/perception/object_recognition/objects$\
|^/perception/obstacle_segmentation/pointcloud$\
|^/perception/object_recognition/detection/rois(11|10|[0-9])$\
|^/perception/traffic_light_recognition/camera(11|10|[0-9])/detection/rois$\
|^/perception/traffic_light_recognition/camera(11|10|[0-9])/detection/rough/rois$\
|^/perception/traffic_light_recognition/camera(11|10|[0-9])/classification/traffic_signals$\
|^/perception/traffic_light_recognition/traffic_signals$\
|^/tf$\
|^/tf_static$\
|^/planning/scenario_planning/lane_driving/behavior_planning/path$\
|^/planning/scenario_planning/trajectory$\
|^/.*/virtual_wall/.*$\
|^/.*/path_candidate/.*\
"""

AUTOWARE_DISABLE = {}

AUTOWARE_ARGS = {
"pose_source": "ndt",
"twist_source": "gyro_odom",
}

NODE_PARAMS = {}

USE_CASE_ARGS: list[DeclareLaunchArgument] = []
Original file line number Diff line number Diff line change
Expand Up @@ -204,7 +204,7 @@ def extract_remap_topics(profile_name: str) -> list[str]:
return remap_dict.get("remap")


def ensure_arg_compatibility(context: LaunchContext) -> list:
def ensure_arg_compatibility(context: LaunchContext) -> list: # noqa
conf = context.launch_configurations

# check conf
Expand Down Expand Up @@ -265,6 +265,9 @@ def ensure_arg_compatibility(context: LaunchContext) -> list:
conf["result_archive_path"] = output_dir.joinpath("result_archive").as_posix()
conf["use_case"] = yaml_obj["Evaluation"]["UseCaseName"]

if conf["use_case"] == "all":
conf["record_only"] = "true"

return [
LogInfo(
msg=f"{t4_dataset_path=}, {dataset_index=}, {output_dir=}, use_case={conf['use_case']}",
Expand Down Expand Up @@ -333,7 +336,7 @@ def launch_evaluator_node(context: LaunchContext) -> list:
if conf["record_only"] != "false":
# output dummy result for Evaluator
output_dummy_result_jsonl(conf["result_json_path"])
return [LogInfo(msg="evaluator_node is not launched because record_only is set")]
return [LogInfo(msg="evaluator_node is not launched due to record only mode")]
params = {
"use_sim_time": True,
"scenario_path": conf["scenario_path"],
Expand Down

0 comments on commit b00f537

Please sign in to comment.