Skip to content

Commit

Permalink
feat: support-override-autoware-launch-arg
Browse files Browse the repository at this point in the history
  • Loading branch information
hayato-m126 committed Jul 23, 2024
1 parent 0c4b748 commit 5d0a740
Show file tree
Hide file tree
Showing 2 changed files with 64 additions and 20 deletions.
19 changes: 13 additions & 6 deletions log_evaluator/launch/log_evaluator.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -109,12 +109,6 @@ def ensure_arg_compatibility(context: LaunchContext) -> list:
for k, v in datasets[dataset_index].items():
dataset_path = dataset_dir.joinpath(k)
conf["vehicle_id"] = v["VehicleId"]
launch_sensing = yaml_obj["Evaluation"].get("LaunchSensing")
launch_localization = yaml_obj["Evaluation"].get("LaunchLocalization")
if launch_sensing is not None:
conf["sensing"] = str(launch_sensing)
if launch_localization is not None:
conf["localization"] = str(launch_localization)
conf["map_path"] = dataset_path.joinpath("map").as_posix()
conf["vehicle_model"] = yaml_obj["VehicleModel"]
conf["sensor_model"] = yaml_obj["SensorModel"]
Expand All @@ -124,6 +118,16 @@ def ensure_arg_compatibility(context: LaunchContext) -> list:
conf["result_bag_path"] = output_dir.joinpath("result_bag").as_posix()
conf["result_archive_path"] = output_dir.joinpath("result_archive_path").as_posix()
conf["use_case"] = yaml_obj["Evaluation"]["UseCaseName"]
use_case_launch_arg = log_evaluator_config[conf["use_case"]]["disable"]
# update autoware component launch or not
autoware_components = ["sensing", "localization", "perception", "planning", "control"]
launch_component = {}
for component in autoware_components:
# argument has higher priority than the launch_config.py setting.
if conf.get(component) is None and use_case_launch_arg.get(component) is not None:
conf[component] = use_case_launch_arg[component]
launch_component[component] = conf.get(component, "true")

# annotationless
conf["annotationless_threshold_file"] = ""
conf["annotationless_pass_range"] = ""
Expand All @@ -135,6 +139,9 @@ def ensure_arg_compatibility(context: LaunchContext) -> list:
LogInfo(
msg=f"{dataset_path=}, {dataset_index=}, {output_dir=}, use_case={conf['use_case']}",
),
LogInfo(
msg=f"{launch_component=}",
),
]


Expand Down
65 changes: 51 additions & 14 deletions log_evaluator/log_evaluator/launch_config.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,10 +26,13 @@
|^/log_evaluator/.*\
"""

LOCALIZATION_AUTOWARE_ARGS = {
LOCALIZATION_AUTOWARE_DISABLE = {
"perception": "false",
"planning": "false",
"control": "false",
}

LOCALIZATION_AUTOWARE_ARGS = {
"pose_source": "ndt",
"twist_source": "gyro_odom",
}
Expand All @@ -44,10 +47,9 @@
|^/localization/pose_estimator/points_aligned$\
"""

EAGLEYE_AUTOWARE_DISABLE = {"perception": "false", "planning": "false", "control": "false"}

EAGLEYE_AUTOWARE_ARGS = {
"perception": "false",
"planning": "false",
"control": "false",
"pose_source": "eagleye",
"twist_source": "eagleye",
}
Expand All @@ -60,10 +62,13 @@
|^/localization/kinematic_state$\
"""

AR_TAG_BASED_LOCALIZER_AUTOWARE_ARGS = {
AR_TAG_BASED_LOCALIZER_AUTOWARE_DISABLE = {
"perception": "false",
"planning": "false",
"control": "false",
}

AR_TAG_BASED_LOCALIZER_AUTOWARE_ARGS = {
"pose_source": "artag",
"twist_source": "gyro_odom",
}
Expand All @@ -78,10 +83,13 @@
|^/localization/pose_estimator/points_aligned$\
"""

YABLOC_AUTOWARE_ARGS = {
YABLOC_AUTOWARE_DISABLE = {
"perception": "false",
"planning": "false",
"control": "false",
}

YABLOC_AUTOWARE_ARGS = {
"pose_source": "yabloc",
"twist_source": "gyro_odom",
}
Expand All @@ -99,13 +107,15 @@
|^/sensing/camera/.*\
"""


PERCEPTION_AUTOWARE_ARGS = {
PERCEPTION_AUTOWARE_DISABLE = {
"sensing": "false",
"localization": "false",
"planning": "false",
"control": "false",
}

PERCEPTION_AUTOWARE_ARGS = {}

PERCEPTION_NODE_PARAMS = {}

OBSTACLE_SEGMENTATION_RECORD_TOPIC = """^/tf$\
Expand All @@ -115,10 +125,12 @@
|^/log_evaluator/.*\
"""

OBSTACLE_SEGMENTATION_AUTOWARE_ARGS = {
OBSTACLE_SEGMENTATION_AUTOWARE_DISABLE = {
"localization": "false",
"planning": "true",
"control": "false",
}

OBSTACLE_SEGMENTATION_AUTOWARE_ARGS = {
"scenario_simulation": "true",
}

Expand All @@ -133,12 +145,15 @@
|^/log_evaluator/.*\
"""

TRAFFIC_LIGHT_AUTOWARE_ARGS = {
TRAFFIC_LIGHT_AUTOWARE_DISABLE = {
"sensing": "false",
"localization": "false",
"planning": "false",
"control": "false",
}

TRAFFIC_LIGHT_AUTOWARE_ARGS = {}

TRAFFIC_LIGHT_NODE_PARAMS = {"map_path": LaunchConfiguration("map_path")}

PERFORMANCE_DIAG_RECORD_TOPIC = """^/tf$\
Expand All @@ -149,12 +164,16 @@
|^/log_evaluator/.*\
"""

PERFORMANCE_DIAG_AUTOWARE_ARGS = {
PERFORMANCE_DIAG_AUTOWARE_DISABLE = {
"localization": "false",
"perception": "false",
"planning": "false",
"control": "false",
}


PERFORMANCE_DIAG_AUTOWARE_ARGS = {}

PERFORMANCE_DIAG_NODE_PARAMS = {}

PERCEPTION_2D_RECORD_TOPIC = """^/tf$\
Expand All @@ -166,10 +185,14 @@
|^/log_evaluator/.*\
"""

PERCEPTION_2D_AUTOWARE_ARGS = {
PERCEPTION_2D_AUTOWARE_DISABLE = {
"sensing": "false",
"localization": "false",
"planning": "false",
"control": "false",
}

PERCEPTION_2D_AUTOWARE_ARGS = {
"perception_mode": "camera_lidar_fusion",
}

Expand All @@ -185,10 +208,14 @@
|^/diagnostic/perception_online_evaluator/.*\
"""

ANNOTATIONLESS_PERCEPTION_AUTOWARE_ARGS = {
ANNOTATIONLESS_PERCEPTION_AUTOWARE_DISABLE = {
"sensing": "false",
"localization": "false",
"planning": "false",
"control": "false",
}

ANNOTATIONLESS_PERCEPTION_AUTOWARE_ARGS = {
"use_perception_online_evaluator": "true",
}

Expand All @@ -206,51 +233,61 @@
log_evaluator_config = {
"localization": {
"record": LOCALIZATION_RECORD_TOPIC,
"disable": LOCALIZATION_AUTOWARE_DISABLE,
"autoware": LOCALIZATION_AUTOWARE_ARGS,
"node": LOCALIZATION_NODE_PARAMS,
},
"eagleye": {
"record": EAGLEYE_RECORD_TOPIC,
"disable": EAGLEYE_AUTOWARE_DISABLE,
"autoware": EAGLEYE_AUTOWARE_ARGS,
"node": EAGLEYE_NODE_PARAMS,
},
"ar_tag_based_localizer": {
"record": AR_TAG_BASED_LOCALIZER_RECORD_TOPIC,
"disable": AR_TAG_BASED_LOCALIZER_AUTOWARE_DISABLE,
"autoware": AR_TAG_BASED_LOCALIZER_AUTOWARE_ARGS,
"node": AR_TAG_BASED_LOCALIZER_NODE_PARAMS,
},
"yabloc": {
"record": YABLOC_RECORD_TOPIC,
"disable": YABLOC_AUTOWARE_DISABLE,
"autoware": YABLOC_AUTOWARE_ARGS,
"node": YABLOC_NODE_PARAMS,
},
"perception": {
"record": PERCEPTION_RECORD_TOPIC,
"disable": PERCEPTION_AUTOWARE_DISABLE,
"autoware": PERCEPTION_AUTOWARE_ARGS,
"node": PERCEPTION_NODE_PARAMS,
},
"obstacle_segmentation": {
"record": OBSTACLE_SEGMENTATION_RECORD_TOPIC,
"disable": OBSTACLE_SEGMENTATION_AUTOWARE_DISABLE,
"autoware": OBSTACLE_SEGMENTATION_AUTOWARE_ARGS,
"node": OBSTACLE_SEGMENTATION_NODE_PARAMS,
},
"traffic_light": {
"record": TRAFFIC_LIGHT_RECORD_TOPIC,
"disable": TRAFFIC_LIGHT_AUTOWARE_DISABLE,
"autoware": TRAFFIC_LIGHT_AUTOWARE_ARGS,
"node": TRAFFIC_LIGHT_NODE_PARAMS,
},
"performance_diag": {
"record": PERFORMANCE_DIAG_RECORD_TOPIC,
"disable": PERFORMANCE_DIAG_AUTOWARE_DISABLE,
"autoware": PERFORMANCE_DIAG_AUTOWARE_ARGS,
"node": PERFORMANCE_DIAG_NODE_PARAMS,
},
"perception_2d": {
"record": PERCEPTION_2D_RECORD_TOPIC,
"disable": PERCEPTION_2D_AUTOWARE_DISABLE,
"autoware": PERCEPTION_AUTOWARE_ARGS,
"node": PERCEPTION_2D_NODE_PARAMS,
},
"annotationless_perception": {
"record": ANNOTATIONLESS_PERCEPTION_RECORD_TOPIC,
"disable": ANNOTATIONLESS_PERCEPTION_AUTOWARE_DISABLE,
"autoware": ANNOTATIONLESS_PERCEPTION_AUTOWARE_ARGS,
"node": ANNOTATIONLESS_PERCEPTION_NODE_PARAMS,
},
Expand Down

0 comments on commit 5d0a740

Please sign in to comment.