diff --git a/driving_log_replayer_v2/driving_log_replayer_v2/launch/all.py b/driving_log_replayer_v2/driving_log_replayer_v2/launch/all.py new file mode 100644 index 00000000..1c67df32 --- /dev/null +++ b/driving_log_replayer_v2/driving_log_replayer_v2/launch/all.py @@ -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] = [] diff --git a/driving_log_replayer_v2/launch/driving_log_replayer_v2.launch.py b/driving_log_replayer_v2/launch/driving_log_replayer_v2.launch.py index bc44006b..c09a7ebe 100644 --- a/driving_log_replayer_v2/launch/driving_log_replayer_v2.launch.py +++ b/driving_log_replayer_v2/launch/driving_log_replayer_v2.launch.py @@ -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 @@ -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']}", @@ -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"],