From 6f279eb06c339f7dd49658340b3e548fd95ea48f Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Tue, 16 Jul 2024 15:36:38 +0900 Subject: [PATCH 01/28] feat: planning control node --- docs/use_case/planning_control.en.md | 139 +++++ docs/use_case/planning_control.ja.md | 138 +++++ log_evaluator/CMakeLists.txt | 1 + .../config/planning_control/qos.yaml | 15 + log_evaluator/log_evaluator/launch_config.py | 16 + .../log_evaluator/planning_control.py | 231 +++++++++ .../planning_control_evaluator_node.py | 58 +++ sample/planning_control/control_diag.txt | 34 ++ sample/planning_control/result.json | 481 ++++++++++++++++++ sample/planning_control/scenario.ja.yaml | 88 ++++ 10 files changed, 1201 insertions(+) create mode 100644 docs/use_case/planning_control.en.md create mode 100644 docs/use_case/planning_control.ja.md create mode 100644 log_evaluator/config/planning_control/qos.yaml create mode 100644 log_evaluator/log_evaluator/planning_control.py create mode 100755 log_evaluator/scripts/planning_control_evaluator_node.py create mode 100644 sample/planning_control/control_diag.txt create mode 100644 sample/planning_control/result.json create mode 100644 sample/planning_control/scenario.ja.yaml diff --git a/docs/use_case/planning_control.en.md b/docs/use_case/planning_control.en.md new file mode 100644 index 00000000..1c84acfd --- /dev/null +++ b/docs/use_case/planning_control.en.md @@ -0,0 +1,139 @@ +# Evaluate Planning Control + +Evaluate whether Planning / Control metrics are output at specified times and conditions + +## Evaluation Method + +The planning_control evaluation is executed by launching the `planning_control.launch.py` file. +Launching the file executes the following steps: + +1. Execute launch of evaluation node (`planning_control_evaluator_node`), `logging_simulator.launch` file and `ros2 bag play` command +2. Autoware receives sensor data output from input rosbag and the perception module performs recognition. +3. Using the results of perception, Autoware output Metrics to `/diagnostic/planning_evaluator/metrics(temporary)` for planning and `/diagnostic/control_evaluator/metrics` for control. +4. The evaluation node subscribes to the topic and evaluates data. The result is dumped into a file. +5. When the playback of the rosbag is finished, Autoware's launch is automatically terminated, and the evaluation is completed. + +## Evaluation Result + +The output from control_evaluator is in the form of the following sample TOPIC. +[control sample](https://github.com/tier4/driving_log_replayer/blob/main/sample/planning_control/control_diag.txt) + +If there is a condition to be evaluated at the time of the header, it is evaluated and the judgment result is output. +If there is no evaluation condition corresponding to the time of the header, it is discarded and no log is output. + +### Normal + +If more than (current time - evaluation start time)\*Hertz\*AllowableRate(=0.95) topics are obtained that satisfy the evaluation conditions. + +In the following example, if the current time is 2, starting from 1 second, at the 2 second mark, (2-1)*10.0=10 topics should be retrieved. +However, the output rate is not exactly the specified rate. +Therefore, if the AllowableRate is applied and floor(10*0.95)=9 or more autonomous_emergency_braking: aeb_emergency_stop decision value stop is obtained, it is considered a success. +At 3 seconds, floor(20\*0.95)=19 or more is success. + +```yaml +Conditions: + Hertz: 10.0 # How many Hz the METRICS will come in. (current time - evaluation start time)* Hertz * AllowableRate(=0.95) or more TOPICS that match the condition must be output. AllowableRate is currently fixed. + ControlConditions: + - TimeRange: { start: 1, end: 3 } # Evaluation start time and end time, end is optional and if omitted, sys.float_info.max + Module: "autonomous_emergency_braking: aeb_emergency_stop" # Modules to be evaluated + Value0Key: decision # Key to be evaluated + Value0Value: stop # Value to be evaluated + DetailedConditions: null # Additional conditions to be determined, such as position, speed, etc. If null, succeeds when Value0Value is matched. If not null, DetailedConditions must also satisfy the condition. +``` + +### Error + +When the normal condition is not met + +## Topic name and data type used by evaluation node + +Subscribed topics: + +| Topic name | Data type | +| ----------------------------------------- | ------------------------------------- | +| /diagnostic/control_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | +| /diagnostic/planning_evaluator/metrics (仮) | diagnostic_msgs::msg::DiagnosticArray | + +Published topics: + +| Topic name | Data type | +| ---------- | --------- | +| N/A | N/A | + +## Arguments passed to logging_simulator.launch + +To make Autoware processing less resource-consuming, modules that are not relevant to evaluation are disabled by passing the `false` parameter as a launch argument. + +- sensing: true / false (Specified by the launch argument. Currently fixed to true.) +- localization: false + +## About simulation + +State the information required to run the simulation. + +### Topic to be included in the input rosbag + +| Topic name | Data type | +| -------------------------------------- | -------------------------------------------- | +| /gsm8/from_can_bus | can_msgs/msg/Frame | +| /localization/kinematic_state | nav_msgs/msg/Odometry | +| /localization/acceleration | geometry_msgs/msg/AccelWithCovarianceStamped | +| /sensing/lidar/concatenated/pointcloud | sensor_msgs/msg/PointCloud2 | +| /tf | tf2_msgs/msg/TFMessage | +| /planning/mission_planning/route | autoware_planning_msgs/msg/LaneletRoute | + +The vehicle topics can be included instead of CAN. + +| Topic name | Data type | +| -------------------------------------- | --------------------------------------------------- | +| /localization/kinematic_state | nav_msgs/msg/Odometry | +| /localization/acceleration | geometry_msgs/msg/AccelWithCovarianceStamped | +| /sensing/lidar/concatenated/pointcloud | sensor_msgs/msg/PointCloud2 | +| /tf | tf2_msgs/msg/TFMessage | +| /planning/mission_planning/route | autoware_planning_msgs/msg/LaneletRoute | +| /vehicle/status/control_mode | autoware_auto_vehicle_msgs/msg/ControlModeReport | +| /vehicle/status/gear_status | autoware_auto_vehicle_msgs/msg/GearReport | +| /vehicle/status/steering_status | autoware_auto_vehicle_msgs/SteeringReport | +| /vehicle/status/turn_indicators_status | autoware_auto_vehicle_msgs/msg/TurnIndicatorsReport | +| /vehicle/status/velocity_status | autoware_auto_vehicle_msgs/msg/VelocityReport | + +### Topics that must not be included in the input rosbag + +| Topic name | Data type | +| -------------------------------------- | ------------------------------------------------- +| -------- | ----------------------- | +| /clock | rosgraph_msgs/msg/Clock | + +The clock is output by the --clock option of ros2 bag play, so if it is recorded in the bag itself, it is output twice, so it is not included in the bag. + +## About Evaluation + +State the information necessary for the evaluation. + +### Scenario Format + +See [sample](https://github.com/tier4/driving_log_replayer/blob/main/sample/planning_control/scenario.ja.yaml). + +### Evaluation Result Format + +See [sample](https://github.com/tier4/driving_log_replayer/blob/main/sample/planning_control/result.json). + +The result format is shown below. +**NOTE: common part of the result file format, which has already been explained, is omitted.** + +Success is determined when all evaluation conditions set in planning and control are met. + +```json +{ + "Frame": { + "CONDITION_INDEX": { + // Results are output for each evaluation condition. + "Result": { "Total": "Success or Fail", "Frame": "Success or Fail" }, + "Info": { + "TotalPassed": "Total number of topics that passed the evaluation criteria", + "RequiredSuccess": "Number of successes required at current time (TotalPassed >= RequiredSuccess makes Total a success)" + } + } + } +} +``` diff --git a/docs/use_case/planning_control.ja.md b/docs/use_case/planning_control.ja.md new file mode 100644 index 00000000..585776c5 --- /dev/null +++ b/docs/use_case/planning_control.ja.md @@ -0,0 +1,138 @@ +# Planning Controlの評価 + +Planning / ControlのMetricsが指定の時刻、条件で出力されているか評価する + +## 評価方法 + +`planning_control.launch.py` を使用して評価する。 +launch を立ち上げると以下のことが実行され、評価される。 + +1. launch で評価ノード(`planning_control_evaluator_node`)と `logging_simulator.launch`、`ros2 bag play`コマンドを立ち上げる +2. bag から出力されたセンサーデータを autoware が受け取って、perception モジュールが認識を行う +3. perceptionの結果を使って、planningは `/diagnostic/planning_evaluator/metrics(仮)` に controlは `/diagnostic/control_evaluator/metrics`にMetricsを出力する +4. 評価ノードが topic を subscribe して、各基準を満たしているかを判定して結果をファイルに記録する +5. bag の再生が終了すると自動で launch が終了して評価が終了する + +## 評価結果 + +controlが出力するtopicは以下のサンプルのような形式となっている。 +[control sample](https://github.com/tier4/driving_log_replayer/blob/main/sample/planning_control/control_diag.txt) + +headerの時刻で評価する条件があれば評価され判定結果が出力される。 +headerの時刻に該当する評価条件がない場合は捨てられるのでログも出力されない。 + +### 正常 + +評価条件を満たすtopic が (現在時刻-評価開始時刻)\*Hertz\*AllowableRate(=0.95)個以上取得できた場合。 + +以下の例の場合、現在時刻が2だとすると、1秒からスタートして2秒の時点で (2-1)*10.0=10 topic程度metricsが出てくるはず。 +しかし、出力レートは厳密に指定のレートにはならない。 +よってAllowableRateをかけて floor(10*0.95)=9個以上 autonomous_emergency_braking: aeb_emergency_stop のdecisionの値stopが出ていたら成功とする +3秒時点では、floor(20\*0.95)=19以上で成功となる。 + +```yaml +Conditions: + Hertz: 10.0 # metricsが何Hzで来るか。 (現在時刻-評価開始時刻)* Hertz * AllowableRate(=0.95)以上条件に合致するtopicが出力される必要がある。AllowableRateは現在固定されている + ControlConditions: + - TimeRange: { start: 1, end: 3 } # 評価開始時間と終了時刻、endは省略可能で省略した場合はsys.float_info.max + Module: "autonomous_emergency_braking: aeb_emergency_stop" # 評価対象のモジュール + Value0Key: decision # 評価対象のキー + Value0Value: stop # 評価対象の値 + DetailedConditions: null # 位置、速度など、追加で判定したい条件。nullの場合はValue0Valueが一致した時点で成功。nullではない時はDetailedConditionsも条件を満たす必要がある +``` + +### 異常 + +正常の条件を満たさないとき + +## 評価ノードが使用する Topic 名とデータ型 + +Subscribed topics: + +| Topic name | Data type | +| ------------------------------------------- | ------------------------------------- | +| /diagnostic/control_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | +| /diagnostic/planning_evaluator/metrics (仮) | diagnostic_msgs::msg::DiagnosticArray | + +Published topics: + +| Topic name | Data type | +| ---------- | --------- | +| N/A | N/A | + +## logging_simulator.launch に渡す引数 + +autoware の処理を軽くするため、評価に関係のないモジュールは launch の引数に false を渡すことで無効化する。以下を設定している。 + +- sensing: true / false (launch引数で指定。現状true固定) +- localization: false + +## simulation + +シミュレーション実行に必要な情報を述べる。 + +### 入力 rosbag に含まれるべき topic + +| topic 名 | データ型 | +| -------------------------------------- | -------------------------------------------- | +| /gsm8/from_can_bus | can_msgs/msg/Frame | +| /localization/kinematic_state | nav_msgs/msg/Odometry | +| /localization/acceleration | geometry_msgs/msg/AccelWithCovarianceStamped | +| /sensing/lidar/concatenated/pointcloud | sensor_msgs/msg/PointCloud2 | +| /tf | tf2_msgs/msg/TFMessage | +| /planning/mission_planning/route | autoware_planning_msgs/msg/LaneletRoute | + +CAN の代わりに vehicle の topic を含めても良い。 + +| topic 名 | データ型 | +| -------------------------------------- | --------------------------------------------------- | +| /localization/kinematic_state | nav_msgs/msg/Odometry | +| /localization/acceleration | geometry_msgs/msg/AccelWithCovarianceStamped | +| /sensing/lidar/concatenated/pointcloud | sensor_msgs/msg/PointCloud2 | +| /tf | tf2_msgs/msg/TFMessage | +| /planning/mission_planning/route | autoware_planning_msgs/msg/LaneletRoute | +| /vehicle/status/control_mode | autoware_auto_vehicle_msgs/msg/ControlModeReport | +| /vehicle/status/gear_status | autoware_auto_vehicle_msgs/msg/GearReport | +| /vehicle/status/steering_status | autoware_auto_vehicle_msgs/SteeringReport | +| /vehicle/status/turn_indicators_status | autoware_auto_vehicle_msgs/msg/TurnIndicatorsReport | +| /vehicle/status/velocity_status | autoware_auto_vehicle_msgs/msg/VelocityReport | + +### 入力 rosbag に含まれてはいけない topic + +| topic 名 | データ型 | +| -------- | ----------------------- | +| /clock | rosgraph_msgs/msg/Clock | + +clock は、ros2 bag play の--clock オプションによって出力しているので、bag 自体に記録されていると 2 重に出力されてしまうので bag には含めない + +## evaluation + +評価に必要な情報を述べる。 + +### シナリオフォーマット + +[サンプル](https://github.com/tier4/driving_log_replayer/blob/main/sample/planning_control/scenario.ja.yaml)参照 + +### 評価結果フォーマット + +[サンプル](https://github.com/tier4/driving_log_replayer/blob/main/sample/planning_control/result.json)参照 + +以下に、それぞれの評価の例を記述する。 +**注:結果ファイルフォーマットで解説済みの共通部分については省略する。** + +planning と controlで設定した全ての評価条件で成功している場合に成功と判定される。 + +```json +{ + "Frame": { + "CONDITION_INDEX": { + // 評価条件毎に結果が出力される + "Result": { "Total": "Success or Fail", "Frame": "Success or Fail" }, + "Info": { + "TotalPassed": "評価条件をパスしたtopicの総数", + "RequiredSuccess": "現在時刻で必要な成功数(TotalPassed >= RequiredSuccessでTotalが成功になる)" + } + } + } +} +``` diff --git a/log_evaluator/CMakeLists.txt b/log_evaluator/CMakeLists.txt index 88dbd6ce..ce37dcef 100644 --- a/log_evaluator/CMakeLists.txt +++ b/log_evaluator/CMakeLists.txt @@ -30,6 +30,7 @@ install(PROGRAMS scripts/eagleye_evaluator_node.py scripts/ar_tag_based_localizer_evaluator_node.py scripts/annotationless_perception_evaluator_node.py + scripts/planning_control_evaluator_node.py DESTINATION lib/${PROJECT_NAME} ) diff --git a/log_evaluator/config/planning_control/qos.yaml b/log_evaluator/config/planning_control/qos.yaml new file mode 100644 index 00000000..efa1210d --- /dev/null +++ b/log_evaluator/config/planning_control/qos.yaml @@ -0,0 +1,15 @@ +/tf_static: + reliability: reliable + history: keep_last + depth: 1 + durability: transient_local +/planning/mission_planning/route: + reliability: reliable + history: keep_last + depth: 1 + durability: transient_local +/perception/obstacle_segmentation/pointcloud: + depth: 10 + durability: volatile + history: keep_last + reliability: best_effort diff --git a/log_evaluator/log_evaluator/launch_config.py b/log_evaluator/log_evaluator/launch_config.py index 365e4df3..509e7910 100644 --- a/log_evaluator/log_evaluator/launch_config.py +++ b/log_evaluator/log_evaluator/launch_config.py @@ -201,6 +201,17 @@ ), } +PLANNING_CONTROL_RECORD_TOPIC = """^/tf$\ +|^/diagnostic/control_evaluator/metrics$\ +|^/diagnostic/planning_evaluator/metrics$\ +""" + +PLANNING_CONTROL_AUTOWARE_ARGS = { + "localization": "false", +} + +PLANNING_CONTROL_NODE_PARAMS = {} + log_evaluator_config = { "localization": { "record": LOCALIZATION_RECORD_TOPIC, @@ -252,4 +263,9 @@ "autoware": ANNOTATIONLESS_PERCEPTION_AUTOWARE_ARGS, "node": ANNOTATIONLESS_PERCEPTION_NODE_PARAMS, }, + "planning_control": { + "record": PLANNING_CONTROL_RECORD_TOPIC, + "autoware": PLANNING_CONTROL_AUTOWARE_ARGS, + "node": PLANNING_CONTROL_NODE_PARAMS, + }, } diff --git a/log_evaluator/log_evaluator/planning_control.py b/log_evaluator/log_evaluator/planning_control.py new file mode 100644 index 00000000..dd46ce80 --- /dev/null +++ b/log_evaluator/log_evaluator/planning_control.py @@ -0,0 +1,231 @@ +# Copyright (c) 2024 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 dataclasses import dataclass +from dataclasses import field +from sys import float_info +from typing import Literal + +from diagnostic_msgs.msg import DiagnosticArray +from diagnostic_msgs.msg import DiagnosticStatus +from diagnostic_msgs.msg import KeyValue +from pydantic import BaseModel +from pydantic import Field +from pydantic import model_validator + +from log_evaluator.result import EvaluationItem +from log_evaluator.result import ResultBase +from log_evaluator.scenario import Scenario + + +class MinMax(BaseModel): + min: float | None = float_info.min + max: float | None = float_info.max + + @model_validator(mode="after") + def validate_min_max(self) -> "MinMax": + err_msg = "max must be a greater number than min" + + if self.max < self.min: + raise ValueError(err_msg) + return self + + +class LeftRight(BaseModel): + left: float = Field(float_info.max, gt=0.0) + right: float = Field(float_info.max, gt=0.0) + + +class LaneInfo(BaseModel): + id: int + s: float | None = None + t: LeftRight | None = None + + def is_started(self, lane_info: tuple) -> bool: + lane_id, s, t = lane_info + if self.id != lane_id: + return False + if self.s is not None and self.s > s: + return False + return True + + def match_condition(self, lane_info: tuple) -> bool: + _, _, t = lane_info + if self.t is not None and not ((-1.0) * self.t.right <= t <= self.left): + return False + return True + + def is_finished(self, lane_info: tuple) -> bool: + lane_id, s, _ = lane_info + if self.id != lane_id: + return False + # sを指定しない場合は、lane_idが切り替わる前までとかやりたいに違いない。 + if self.s is not None and self.s < s: + return False + return True + + +class LaneCondition(BaseModel): + start: LaneInfo + end: LaneInfo | None = None + started = False + finished = False + + @classmethod + def diag_lane_info(cls, lane_info: DiagnosticStatus) -> tuple[float, float, float]: + for kv in lane_info.values: + kv: KeyValue + if kv.key == "lane_id": + lane_id = kv.value + if kv.key == "s": + s = kv.value + if kv.key == "t": + t = kv.value + return (lane_id, s, t) + + def match_condition(self, lane_info: DiagnosticStatus) -> bool: + diag_lane_info = LaneCondition.diag_lane_info(lane_info) + if not self.started: + self.started = self.start.is_started(diag_lane_info) + if not self.finished: + self.finished = self.end.is_finished(diag_lane_info) + if not self.finished: + self. + + def is_started(self, lane_info: DiagnosticStatus) -> bool: + self.start.is_started(lane_info) + + def is_finished(self, lane_info: DiagnosticStatus) -> bool: + if self.end is None: + return False + return self.end.is_finished(lane_info) + + +class KinematicCondition(BaseModel): + vel: MinMax + acc: MinMax + jerk: MinMax + + +class PlanningControlCondition(BaseModel): + module: str + decision: str + condition_type: Literal["any_of", "all_of"] | None = "any_of" + lane_condition: LaneCondition | None = None + kinematic_condition: KinematicCondition | None = None + + +class Conditions(BaseModel): + ControlConditions: list[PlanningControlCondition] = [] + PlanningConditions: list[PlanningControlCondition] = [] + + +class Evaluation(BaseModel): + UseCaseName: Literal["planning_control"] + UseCaseFormatVersion: Literal["0.1.0"] + Conditions: Conditions + + +class PlanningControlScenario(Scenario): + Evaluation: Evaluation + + +@dataclass +class Metrics(EvaluationItem): + lane_info_list: list = field(default_factory=list) + kinematic_state_list: list = field(default_factory=list) + started: bool = False + + def set_frame(self, msg: DiagnosticArray) -> dict | None: + self.condition: PlanningControlCondition + + for status in msg.status: + if status.name != self.condition.module: + continue + if status.values[0].key != "decision": + continue + if status.values[0].value != self.condition.decision: + continue + + self.total += 1 + + frame_success = "Fail" + if (self.condition.Value0Value == status.values[0].value) and ( + self.condition.DetailedConditions is None + or self.check_detailed_condition(status.values[1:]) + ): + frame_success = "Success" + self.passed += 1 + self.success = self.passed >= required_successes + return { + "Result": {"Total": self.success_str(), "Frame": frame_success}, + "Info": {"TotalPassed": self.passed, "RequiredSuccess": required_successes}, + } + return None + + +class MetricsClassContainer: + def __init__(self, conditions: list[PlanningControlCondition], hz: float, module: str) -> None: + self.__container: list[Metrics] = [] + for i, time_cond in enumerate(conditions): + self.__container.append(Metrics(f"{module}_{i}", time_cond, hz=hz)) + + def set_frame(self, msg: DiagnosticArray) -> dict: + frame_result: dict[int, dict] = {} + for evaluation_item in self.__container: + result_i = evaluation_item.set_frame(msg) + if result_i is not None: + frame_result[f"{evaluation_item.name}"] = result_i + return frame_result + + def update(self) -> tuple[bool, str]: + rtn_success = True + rtn_summary = [] if len(self.__container) != 0 else ["NotTestTarget"] + for evaluation_item in self.__container: + if not evaluation_item.success: + rtn_success = False + rtn_summary.append(f"{evaluation_item.name} (Fail)") + else: + rtn_summary.append(f"{evaluation_item.name} (Success)") + prefix_str = "Passed" if rtn_success else "Failed" + rtn_summary_str = prefix_str + ":" + ", ".join(rtn_summary) + return (rtn_success, rtn_summary_str) + + +class PlanningControlResult(ResultBase): + def __init__(self, condition: Conditions) -> None: + super().__init__() + self.__control_container = MetricsClassContainer( + condition.ControlConditions, + condition.Hertz, + "control", + ) + self.__planning_container = MetricsClassContainer( + condition.PlanningConditions, + condition.Hertz, + "planning", + ) + + def update(self) -> None: + control_success, control_summary = self.__control_container.update() + planning_success, planning_summary = self.__planning_container.update() + self._success = control_success and planning_success + self._summary = "Control: " + control_summary + " Planning: " + planning_summary + + def set_frame(self, msg: DiagnosticArray, module: str) -> None: + if module == "control": + self._frame = self.__control_container.set_frame(msg) + if module == "planning": + self._frame = self.__planning_container.set_frame(msg) + self.update() diff --git a/log_evaluator/scripts/planning_control_evaluator_node.py b/log_evaluator/scripts/planning_control_evaluator_node.py new file mode 100755 index 00000000..41f0aa18 --- /dev/null +++ b/log_evaluator/scripts/planning_control_evaluator_node.py @@ -0,0 +1,58 @@ +#!/usr/bin/env python3 + +# Copyright (c) 2024 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 diagnostic_msgs.msg import DiagnosticArray + +from log_evaluator.evaluator import evaluator_main +from log_evaluator.evaluator import LogEvaluator +from log_evaluator.planning_control import PlanningControlResult +from log_evaluator.planning_control import PlanningControlScenario + + +class PlanningControlEvaluator(LogEvaluator): + def __init__(self, name: str) -> None: + super().__init__(name, PlanningControlScenario, PlanningControlResult) + self._scenario: PlanningControlScenario + self._result: PlanningControlResult + + self.__sub_planning_diagnostics = self.create_subscription( + DiagnosticArray, + "/diagnostic/planning_evaluator/metrics", + lambda msg, module_type="planning": self.diagnostics_cb(msg, module_type), + 1, + ) + + self.__sub_control_diagnostics = self.create_subscription( + DiagnosticArray, + "/diagnostic/control_evaluator/metrics", + lambda msg, module_type="control": self.diagnostics_cb(msg, module_type), + 1, + ) + + def diagnostics_cb(self, msg: DiagnosticArray, module: str) -> None: + self._result.set_frame(msg, module) + if self._result.frame != {}: + self._result_writer.write_result(self._result) + + +@evaluator_main +def main() -> LogEvaluator: + return PlanningControlEvaluator("planning_control_evaluator") + + +if __name__ == "__main__": + main() diff --git a/sample/planning_control/control_diag.txt b/sample/planning_control/control_diag.txt new file mode 100644 index 00000000..299bc815 --- /dev/null +++ b/sample/planning_control/control_diag.txt @@ -0,0 +1,34 @@ +# pos_x, pos_yでなくてstart_s, start_t, end_s, end_tとするのは区間指定・重複対応のため。 +# s,tは求めづらいのでrvizで可視化できると良い。 + +#---------- +# planning/control evaluator側 +# Decision +name: aeb # crosswalk, obstacle_cruise_planner.... + - key: decision + value: 'deceleration' # 'deceleration', 'none' + +name: crosswalk + - key: decision + value: 'none' # 複数ある場合は一番近いの計算して送る + +name: ... # その他色んなモジュールがdecisionを出す。 + +# 現在のvel, acc, jerkもだす +# planning/control evaluatorどちらから出すべき +name: kinematic_state # こっちは詳細条件で指定された場合に使うやつ + - key: vel + value: + - key: acc + value: + - key: jerk + value: +#---------- + +name: lane_info # kinematicでないので分離するほうがいいかも?これがモジュールの条件判定に使われる。lanelet2_extension_pythonで計算できるならlog_evaluatorで計算も可。sとtの計算はよくわからない。 + - key: lane_id + value: + - key: s # laneの開始からの縦距離 + value: + - key: t # laneの中心からの横距離 + value: diff --git a/sample/planning_control/result.json b/sample/planning_control/result.json new file mode 100644 index 00000000..356d3f62 --- /dev/null +++ b/sample/planning_control/result.json @@ -0,0 +1,481 @@ +[ + { + "Condition": { + "Hertz": 10, + "ControlConditions": [ + { + "TimeRange": { + "start": 1709009638.3, + "end": 1709009639.3 + }, + "Module": "autonomous_emergency_braking", + "Value0Key": "decision", + "Value0Value": "stop", + "DetailedConditions": null + }, + { + "TimeRange": { + "start": 1709009640, + "end": 1709009641 + }, + "Module": "autonomous_emergency_braking", + "Value0Key": "decision", + "Value0Value": "none", + "DetailedConditions": null + }, + { + "TimeRange": { + "start": 1709009640, + "end": 1709009641 + }, + "Module": "crosswalk", + "Value0Key": "decision", + "Value0Value": "slow_down", + "DetailedConditions": { + "pos_x": { + "lower": 1, + "upper": 2 + }, + "pos_y": { + "lower": 3, + "upper": 4 + }, + "vel": { + "lower": 3, + "upper": 4 + } + } + } + ], + "PlanningConditions": [] + } + }, + { + "Result": { + "Success": false, + "Summary": "NoData" + }, + "Stamp": { + "System": 1717122177.6615398 + }, + "Frame": {} + }, + { + "Result": { + "Success": false, + "Summary": "Control: Failed:condition0 (Success), condition1 (Fail), condition2 (Fail) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1717122206.1682308, + "ROS": 1717033424.612271 + }, + "Frame": { + "control_0": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 1, + "RequiredSuccess": 0 + } + } + } + }, + { + "Result": { + "Success": false, + "Summary": "Control: Failed:condition0 (Success), condition1 (Fail), condition2 (Fail) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1717122206.2692165, + "ROS": 1717033424.7122746 + }, + "Frame": { + "control_0": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 2, + "RequiredSuccess": 1 + } + } + } + }, + { + "Result": { + "Success": false, + "Summary": "Control: Failed:condition0 (Success), condition1 (Fail), condition2 (Fail) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1717122206.3680265, + "ROS": 1717033424.81225 + }, + "Frame": { + "control_0": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 3, + "RequiredSuccess": 2 + } + } + } + }, + { + "Result": { + "Success": false, + "Summary": "Control: Failed:condition0 (Success), condition1 (Fail), condition2 (Fail) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1717122206.4701612, + "ROS": 1717033424.912282 + }, + "Frame": { + "control_0": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 4, + "RequiredSuccess": 2 + } + } + } + }, + { + "Result": { + "Success": false, + "Summary": "Control: Failed:condition0 (Success), condition1 (Fail), condition2 (Fail) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1717122206.5757322, + "ROS": 1717033425.017296 + }, + "Frame": { + "control_0": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 5, + "RequiredSuccess": 3 + } + } + } + }, + { + "Result": { + "Success": false, + "Summary": "Control: Failed:condition0 (Success), condition1 (Fail), condition2 (Fail) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1717122206.6726487, + "ROS": 1717033425.107275 + }, + "Frame": { + "control_0": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 6, + "RequiredSuccess": 4 + } + } + } + }, + { + "Result": { + "Success": false, + "Summary": "Control: Failed:condition0 (Success), condition1 (Fail), condition2 (Fail) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1717122206.8685193, + "ROS": 1717033425.3122783 + }, + "Frame": { + "control_0": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 7, + "RequiredSuccess": 6 + } + } + } + }, + { + "Result": { + "Success": false, + "Summary": "Control: Failed:condition0 (Success), condition1 (Fail), condition2 (Fail) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1717122206.9683797, + "ROS": 1717033425.4123263 + }, + "Frame": { + "control_0": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 8, + "RequiredSuccess": 7 + } + } + } + }, + { + "Result": { + "Success": false, + "Summary": "Control: Failed:condition0 (Success), condition1 (Fail), condition2 (Fail) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1717122207.0700681, + "ROS": 1717033425.512249 + }, + "Frame": { + "control_0": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 9, + "RequiredSuccess": 8 + } + } + } + }, + { + "Result": { + "Success": false, + "Summary": "Control: Failed:condition0 (Success), condition1 (Success), condition2 (Fail) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1717122207.868164, + "ROS": 1717033426.312265 + }, + "Frame": { + "control_1": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 1, + "RequiredSuccess": 0 + } + } + } + }, + { + "Result": { + "Success": false, + "Summary": "Control: Failed:condition0 (Success), condition1 (Success), condition2 (Fail) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1717122207.9685762, + "ROS": 1717033426.4122493 + }, + "Frame": { + "control_1": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 2, + "RequiredSuccess": 1 + } + } + } + }, + { + "Result": { + "Success": false, + "Summary": "Control: Failed:condition0 (Success), condition1 (Success), condition2 (Fail) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1717122208.0686288, + "ROS": 1717033426.5122614 + }, + "Frame": { + "control_1": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 3, + "RequiredSuccess": 1 + } + } + } + }, + { + "Result": { + "Success": false, + "Summary": "Control: Failed:condition0 (Success), condition1 (Success), condition2 (Fail) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1717122208.1686108, + "ROS": 1717033426.6122468 + }, + "Frame": { + "control_1": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 4, + "RequiredSuccess": 2 + } + } + } + }, + { + "Result": { + "Success": false, + "Summary": "Control: Failed:condition0 (Success), condition1 (Success), condition2 (Fail) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1717122208.2720394, + "ROS": 1717033426.7122464 + }, + "Frame": { + "control_1": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 5, + "RequiredSuccess": 3 + } + } + } + }, + { + "Result": { + "Success": false, + "Summary": "Control: Failed:condition0 (Success), condition1 (Success), condition2 (Fail) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1717122208.3684468, + "ROS": 1717033426.8123136 + }, + "Frame": { + "control_1": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 6, + "RequiredSuccess": 4 + } + } + } + }, + { + "Result": { + "Success": false, + "Summary": "Control: Failed:condition0 (Success), condition1 (Success), condition2 (Fail) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1717122208.4684315, + "ROS": 1717033426.9122937 + }, + "Frame": { + "control_1": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 7, + "RequiredSuccess": 5 + } + } + } + }, + { + "Result": { + "Success": false, + "Summary": "Control: Failed:condition0 (Success), condition1 (Success), condition2 (Fail) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1717122208.5685694, + "ROS": 1717033427.0122683 + }, + "Frame": { + "control_1": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 8, + "RequiredSuccess": 6 + } + } + } + }, + { + "Result": { + "Success": false, + "Summary": "Control: Failed:condition0 (Success), condition1 (Success), condition2 (Fail) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1717122208.668613, + "ROS": 1717033427.1122494 + }, + "Frame": { + "control_1": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 9, + "RequiredSuccess": 7 + } + } + } + }, + { + "Result": { + "Success": false, + "Summary": "Control: Failed:condition0 (Success), condition1 (Success), condition2 (Fail) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1717122208.768232, + "ROS": 1717033427.2122433 + }, + "Frame": { + "control_1": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 10, + "RequiredSuccess": 8 + } + } + } + } +] diff --git a/sample/planning_control/scenario.ja.yaml b/sample/planning_control/scenario.ja.yaml new file mode 100644 index 00000000..787adeb9 --- /dev/null +++ b/sample/planning_control/scenario.ja.yaml @@ -0,0 +1,88 @@ +ScenarioFormatVersion: 2.2.0 +ScenarioName: sample_planning_control +ScenarioDescription: sample_planning_control +SensorModel: sample_sensor_kit +VehicleModel: sample_vehicle +VehicleId: default +LocalMapPath: $HOME/autoware_map/sample-map-planning +DataSetPath: /home/hyt/dlr_data/auto/t4_pc/xx1 +Evaluation: + UseCaseName: planning_control + UseCaseFormatVersion: 0.1.0 + Conditions: + ControlConditions: + - module: aeb + decision: deceleration # module の KeyValueのkeyをkeyにvalueをvalueに指定。今後追加でdecision以外が評価したいとなったらkey-valueが追加して対応する + condition_type: any_of # start-endのいずれかの区間で満たせばよい。 + lane_info: + start: + id: 100 + s: 1.0 + t: {left: 0.0, right: 0.0} + end: + id: 101 + s: 3.0 + t: {left: 3.0, right: 3.0} + kinematic_state: null # optional. 何も指定しないと減速しているかをdriving log replayer側で判定。指定する場合はそれの制約内かを判定。 + # 一定速度まで減速する必要がある場合。一つのモジュールで複数の範囲で指定可能 + - module: aeb + decision: deceleration + condition_type: any_of + lane_info: + start: + id: 200 + s: 5.0 + t: {left: 0.0, right: 0.0} + end: + id: 201 + s: 10.0 + t: {left: 0.0, right: 0.0} + kinematic_state: + vel: {min: 0.0, max: 1.0} + # planningもcontrolとまとめる? + # crosswalkの場合は停止計画なので速度を指定する + - module: crosswalk + decision: deceleration + condition_type: any_of + lane_info: + start: + id: 100 + s: 1.0 + t: {left: 0.0, right: 0.0} + end: + id: 101 + s: 3.0 + t: {left: 3.0, right: 3.0} + kinematic_state: + vel: {min: 0.0, max: 0.1} + - module: crosswalk + decision: deceleration + condition_type: any_of + lane_info: + start: + id: 200 + s: 5.0 + t: {left: 0.0, right: 0.0} + end: + id: 201 + s: 10.0 + t: {left: 0.0, right: 0.0} + kinematic_state: + vel: {min: 0.0, vel: 0.1} + # slowdownの例 指定区間全てで減速している必要がある + - module: obstacle_cruise_planner + decision: deceleration + condition_type: all_of # start-endの全ての区間で満たす + lane_info: + start: + id: 100 + s: 1.0 + t: {left: 0.0, right: 0.0} + end: + id: 101 + s: 3.0 + t: {left: 3.0, right: 3.0} + kinematic_state: + vel: {min: 1.0, max: 5.0} + acc: {min: -1.0, max: 0.0} + jerk: {min: -0.5} From 6fd279f0d8e5960d1ee7f52a76e91fe48b575cd1 Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Tue, 16 Jul 2024 18:06:23 +0900 Subject: [PATCH 02/28] feat: update evaluation logic --- .../log_evaluator/planning_control.py | 35 +- sample/planning_control/control_diag.txt | 6178 +++++++++++++++++ sample/planning_control/scenario.ja.yaml | 13 +- 3 files changed, 6200 insertions(+), 26 deletions(-) diff --git a/log_evaluator/log_evaluator/planning_control.py b/log_evaluator/log_evaluator/planning_control.py index dd46ce80..30dc941d 100644 --- a/log_evaluator/log_evaluator/planning_control.py +++ b/log_evaluator/log_evaluator/planning_control.py @@ -43,8 +43,13 @@ def validate_min_max(self) -> "MinMax": class LeftRight(BaseModel): - left: float = Field(float_info.max, gt=0.0) - right: float = Field(float_info.max, gt=0.0) + left: float = Field(float_info.max, gt=0.0) # + + right: float = Field(float_info.max, gt=0.0) # - + + def match_condition(self, t: float): + if (-1)*self.right <= t <= self.left: + return True + return False class LaneInfo(BaseModel): @@ -58,11 +63,7 @@ def is_started(self, lane_info: tuple) -> bool: return False if self.s is not None and self.s > s: return False - return True - - def match_condition(self, lane_info: tuple) -> bool: - _, _, t = lane_info - if self.t is not None and not ((-1.0) * self.t.right <= t <= self.left): + if self.t is not None and not self.t.match_condition(t): return False return True @@ -70,17 +71,14 @@ def is_finished(self, lane_info: tuple) -> bool: lane_id, s, _ = lane_info if self.id != lane_id: return False - # sを指定しない場合は、lane_idが切り替わる前までとかやりたいに違いない。 if self.s is not None and self.s < s: return False return True class LaneCondition(BaseModel): - start: LaneInfo + start: LaneInfo | None = None end: LaneInfo | None = None - started = False - finished = False @classmethod def diag_lane_info(cls, lane_info: DiagnosticStatus) -> tuple[float, float, float]: @@ -121,7 +119,7 @@ class KinematicCondition(BaseModel): class PlanningControlCondition(BaseModel): module: str decision: str - condition_type: Literal["any_of", "all_of"] | None = "any_of" + condition_type: Literal["any_of", "all_of"] lane_condition: LaneCondition | None = None kinematic_condition: KinematicCondition | None = None @@ -143,14 +141,13 @@ class PlanningControlScenario(Scenario): @dataclass class Metrics(EvaluationItem): - lane_info_list: list = field(default_factory=list) - kinematic_state_list: list = field(default_factory=list) - started: bool = False + is_under_evaluation: bool = False def set_frame(self, msg: DiagnosticArray) -> dict | None: self.condition: PlanningControlCondition for status in msg.status: + status: DiagnosticStatus if status.name != self.condition.module: continue if status.values[0].key != "decision": @@ -176,10 +173,10 @@ def set_frame(self, msg: DiagnosticArray) -> dict | None: class MetricsClassContainer: - def __init__(self, conditions: list[PlanningControlCondition], hz: float, module: str) -> None: + def __init__(self, conditions: list[PlanningControlCondition], module: str) -> None: self.__container: list[Metrics] = [] - for i, time_cond in enumerate(conditions): - self.__container.append(Metrics(f"{module}_{i}", time_cond, hz=hz)) + for i, module_cond in enumerate(conditions): + self.__container.append(Metrics(f"{module}_{i}", module_cond)) def set_frame(self, msg: DiagnosticArray) -> dict: frame_result: dict[int, dict] = {} @@ -208,12 +205,10 @@ def __init__(self, condition: Conditions) -> None: super().__init__() self.__control_container = MetricsClassContainer( condition.ControlConditions, - condition.Hertz, "control", ) self.__planning_container = MetricsClassContainer( condition.PlanningConditions, - condition.Hertz, "planning", ) diff --git a/sample/planning_control/control_diag.txt b/sample/planning_control/control_diag.txt index 299bc815..cb26d934 100644 --- a/sample/planning_control/control_diag.txt +++ b/sample/planning_control/control_diag.txt @@ -32,3 +32,6181 @@ name: lane_info # kinematicでないので分離するほうがいいかも? value: - key: t # laneの中心からの横距離 value: + + +~/ros_ws/planning_control dlr/test-platform* 5m 49s +❯ ros2 topic echo /diagnostic/control_evaluator/metrics +1721114673.647621 [77] ros2: determined eno1 (udp/10.0.55.137) as highest quality interface, selected for automatic interface. +header: + stamp: + sec: 1709009632 + nanosec: 404397388 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '11.807869' + - key: t + value: '-0.027418' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '4.164290' + - key: acc + value: '-0.245304' + - key: jerk + value: '-0.860871' +--- +header: + stamp: + sec: 1709009632 + nanosec: 504355839 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '12.224617' + - key: t + value: '-0.018463' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '4.157930' + - key: acc + value: '-0.162705' + - key: jerk + value: '0.824320' +--- +header: + stamp: + sec: 1709009632 + nanosec: 604399852 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '12.638497' + - key: t + value: '-0.005600' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '4.114442' + - key: acc + value: '-0.262229' + - key: jerk + value: '-0.995871' +--- +header: + stamp: + sec: 1709009632 + nanosec: 704401222 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '13.048985' + - key: t + value: '-0.017200' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '4.077619' + - key: acc + value: '-0.306019' + - key: jerk + value: '-0.434886' +--- +header: + stamp: + sec: 1709009632 + nanosec: 804405494 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '13.459571' + - key: t + value: '-0.026677' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '4.051801' + - key: acc + value: '-0.290056' + - key: jerk + value: '0.159762' +--- +header: + stamp: + sec: 1709009632 + nanosec: 904397276 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '13.864332' + - key: t + value: '-0.032471' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '4.039792' + - key: acc + value: '-0.237908' + - key: jerk + value: '0.522073' +--- +header: + stamp: + sec: 1709009633 + nanosec: 4402718 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '14.268093' + - key: t + value: '-0.031601' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '4.024280' + - key: acc + value: '-0.192781' + - key: jerk + value: '0.450397' +--- +header: + stamp: + sec: 1709009633 + nanosec: 104399187 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '14.668894' + - key: t + value: '-0.027730' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.993165' + - key: acc + value: '-0.238488' + - key: jerk + value: '-0.460506' +--- +header: + stamp: + sec: 1709009633 + nanosec: 204398359 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '15.068897' + - key: t + value: '-0.018027' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.987874' + - key: acc + value: '-0.164279' + - key: jerk + value: '0.737804' +--- +header: + stamp: + sec: 1709009633 + nanosec: 304349655 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.025369' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.004000' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '15.465595' + - key: t + value: '-0.002923' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.988385' + - key: acc + value: '-0.093019' + - key: jerk + value: '0.718444' +--- +header: + stamp: + sec: 1709009633 + nanosec: 404406859 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.026010' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.004765' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '15.860878' + - key: t + value: '0.018357' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.951453' + - key: acc + value: '-0.201406' + - key: jerk + value: '-1.084758' +--- +header: + stamp: + sec: 1709009633 + nanosec: 504402461 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.043618' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.001869' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '16.253703' + - key: t + value: '0.045773' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.933332' + - key: acc + value: '-0.190086' + - key: jerk + value: '0.112204' +--- +header: + stamp: + sec: 1709009633 + nanosec: 604397104 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.033925' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.005160' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '16.646073' + - key: t + value: '0.078742' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.924233' + - key: acc + value: '-0.147421' + - key: jerk + value: '0.427608' +--- +header: + stamp: + sec: 1709009633 + nanosec: 704398088 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.032928' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.003028' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '17.054920' + - key: t + value: '0.067871' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.897449' + - key: acc + value: '-0.176098' + - key: jerk + value: '-0.283933' +--- +header: + stamp: + sec: 1709009633 + nanosec: 804396573 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.034375' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.002316' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '17.438880' + - key: t + value: '0.033011' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.864558' + - key: acc + value: '-0.224534' + - key: jerk + value: '-0.484897' +--- +header: + stamp: + sec: 1709009633 + nanosec: 904370804 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.033854' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.000219' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '17.822643' + - key: t + value: '0.003604' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.815756' + - key: acc + value: '-0.324810' + - key: jerk + value: '-1.014564' +--- +header: + stamp: + sec: 1709009634 + nanosec: 4622345 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.032416' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.003169' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '18.202224' + - key: t + value: '-0.016596' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.793325' + - key: acc + value: '-0.269849' + - key: jerk + value: '0.551987' +--- +header: + stamp: + sec: 1709009634 + nanosec: 104403083 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.032518' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.017093' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '18.578890' + - key: t + value: '-0.029997' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.758273' + - key: acc + value: '-0.317572' + - key: jerk + value: '-0.474196' +--- +header: + stamp: + sec: 1709009634 + nanosec: 204407371 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.032112' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.015094' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '18.950500' + - key: t + value: '-0.035818' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.728484' + - key: acc + value: '-0.300998' + - key: jerk + value: '0.166093' +--- +header: + stamp: + sec: 1709009634 + nanosec: 304399499 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.027861' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.011690' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '19.317634' + - key: t + value: '-0.030101' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.693635' + - key: acc + value: '-0.332801' + - key: jerk + value: '-0.315577' +--- +header: + stamp: + sec: 1709009634 + nanosec: 404400912 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.020459' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.014390' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '19.683569' + - key: t + value: '-0.018609' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.644010' + - key: acc + value: '-0.417998' + - key: jerk + value: '-0.860537' +--- +header: + stamp: + sec: 1709009634 + nanosec: 504402082 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.033513' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.013516' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '20.047342' + - key: t + value: '0.001176' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.651010' + - key: acc + value: '-0.219605' + - key: jerk + value: '1.982136' +--- +header: + stamp: + sec: 1709009634 + nanosec: 604408766 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.036433' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.014549' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '20.411824' + - key: t + value: '0.028157' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.631270' + - key: acc + value: '-0.224491' + - key: jerk + value: '-0.048567' +--- +header: + stamp: + sec: 1709009634 + nanosec: 704401891 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.021742' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.012889' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '20.770255' + - key: t + value: '0.063837' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.609732' + - key: acc + value: '-0.223466' + - key: jerk + value: '0.010292' +--- +header: + stamp: + sec: 1709009634 + nanosec: 804402528 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.033043' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.010015' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '21.172657' + - key: t + value: '0.060088' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.602591' + - key: acc + value: '-0.176368' + - key: jerk + value: '0.444927' +--- +header: + stamp: + sec: 1709009634 + nanosec: 904401578 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.023385' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.009472' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '21.504707' + - key: t + value: '0.016219' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.563133' + - key: acc + value: '-0.277536' + - key: jerk + value: '-1.073808' +--- +header: + stamp: + sec: 1709009635 + nanosec: 4409379 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.028143' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.010353' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '21.855572' + - key: t + value: '-0.020629' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.547458' + - key: acc + value: '-0.228453' + - key: jerk + value: '0.490374' +--- +header: + stamp: + sec: 1709009635 + nanosec: 104402212 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.024038' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.009086' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '22.208145' + - key: t + value: '-0.049282' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.531702' + - key: acc + value: '-0.214168' + - key: jerk + value: '0.143816' +--- +header: + stamp: + sec: 1709009635 + nanosec: 204399984 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.027309' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.009630' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '22.558326' + - key: t + value: '-0.071643' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.516410' + - key: acc + value: '-0.189944' + - key: jerk + value: '0.237638' +--- +header: + stamp: + sec: 1709009635 + nanosec: 304401060 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.036380' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.009749' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '22.906186' + - key: t + value: '-0.087145' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.496249' + - key: acc + value: '-0.192153' + - key: jerk + value: '-0.022431' +--- +header: + stamp: + sec: 1709009635 + nanosec: 404403684 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.051493' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.006277' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '23.251555' + - key: t + value: '-0.092226' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.488161' + - key: acc + value: '-0.141204' + - key: jerk + value: '0.508395' +--- +header: + stamp: + sec: 1709009635 + nanosec: 504404540 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.034991' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.014021' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '23.596912' + - key: t + value: '-0.090172' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.472385' + - key: acc + value: '-0.165042' + - key: jerk + value: '-0.239460' +--- +header: + stamp: + sec: 1709009635 + nanosec: 604401859 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.069065' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.007616' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '23.943344' + - key: t + value: '-0.079462' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.464842' + - key: acc + value: '-0.133225' + - key: jerk + value: '0.316310' +--- +header: + stamp: + sec: 1709009635 + nanosec: 704401363 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.069201' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.002540' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '24.286892' + - key: t + value: '-0.059856' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.459577' + - key: acc + value: '-0.105967' + - key: jerk + value: '0.275366' +--- +header: + stamp: + sec: 1709009635 + nanosec: 804404624 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.065768' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.003422' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '24.632572' + - key: t + value: '-0.033874' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.459042' + - key: acc + value: '-0.065826' + - key: jerk + value: '0.398159' +--- +header: + stamp: + sec: 1709009635 + nanosec: 904385192 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.056024' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.006617' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '24.971668' + - key: t + value: '0.000769' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.431239' + - key: acc + value: '-0.159842' + - key: jerk + value: '-0.936098' +--- +header: + stamp: + sec: 1709009636 + nanosec: 4414142 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.078727' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.001546' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '25.314088' + - key: t + value: '0.007231' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.406308' + - key: acc + value: '-0.197551' + - key: jerk + value: '-0.378975' +--- +header: + stamp: + sec: 1709009636 + nanosec: 104402382 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.077044' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.003557' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '25.647174' + - key: t + value: '-0.029318' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.385903' + - key: acc + value: '-0.199265' + - key: jerk + value: '-0.017086' +--- +header: + stamp: + sec: 1709009636 + nanosec: 204404017 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.087602' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.000475' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '25.983543' + - key: t + value: '-0.058872' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.373357' + - key: acc + value: '-0.156002' + - key: jerk + value: '0.435549' +--- +header: + stamp: + sec: 1709009636 + nanosec: 304404689 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.083968' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.003294' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '26.317021' + - key: t + value: '-0.078753' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.339658' + - key: acc + value: '-0.234312' + - key: jerk + value: '-0.780355' +--- +header: + stamp: + sec: 1709009636 + nanosec: 404400526 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.090360' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.006444' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '26.646357' + - key: t + value: '-0.091089' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.318838' + - key: acc + value: '-0.227483' + - key: jerk + value: '0.067870' +--- +header: + stamp: + sec: 1709009636 + nanosec: 504401874 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.094138' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.010599' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '26.973981' + - key: t + value: '-0.094759' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.289312' + - key: acc + value: '-0.259603' + - key: jerk + value: '-0.323090' +--- +header: + stamp: + sec: 1709009636 + nanosec: 604399116 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.085571' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.014195' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '27.298338' + - key: t + value: '-0.089062' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.282849' + - key: acc + value: '-0.167568' + - key: jerk + value: '0.921623' +--- +header: + stamp: + sec: 1709009636 + nanosec: 704403027 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.076062' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.010848' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '27.624338' + - key: t + value: '-0.075814' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.276570' + - key: acc + value: '-0.116953' + - key: jerk + value: '0.507004' +--- +header: + stamp: + sec: 1709009636 + nanosec: 804409130 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.070814' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.015993' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '27.949007' + - key: t + value: '-0.056075' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.285428' + - key: acc + value: '-0.024339' + - key: jerk + value: '0.929589' +--- +header: + stamp: + sec: 1709009636 + nanosec: 904401159 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.063623' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.013067' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '28.274616' + - key: t + value: '-0.027441' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.294343' + - key: acc + value: '0.020471' + - key: jerk + value: '0.436154' +--- +header: + stamp: + sec: 1709009637 + nanosec: 4401350 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.060313' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.001066' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '28.602352' + - key: t + value: '0.009481' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.299993' + - key: acc + value: '0.033551' + - key: jerk + value: '0.134107' +--- +header: + stamp: + sec: 1709009637 + nanosec: 104377720 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.063324' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.006147' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '28.930982' + - key: t + value: '0.055127' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.310351' + - key: acc + value: '0.051750' + - key: jerk + value: '0.181860' +--- +header: + stamp: + sec: 1709009637 + nanosec: 204400741 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.065196' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.009482' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '29.253953' + - key: t + value: '0.107721' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.327083' + - key: acc + value: '0.110871' + - key: jerk + value: '0.581150' +--- +header: + stamp: + sec: 1709009637 + nanosec: 304399357 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.061152' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.010437' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '29.625718' + - key: t + value: '0.076836' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.322890' + - key: acc + value: '0.046393' + - key: jerk + value: '-0.633029' +--- +header: + stamp: + sec: 1709009637 + nanosec: 404402047 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.045513' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.009830' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '29.951530' + - key: t + value: '0.029930' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.332101' + - key: acc + value: '0.062972' + - key: jerk + value: '0.171483' +--- +header: + stamp: + sec: 1709009637 + nanosec: 504399264 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.027418' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.002446' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '30.282104' + - key: t + value: '-0.009942' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.348156' + - key: acc + value: '0.094798' + - key: jerk + value: '0.313989' +--- +header: + stamp: + sec: 1709009637 + nanosec: 604402430 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.067232' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.016803' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '30.617080' + - key: t + value: '-0.044809' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.376559' + - key: acc + value: '0.177190' + - key: jerk + value: '0.839564' +--- +header: + stamp: + sec: 1709009637 + nanosec: 704400683 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.077263' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.010312' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '30.955830' + - key: t + value: '-0.071936' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.403736' + - key: acc + value: '0.216875' + - key: jerk + value: '0.392260' +--- +header: + stamp: + sec: 1709009637 + nanosec: 804399832 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.103227' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.007414' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '31.295542' + - key: t + value: '-0.092534' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.422113' + - key: acc + value: '0.205161' + - key: jerk + value: '-0.116102' +--- +header: + stamp: + sec: 1709009637 + nanosec: 904404386 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.114550' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.006291' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '31.637928' + - key: t + value: '-0.106168' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.433946' + - key: acc + value: '0.164503' + - key: jerk + value: '-0.413887' +--- +header: + stamp: + sec: 1709009638 + nanosec: 4380889 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.097242' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.010474' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '31.976767' + - key: t + value: '-0.112751' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.423078' + - key: acc + value: '0.047411' + - key: jerk + value: '-1.155156' +--- +header: + stamp: + sec: 1709009638 + nanosec: 104401638 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.120685' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.015547' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '32.330131' + - key: t + value: '-0.110941' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.409248' + - key: acc + value: '-0.028400' + - key: jerk + value: '-0.739542' +--- +header: + stamp: + sec: 1709009638 + nanosec: 204401112 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.129125' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.012326' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '32.653723' + - key: t + value: '-0.103303' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.392227' + - key: acc + value: '-0.089833' + - key: jerk + value: '-0.636760' +--- +header: + stamp: + sec: 1709009638 + nanosec: 304399600 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.094222' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.004253' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '32.991292' + - key: t + value: '-0.092907' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.375724' + - key: acc + value: '-0.119411' + - key: jerk + value: '-0.292589' +--- +header: + stamp: + sec: 1709009638 + nanosec: 404406320 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.094543' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.030371' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '33.328334' + - key: t + value: '-0.080002' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.347397' + - key: acc + value: '-0.181810' + - key: jerk + value: '-0.624531' +--- +header: + stamp: + sec: 1709009638 + nanosec: 504404271 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.081011' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.057709' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '33.638464' + - key: t + value: '-0.090885' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.302839' + - key: acc + value: '-0.287816' + - key: jerk + value: '-1.071392' +--- +header: + stamp: + sec: 1709009638 + nanosec: 604400878 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.035806' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.083509' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '33.957364' + - key: t + value: '-0.146791' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.250613' + - key: acc + value: '-0.395964' + - key: jerk + value: '-1.082415' +--- +header: + stamp: + sec: 1709009638 + nanosec: 704405284 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.002404' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.109910' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '34.271024' + - key: t + value: '-0.207536' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.201738' + - key: acc + value: '-0.424839' + - key: jerk + value: '-0.288387' +--- +header: + stamp: + sec: 1709009638 + nanosec: 804405072 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: deceleration +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.038727' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.139692' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '34.610130' + - key: t + value: '-0.275624' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.164714' + - key: acc + value: '-0.400825' + - key: jerk + value: '0.217844' +--- +header: + stamp: + sec: 1709009638 + nanosec: 904416356 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: deceleration +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.196166' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.154997' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '34.882375' + - key: t + value: '-0.334608' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.133997' + - key: acc + value: '-0.404052' + - key: jerk + value: '-0.035990' +--- +header: + stamp: + sec: 1709009639 + nanosec: 4417901 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: deceleration +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.247082' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.168040' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '35.183540' + - key: t + value: '-0.399925' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.108041' + - key: acc + value: '-0.337578' + - key: jerk + value: '0.643050' +--- +header: + stamp: + sec: 1709009639 + nanosec: 104411118 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: deceleration +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.292116' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.176340' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '35.484670' + - key: t + value: '-0.464261' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.068601' + - key: acc + value: '-0.366837' + - key: jerk + value: '-0.304465' +--- +header: + stamp: + sec: 1709009639 + nanosec: 204407354 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: deceleration +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.341302' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.182917' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '35.778943' + - key: t + value: '-0.529533' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.023590' + - key: acc + value: '-0.409510' + - key: jerk + value: '-0.421688' +--- +header: + stamp: + sec: 1709009639 + nanosec: 304410525 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: deceleration +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.417672' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.186204' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '36.095905' + - key: t + value: '-0.597037' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '2.995624' + - key: acc + value: '-0.345813' + - key: jerk + value: '0.593408' +--- +header: + stamp: + sec: 1709009639 + nanosec: 404414696 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: deceleration +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.459117' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.189278' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '36.359724' + - key: t + value: '-0.654262' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '2.972544' + - key: acc + value: '-0.299326' + - key: jerk + value: '0.508477' +--- +header: + stamp: + sec: 1709009639 + nanosec: 504406939 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: deceleration +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.511652' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.191124' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '36.645451' + - key: t + value: '-0.712760' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '2.944074' + - key: acc + value: '-0.285829' + - key: jerk + value: '0.132708' +--- +header: + stamp: + sec: 1709009639 + nanosec: 604409723 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: deceleration +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.587826' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.188456' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '36.933826' + - key: t + value: '-0.770362' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '2.919497' + - key: acc + value: '-0.274788' + - key: jerk + value: '0.111478' +--- +header: + stamp: + sec: 1709009639 + nanosec: 704403639 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: deceleration +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.659352' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.184065' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '37.217586' + - key: t + value: '-0.824414' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '2.877049' + - key: acc + value: '-0.330259' + - key: jerk + value: '-0.558135' +--- +header: + stamp: + sec: 1709009639 + nanosec: 804407921 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: deceleration +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.710881' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.178507' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '37.496811' + - key: t + value: '-0.876442' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '2.849749' + - key: acc + value: '-0.320258' + - key: jerk + value: '0.099428' +--- +header: + stamp: + sec: 1709009639 + nanosec: 904405274 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: deceleration +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.765217' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.172269' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '176472' + - key: s + value: '37.738132' + - key: t + value: '-0.925174' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '2.809040' + - key: acc + value: '-0.352498' + - key: jerk + value: '-0.321446' +--- +header: + stamp: + sec: 1709009640 + nanosec: 4411217 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: deceleration +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.832975' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.161679' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '0.254821' + - key: t + value: '-0.983676' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '2.780202' + - key: acc + value: '-0.322109' + - key: jerk + value: '0.299525' +--- +header: + stamp: + sec: 1709009640 + nanosec: 104409667 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: deceleration +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.876415' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.153313' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '0.524374' + - key: t + value: '-1.038678' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '2.778970' + - key: acc + value: '-0.193682' + - key: jerk + value: '1.284198' +--- +header: + stamp: + sec: 1709009640 + nanosec: 204408500 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: deceleration +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.914800' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.142017' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '0.797716' + - key: t + value: '-1.089461' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '2.766703' + - key: acc + value: '-0.157067' + - key: jerk + value: '0.374411' +--- +header: + stamp: + sec: 1709009640 + nanosec: 304402334 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: deceleration +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.951588' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.128978' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '1.072910' + - key: t + value: '-1.137064' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '2.774931' + - key: acc + value: '-0.064950' + - key: jerk + value: '0.919988' +--- +header: + stamp: + sec: 1709009640 + nanosec: 404404029 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: deceleration +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '1.016150' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.118127' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '1.345795' + - key: t + value: '-1.181963' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '2.785044' + - key: acc + value: '0.000635' + - key: jerk + value: '0.654367' +--- +header: + stamp: + sec: 1709009640 + nanosec: 504402608 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: deceleration +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '1.043522' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.104031' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '1.619427' + - key: t + value: '-1.222165' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '2.806327' + - key: acc + value: '0.093698' + - key: jerk + value: '0.929944' +--- +header: + stamp: + sec: 1709009640 + nanosec: 604408011 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: deceleration +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '1.069969' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.091281' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '1.899189' + - key: t + value: '-1.257947' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '2.826436' + - key: acc + value: '0.134591' + - key: jerk + value: '0.411654' +--- +header: + stamp: + sec: 1709009640 + nanosec: 704403572 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: deceleration +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '1.103021' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.076999' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '2.180388' + - key: t + value: '-1.287927' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '2.855254' + - key: acc + value: '0.206083' + - key: jerk + value: '0.706992' +--- +header: + stamp: + sec: 1709009640 + nanosec: 804400090 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: deceleration +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '1.166697' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.064772' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '2.463578' + - key: t + value: '-1.315164' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '2.871829' + - key: acc + value: '0.189194' + - key: jerk + value: '-0.169536' +--- +header: + stamp: + sec: 1709009640 + nanosec: 904408423 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: deceleration +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '1.185643' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.049794' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '2.756252' + - key: t + value: '-1.339019' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '2.924632' + - key: acc + value: '0.313097' + - key: jerk + value: '1.232130' +--- +header: + stamp: + sec: 1709009641 + nanosec: 4410489 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '1.200281' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.034773' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '3.048498' + - key: t + value: '-1.357804' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '2.973334' + - key: acc + value: '0.388577' + - key: jerk + value: '0.757059' +--- +header: + stamp: + sec: 1709009641 + nanosec: 104403955 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '1.241443' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.020706' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '3.348355' + - key: t + value: '-1.371031' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.031645' + - key: acc + value: '0.492628' + - key: jerk + value: '1.050884' +--- +header: + stamp: + sec: 1709009641 + nanosec: 204406868 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '1.256049' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.005195' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '3.654895' + - key: t + value: '-1.378377' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.088592' + - key: acc + value: '0.524980' + - key: jerk + value: '0.322604' +--- +header: + stamp: + sec: 1709009641 + nanosec: 304403545 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '1.255756' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.010914' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '3.967671' + - key: t + value: '-1.380667' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.152821' + - key: acc + value: '0.584220' + - key: jerk + value: '0.590881' +--- +header: + stamp: + sec: 1709009641 + nanosec: 404414036 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '1.259759' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.025090' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '4.286699' + - key: t + value: '-1.378690' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.220785' + - key: acc + value: '0.655660' + - key: jerk + value: '0.710801' +--- +header: + stamp: + sec: 1709009641 + nanosec: 504407066 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '1.221319' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.040636' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '4.614102' + - key: t + value: '-1.371985' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.287503' + - key: acc + value: '0.687749' + - key: jerk + value: '0.320499' +--- +header: + stamp: + sec: 1709009641 + nanosec: 604411210 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '1.215403' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.052577' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '4.954561' + - key: t + value: '-1.359024' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.346353' + - key: acc + value: '0.642912' + - key: jerk + value: '-0.443885' +--- +header: + stamp: + sec: 1709009641 + nanosec: 704414774 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '1.227203' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.061235' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '5.289516' + - key: t + value: '-1.341692' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.407900' + - key: acc + value: '0.626983' + - key: jerk + value: '-0.162374' +--- +header: + stamp: + sec: 1709009641 + nanosec: 804408603 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '1.203615' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.071551' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '5.636661' + - key: t + value: '-1.319875' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.475030' + - key: acc + value: '0.605346' + - key: jerk + value: '-0.217098' +--- +header: + stamp: + sec: 1709009641 + nanosec: 904408132 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '1.175841' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.080601' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '5.989970' + - key: t + value: '-1.294059' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.537443' + - key: acc + value: '0.650080' + - key: jerk + value: '0.445461' +--- +header: + stamp: + sec: 1709009642 + nanosec: 4359569 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '1.152956' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.087397' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '6.348585' + - key: t + value: '-1.265829' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.609332' + - key: acc + value: '0.664397' + - key: jerk + value: '0.140656' +--- +header: + stamp: + sec: 1709009642 + nanosec: 104407311 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '1.118816' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.093438' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '6.715403' + - key: t + value: '-1.232613' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.693096' + - key: acc + value: '0.754094' + - key: jerk + value: '0.908683' +--- +header: + stamp: + sec: 1709009642 + nanosec: 204410579 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '1.083005' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.097700' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '7.089984' + - key: t + value: '-1.197086' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.774627' + - key: acc + value: '0.811998' + - key: jerk + value: '0.580573' +--- +header: + stamp: + sec: 1709009642 + nanosec: 304407858 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '1.048047' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.100630' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '7.473814' + - key: t + value: '-1.158361' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.848118' + - key: acc + value: '0.791756' + - key: jerk + value: '-0.201294' +--- +header: + stamp: + sec: 1709009642 + nanosec: 404405559 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '1.006286' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.102594' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '7.863955' + - key: t + value: '-1.116921' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '3.930269' + - key: acc + value: '0.825974' + - key: jerk + value: '0.344808' +--- +header: + stamp: + sec: 1709009642 + nanosec: 504405783 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.966912' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.102802' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '8.264956' + - key: t + value: '-1.076771' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '4.006945' + - key: acc + value: '0.811871' + - key: jerk + value: '-0.140155' +--- +header: + stamp: + sec: 1709009642 + nanosec: 604410778 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.927086' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.102103' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '8.687818' + - key: t + value: '-1.034342' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '4.083466' + - key: acc + value: '0.789160' + - key: jerk + value: '-0.220425' +--- +header: + stamp: + sec: 1709009642 + nanosec: 704406881 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.887594' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.101057' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '9.086423' + - key: t + value: '-0.993832' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '4.153996' + - key: acc + value: '0.769382' + - key: jerk + value: '-0.205345' +--- +header: + stamp: + sec: 1709009642 + nanosec: 804408753 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.847435' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.099233' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '9.505482' + - key: t + value: '-0.951828' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '4.233492' + - key: acc + value: '0.802354' + - key: jerk + value: '0.328948' +--- +header: + stamp: + sec: 1709009642 + nanosec: 904416934 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.802559' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.097481' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '9.943206' + - key: t + value: '-0.906019' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '4.281736' + - key: acc + value: '0.657596' + - key: jerk + value: '-1.443561' +--- +header: + stamp: + sec: 1709009643 + nanosec: 4414587 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.760994' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.095718' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '10.377127' + - key: t + value: '-0.859918' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '4.371687' + - key: acc + value: '0.765366' + - key: jerk + value: '1.085507' +--- +header: + stamp: + sec: 1709009643 + nanosec: 104420505 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.718341' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.093899' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '10.819839' + - key: t + value: '-0.813713' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '4.449620' + - key: acc + value: '0.759741' + - key: jerk + value: '-0.056001' +--- +header: + stamp: + sec: 1709009643 + nanosec: 204414143 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.677567' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.091658' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '11.269511' + - key: t + value: '-0.769288' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '4.515152' + - key: acc + value: '0.705259' + - key: jerk + value: '-0.547844' +--- +header: + stamp: + sec: 1709009643 + nanosec: 304409405 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.636199' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.089442' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '11.732517' + - key: t + value: '-0.723596' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '4.643522' + - key: acc + value: '0.936769' + - key: jerk + value: '2.295276' +--- +header: + stamp: + sec: 1709009643 + nanosec: 404408357 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.595805' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.086742' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '12.203680' + - key: t + value: '-0.679467' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '4.714383' + - key: acc + value: '0.870530' + - key: jerk + value: '-0.665125' +--- +header: + stamp: + sec: 1709009643 + nanosec: 504408288 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.556659' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.083749' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '12.681458' + - key: t + value: '-0.636197' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '4.781159' + - key: acc + value: '0.782888' + - key: jerk + value: '-0.871966' +--- +header: + stamp: + sec: 1709009643 + nanosec: 604416966 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.518422' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.080730' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '13.165103' + - key: t + value: '-0.594228' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '4.845298' + - key: acc + value: '0.875744' + - key: jerk + value: '0.938267' +--- +header: + stamp: + sec: 1709009643 + nanosec: 704412200 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.478444' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.077884' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '13.659722' + - key: t + value: '-0.550278' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '4.961584' + - key: acc + value: '0.963578' + - key: jerk + value: '0.874294' +--- +header: + stamp: + sec: 1709009643 + nanosec: 804416329 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.438143' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.075065' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '14.164645' + - key: t + value: '-0.506251' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '5.028357' + - key: acc + value: '0.830937' + - key: jerk + value: '-1.324163' +--- +header: + stamp: + sec: 1709009643 + nanosec: 904411958 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.399433' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.071776' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '14.675367' + - key: t + value: '-0.463699' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '5.105083' + - key: acc + value: '0.820178' + - key: jerk + value: '-0.107559' +--- +header: + stamp: + sec: 1709009644 + nanosec: 4412436 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.363026' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.067987' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '15.195114' + - key: t + value: '-0.423452' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '5.183570' + - key: acc + value: '0.803005' + - key: jerk + value: '-0.171691' +--- +header: + stamp: + sec: 1709009644 + nanosec: 104404806 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.327198' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.064287' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '15.720697' + - key: t + value: '-0.383685' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '5.263354' + - key: acc + value: '0.804745' + - key: jerk + value: '0.017441' +--- +header: + stamp: + sec: 1709009644 + nanosec: 204374578 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.294181' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.060668' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '16.255231' + - key: t + value: '-0.346902' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '5.344423' + - key: acc + value: '0.821352' + - key: jerk + value: '0.166395' +--- +header: + stamp: + sec: 1709009644 + nanosec: 304407810 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.264649' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.056752' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '16.797438' + - key: t + value: '-0.313619' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '5.409145' + - key: acc + value: '0.724561' + - key: jerk + value: '-0.960358' +--- +header: + stamp: + sec: 1709009644 + nanosec: 404406024 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.230520' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.052595' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '17.374075' + - key: t + value: '-0.275700' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '5.488134' + - key: acc + value: '0.744188' + - key: jerk + value: '0.188219' +--- +header: + stamp: + sec: 1709009644 + nanosec: 504406423 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.209591' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.049251' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '17.792559' + - key: t + value: '-0.252145' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '5.567167' + - key: acc + value: '0.861748' + - key: jerk + value: '1.555661' +--- +header: + stamp: + sec: 1709009644 + nanosec: 604407422 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.177184' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.044099' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '18.469470' + - key: t + value: '-0.215682' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '5.639301' + - key: acc + value: '1.686702' + - key: jerk + value: '6.896215' +--- +header: + stamp: + sec: 1709009644 + nanosec: 704407151 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.154012' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.039584' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '19.048558' + - key: t + value: '-0.189305' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '5.704660' + - key: acc + value: '1.253791' + - key: jerk + value: '-4.334988' +--- +header: + stamp: + sec: 1709009644 + nanosec: 804415775 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.134210' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.035080' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '19.624477' + - key: t + value: '-0.166634' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '5.789560' + - key: acc + value: '1.094605' + - key: jerk + value: '-1.583055' +--- +header: + stamp: + sec: 1709009644 + nanosec: 904406820 + frame_id: '' +status: +- level: "\0" + name: 'autonomous_emergency_braking: aeb_emergency_stop' + message: '' + hardware_id: '' + values: + - key: decision + value: none +- level: "\0" + name: lateral_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.112861' +- level: "\0" + name: yaw_deviation + message: '' + hardware_id: '' + values: + - key: metric_value + value: '0.031182' +- level: "\0" + name: ego_lane_info + message: '' + hardware_id: '' + values: + - key: lane_id + value: '1500' + - key: s + value: '20.211304' + - key: t + value: '-0.142367' +- level: "\0" + name: kinematic_state + message: '' + hardware_id: '' + values: + - key: vel + value: '5.862113' + - key: acc + value: '0.953421' + - key: jerk + value: '-1.418752' diff --git a/sample/planning_control/scenario.ja.yaml b/sample/planning_control/scenario.ja.yaml index 787adeb9..c87e366c 100644 --- a/sample/planning_control/scenario.ja.yaml +++ b/sample/planning_control/scenario.ja.yaml @@ -1,14 +1,15 @@ -ScenarioFormatVersion: 2.2.0 +ScenarioFormatVersion: 3.0.0 ScenarioName: sample_planning_control ScenarioDescription: sample_planning_control -SensorModel: sample_sensor_kit -VehicleModel: sample_vehicle -VehicleId: default -LocalMapPath: $HOME/autoware_map/sample-map-planning -DataSetPath: /home/hyt/dlr_data/auto/t4_pc/xx1 +SensorModel: aip_xx1 +VehicleModel: lexus Evaluation: UseCaseName: planning_control UseCaseFormatVersion: 0.1.0 + Datasets: + - odaiba: + VehicleId: default + LaunchSensing: true Conditions: ControlConditions: - module: aeb From 3656ce6e614fbc5bc3fe49242747016a1bd90751 Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Wed, 17 Jul 2024 17:35:57 +0900 Subject: [PATCH 03/28] feat: update evaluation logic --- .../log_evaluator/planning_control.py | 136 ++++++++++++------ 1 file changed, 89 insertions(+), 47 deletions(-) diff --git a/log_evaluator/log_evaluator/planning_control.py b/log_evaluator/log_evaluator/planning_control.py index 30dc941d..4538a229 100644 --- a/log_evaluator/log_evaluator/planning_control.py +++ b/log_evaluator/log_evaluator/planning_control.py @@ -13,7 +13,6 @@ # limitations under the License. from dataclasses import dataclass -from dataclasses import field from sys import float_info from typing import Literal @@ -43,11 +42,11 @@ def validate_min_max(self) -> "MinMax": class LeftRight(BaseModel): - left: float = Field(float_info.max, gt=0.0) # + - right: float = Field(float_info.max, gt=0.0) # - + left: float = Field(float_info.max, gt=0.0) # + + right: float = Field(float_info.max, gt=0.0) # - - def match_condition(self, t: float): - if (-1)*self.right <= t <= self.left: + def match_condition(self, t: float) -> bool: + if (-1.0) * self.right <= t <= self.left: return True return False @@ -67,7 +66,7 @@ def is_started(self, lane_info: tuple) -> bool: return False return True - def is_finished(self, lane_info: tuple) -> bool: + def is_ended(self, lane_info: tuple) -> bool: lane_id, s, _ = lane_info if self.id != lane_id: return False @@ -77,11 +76,14 @@ def is_finished(self, lane_info: tuple) -> bool: class LaneCondition(BaseModel): - start: LaneInfo | None = None - end: LaneInfo | None = None + start: LaneInfo + end: LaneInfo + started: bool = False + ended: bool = False @classmethod def diag_lane_info(cls, lane_info: DiagnosticStatus) -> tuple[float, float, float]: + lane_id, s, t = None, None, None for kv in lane_info.values: kv: KeyValue if kv.key == "lane_id": @@ -92,22 +94,17 @@ def diag_lane_info(cls, lane_info: DiagnosticStatus) -> tuple[float, float, floa t = kv.value return (lane_id, s, t) - def match_condition(self, lane_info: DiagnosticStatus) -> bool: - diag_lane_info = LaneCondition.diag_lane_info(lane_info) + def is_started(self, lane_info_tuple: tuple) -> bool: + # 一度Trueになったら変更しない if not self.started: - self.started = self.start.is_started(diag_lane_info) - if not self.finished: - self.finished = self.end.is_finished(diag_lane_info) - if not self.finished: - self. + self.started = self.start.is_started(lane_info_tuple) + return self.started - def is_started(self, lane_info: DiagnosticStatus) -> bool: - self.start.is_started(lane_info) - - def is_finished(self, lane_info: DiagnosticStatus) -> bool: - if self.end is None: - return False - return self.end.is_finished(lane_info) + def is_ended(self, lane_info_tuple: tuple) -> bool: + # 一度Trueになったら変更しない + if not self.ended: + self.ended = self.end.is_ended(lane_info_tuple) + return self.ended class KinematicCondition(BaseModel): @@ -115,6 +112,29 @@ class KinematicCondition(BaseModel): acc: MinMax jerk: MinMax + @classmethod + def diag_kinematic_state(cls, kinematic_state: DiagnosticStatus) -> tuple[float, float, float]: + vel, acc, jerk = None, None, None + for kv in kinematic_state.values: + kv: KeyValue + if kv.key == "vel": + vel = kv.value + if kv.key == "acc": + acc = kv.value + if kv.key == "jerk": + jerk = kv.value + return (vel, acc, jerk) + + def match_condition(self, kinematic_state_tuple: tuple) -> bool: + vel, acc, jerk = kinematic_state_tuple + if not self.vel.min <= vel <= self.vel.max: + return False + if not self.acc.min <= acc <= self.acc.max: + return False + if not self.jerk.min <= jerk <= self.jerk.max: + return False + return True + class PlanningControlCondition(BaseModel): module: str @@ -141,35 +161,57 @@ class PlanningControlScenario(Scenario): @dataclass class Metrics(EvaluationItem): - is_under_evaluation: bool = False - - def set_frame(self, msg: DiagnosticArray) -> dict | None: + def __post_init__(self) -> None: self.condition: PlanningControlCondition - - for status in msg.status: + self.use_lane_condition = self.condition.lane_condition is not None + self.use_kinetic_condition = self.condition.kinematic_condition is not None + + def set_frame(self, msg: DiagnosticArray) -> dict | None: # noqa + if len(msg.status) == 0: + return None + + # key check + status0: DiagnosticStatus = msg.status[0] + if status0.name != self.condition.module: + return None + if status0.values[0].key != "decision": + return None + + # get additional condition + for _, status in enumerate(msg.status, 1): status: DiagnosticStatus - if status.name != self.condition.module: - continue - if status.values[0].key != "decision": - continue - if status.values[0].value != self.condition.decision: - continue - - self.total += 1 - - frame_success = "Fail" - if (self.condition.Value0Value == status.values[0].value) and ( - self.condition.DetailedConditions is None - or self.check_detailed_condition(status.values[1:]) - ): + if status.name == "ego_lane_info": + lane_info_tuple = LaneCondition.diag_lane_info(status) + if status.name == "kinematic_state": + kinetic_state_tuple = KinematicCondition.diag_kinematic_state(status) + + if self.use_lane_condition and not ( + self.condition.lane_condition.is_started(lane_info_tuple) + and not self.condition.lane_condition.is_ended(lane_info_tuple) + ): + return None + + self.total += 1 + frame_success = "Fail" + # decisionが一致している、且つkinetic_stateが条件を満たしていればOK + if self.condition.decision == status0.values[0].value: + if self.use_kinetic_condition: + if self.condition.kinematic_condition.match_condition(kinetic_state_tuple): + frame_success = "Success" + self.passed += 1 + else: frame_success = "Success" self.passed += 1 - self.success = self.passed >= required_successes - return { - "Result": {"Total": self.success_str(), "Frame": frame_success}, - "Info": {"TotalPassed": self.passed, "RequiredSuccess": required_successes}, - } - return None + # any_ofなら1個あればいい。all_ofは全部 + self.success = ( + self.passed > 0 + if self.condition.condition_type == "any_of" + else self.passed == self.total + ) + return { + "Result": {"Total": self.success_str(), "Frame": frame_success}, + "Info": {"TotalPassed": self.passed}, + } class MetricsClassContainer: From ba71358fbc81f3a0cbaff52eb74b20e78bda1056 Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Wed, 17 Jul 2024 17:59:47 +0900 Subject: [PATCH 04/28] fix: cast string --- .../log_evaluator/planning_control.py | 22 +++++++++---------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/log_evaluator/log_evaluator/planning_control.py b/log_evaluator/log_evaluator/planning_control.py index 4538a229..06eef0da 100644 --- a/log_evaluator/log_evaluator/planning_control.py +++ b/log_evaluator/log_evaluator/planning_control.py @@ -29,8 +29,8 @@ class MinMax(BaseModel): - min: float | None = float_info.min - max: float | None = float_info.max + min: float = float_info.min + max: float = float_info.max @model_validator(mode="after") def validate_min_max(self) -> "MinMax": @@ -87,20 +87,20 @@ def diag_lane_info(cls, lane_info: DiagnosticStatus) -> tuple[float, float, floa for kv in lane_info.values: kv: KeyValue if kv.key == "lane_id": - lane_id = kv.value + lane_id = int(kv.value) if kv.key == "s": - s = kv.value + s = float(kv.value) if kv.key == "t": - t = kv.value + t = float(kv.value) return (lane_id, s, t) - def is_started(self, lane_info_tuple: tuple) -> bool: + def is_started(self, lane_info_tuple: tuple[float, float, float]) -> bool: # 一度Trueになったら変更しない if not self.started: self.started = self.start.is_started(lane_info_tuple) return self.started - def is_ended(self, lane_info_tuple: tuple) -> bool: + def is_ended(self, lane_info_tuple: tuple[float, float, float]) -> bool: # 一度Trueになったら変更しない if not self.ended: self.ended = self.end.is_ended(lane_info_tuple) @@ -118,14 +118,14 @@ def diag_kinematic_state(cls, kinematic_state: DiagnosticStatus) -> tuple[float, for kv in kinematic_state.values: kv: KeyValue if kv.key == "vel": - vel = kv.value + vel = float(kv.value) if kv.key == "acc": - acc = kv.value + acc = float(kv.value) if kv.key == "jerk": - jerk = kv.value + jerk = float(kv.value) return (vel, acc, jerk) - def match_condition(self, kinematic_state_tuple: tuple) -> bool: + def match_condition(self, kinematic_state_tuple: tuple[float, float, float]) -> bool: vel, acc, jerk = kinematic_state_tuple if not self.vel.min <= vel <= self.vel.max: return False From 872c70b99f65b78a41fd0d617998075294da5132 Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Wed, 17 Jul 2024 18:32:39 +0900 Subject: [PATCH 05/28] fix: field --- log_evaluator/log_evaluator/planning_control.py | 1 + 1 file changed, 1 insertion(+) diff --git a/log_evaluator/log_evaluator/planning_control.py b/log_evaluator/log_evaluator/planning_control.py index 06eef0da..88910312 100644 --- a/log_evaluator/log_evaluator/planning_control.py +++ b/log_evaluator/log_evaluator/planning_control.py @@ -153,6 +153,7 @@ class Evaluation(BaseModel): UseCaseName: Literal["planning_control"] UseCaseFormatVersion: Literal["0.1.0"] Conditions: Conditions + Datasets: list[dict] class PlanningControlScenario(Scenario): From 14ea7ab69010ec48226fbf7a2e637a36dac09f51 Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Wed, 17 Jul 2024 19:48:52 +0900 Subject: [PATCH 06/28] feat: add unit test --- .../test/unittest/test_planning_control.py | 25 +++++++++++++++++++ sample/planning_control/scenario.yaml | 24 ++++++++++++++++++ 2 files changed, 49 insertions(+) create mode 100644 log_evaluator/test/unittest/test_planning_control.py create mode 100644 sample/planning_control/scenario.yaml diff --git a/log_evaluator/test/unittest/test_planning_control.py b/log_evaluator/test/unittest/test_planning_control.py new file mode 100644 index 00000000..df8987ab --- /dev/null +++ b/log_evaluator/test/unittest/test_planning_control.py @@ -0,0 +1,25 @@ +# Copyright (c) 2024 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 log_evaluator.planning_control import PlanningControlScenario +from log_evaluator.scenario import load_sample_scenario + + +def test_scenario() -> None: + scenario: PlanningControlScenario = load_sample_scenario( + "planning_control", + PlanningControlScenario, + ) + assert scenario.ScenarioName == "sample_planning_control" + assert scenario.Evaluation.Conditions.ControlConditions[0].condition_type == "all_of" diff --git a/sample/planning_control/scenario.yaml b/sample/planning_control/scenario.yaml new file mode 100644 index 00000000..c7f50c80 --- /dev/null +++ b/sample/planning_control/scenario.yaml @@ -0,0 +1,24 @@ +ScenarioFormatVersion: 3.0.0 +ScenarioName: sample_planning_control +ScenarioDescription: sample_planning_control +SensorModel: aip_xx1 +VehicleModel: lexus +Evaluation: + UseCaseName: planning_control + UseCaseFormatVersion: 0.1.0 + Datasets: + - odaiba: + VehicleId: default + LaunchSensing: true + Conditions: + ControlConditions: + - module: aeb + decision: deceleration + condition_type: all_of + lane_condition: + start: + id: 1500 + end: + id: 1500 + s: 2.5 + kinematic_condition: null From d20482c13efe88425ce81e6b5fd535c78bd91928 Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Thu, 18 Jul 2024 11:43:07 +0900 Subject: [PATCH 07/28] chore: add temporary logic --- log_evaluator/log_evaluator/planning_control.py | 16 +++++++++++++++- 1 file changed, 15 insertions(+), 1 deletion(-) diff --git a/log_evaluator/log_evaluator/planning_control.py b/log_evaluator/log_evaluator/planning_control.py index 88910312..1a41b1c8 100644 --- a/log_evaluator/log_evaluator/planning_control.py +++ b/log_evaluator/log_evaluator/planning_control.py @@ -171,9 +171,19 @@ def set_frame(self, msg: DiagnosticArray) -> dict | None: # noqa if len(msg.status) == 0: return None + # temporary + if len(msg.status) == 1: + # to avoid local variable 'lane_info_tuple' referenced before assignment + return None + # key check status0: DiagnosticStatus = msg.status[0] if status0.name != self.condition.module: + """ + return { + "Error": f"{status0.name=}, {self.condition.module=} module name is not matched", + } + """ return None if status0.values[0].key != "decision": return None @@ -211,7 +221,11 @@ def set_frame(self, msg: DiagnosticArray) -> dict | None: # noqa ) return { "Result": {"Total": self.success_str(), "Frame": frame_success}, - "Info": {"TotalPassed": self.passed}, + "Info": { + "TotalPassed": self.passed, + "LaneInfo": lane_info_tuple, + "KinematicState": kinetic_state_tuple, + }, } From df97d7903f5ac05b7ba40dd30b28ea6e19975bda Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Thu, 18 Jul 2024 12:20:51 +0900 Subject: [PATCH 08/28] fix: lane condition --- .../log_evaluator/planning_control.py | 24 +++++++++++++------ 1 file changed, 17 insertions(+), 7 deletions(-) diff --git a/log_evaluator/log_evaluator/planning_control.py b/log_evaluator/log_evaluator/planning_control.py index 1a41b1c8..ebedef94 100644 --- a/log_evaluator/log_evaluator/planning_control.py +++ b/log_evaluator/log_evaluator/planning_control.py @@ -60,7 +60,7 @@ def is_started(self, lane_info: tuple) -> bool: lane_id, s, t = lane_info if self.id != lane_id: return False - if self.s is not None and self.s > s: + if self.s is not None and self.s < s: return False if self.t is not None and not self.t.match_condition(t): return False @@ -70,7 +70,7 @@ def is_ended(self, lane_info: tuple) -> bool: lane_id, s, _ = lane_info if self.id != lane_id: return False - if self.s is not None and self.s < s: + if self.s is not None and self.s > s: return False return True @@ -196,11 +196,21 @@ def set_frame(self, msg: DiagnosticArray) -> dict | None: # noqa if status.name == "kinematic_state": kinetic_state_tuple = KinematicCondition.diag_kinematic_state(status) - if self.use_lane_condition and not ( - self.condition.lane_condition.is_started(lane_info_tuple) - and not self.condition.lane_condition.is_ended(lane_info_tuple) - ): - return None + if self.use_lane_condition: + started = self.condition.lane_condition.is_started(lane_info_tuple) + ended = self.condition.lane_condition.is_ended(lane_info_tuple) + if not (started and not ended): + """ + return { + "Error": { + "LaneInfo": lane_info_tuple, + "KinematicState": kinetic_state_tuple, + "started": started, + "ended": ended, + }, + } + """ + return None self.total += 1 frame_success = "Fail" From f65d46c7a2aec66eca5aa69652c459c4946c5658 Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Thu, 18 Jul 2024 12:41:10 +0900 Subject: [PATCH 09/28] fix: lane s condition --- .../log_evaluator/planning_control.py | 18 +++++------------- 1 file changed, 5 insertions(+), 13 deletions(-) diff --git a/log_evaluator/log_evaluator/planning_control.py b/log_evaluator/log_evaluator/planning_control.py index ebedef94..42120bca 100644 --- a/log_evaluator/log_evaluator/planning_control.py +++ b/log_evaluator/log_evaluator/planning_control.py @@ -56,21 +56,13 @@ class LaneInfo(BaseModel): s: float | None = None t: LeftRight | None = None - def is_started(self, lane_info: tuple) -> bool: + def match_condition(self, lane_info: tuple, *, start_condition: bool = False) -> bool: lane_id, s, t = lane_info if self.id != lane_id: return False - if self.s is not None and self.s < s: + if self.s is not None and self.s >= s: # 超えたら開始、または終了 return False - if self.t is not None and not self.t.match_condition(t): - return False - return True - - def is_ended(self, lane_info: tuple) -> bool: - lane_id, s, _ = lane_info - if self.id != lane_id: - return False - if self.s is not None and self.s > s: + if start_condition and self.t is not None and not self.t.match_condition(t): return False return True @@ -97,13 +89,13 @@ def diag_lane_info(cls, lane_info: DiagnosticStatus) -> tuple[float, float, floa def is_started(self, lane_info_tuple: tuple[float, float, float]) -> bool: # 一度Trueになったら変更しない if not self.started: - self.started = self.start.is_started(lane_info_tuple) + self.started = self.start.match_condition(lane_info_tuple, start_condition=True) return self.started def is_ended(self, lane_info_tuple: tuple[float, float, float]) -> bool: # 一度Trueになったら変更しない if not self.ended: - self.ended = self.end.is_ended(lane_info_tuple) + self.ended = self.end.match_condition(lane_info_tuple) return self.ended From 3cda13f023fd33d6a3c6754beaa6d1e399dc957b Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Thu, 18 Jul 2024 13:01:55 +0900 Subject: [PATCH 10/28] chore: allow empty KinematicCondition --- log_evaluator/log_evaluator/planning_control.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/log_evaluator/log_evaluator/planning_control.py b/log_evaluator/log_evaluator/planning_control.py index 42120bca..fb734a31 100644 --- a/log_evaluator/log_evaluator/planning_control.py +++ b/log_evaluator/log_evaluator/planning_control.py @@ -100,9 +100,9 @@ def is_ended(self, lane_info_tuple: tuple[float, float, float]) -> bool: class KinematicCondition(BaseModel): - vel: MinMax - acc: MinMax - jerk: MinMax + vel: MinMax | None = None + acc: MinMax | None = None + jerk: MinMax | None = None @classmethod def diag_kinematic_state(cls, kinematic_state: DiagnosticStatus) -> tuple[float, float, float]: @@ -119,11 +119,11 @@ def diag_kinematic_state(cls, kinematic_state: DiagnosticStatus) -> tuple[float, def match_condition(self, kinematic_state_tuple: tuple[float, float, float]) -> bool: vel, acc, jerk = kinematic_state_tuple - if not self.vel.min <= vel <= self.vel.max: + if self.vel is not None and not self.vel.min <= vel <= self.vel.max: return False - if not self.acc.min <= acc <= self.acc.max: + if self.acc is not None and not self.acc.min <= acc <= self.acc.max: return False - if not self.jerk.min <= jerk <= self.jerk.max: + if self.jerk is not None and not self.jerk.min <= jerk <= self.jerk.max: return False return True From 8de32ca52f73541a5552450cbb088cab5280d39d Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Thu, 18 Jul 2024 13:35:53 +0900 Subject: [PATCH 11/28] chore: add output decision --- log_evaluator/log_evaluator/planning_control.py | 1 + 1 file changed, 1 insertion(+) diff --git a/log_evaluator/log_evaluator/planning_control.py b/log_evaluator/log_evaluator/planning_control.py index fb734a31..b3352332 100644 --- a/log_evaluator/log_evaluator/planning_control.py +++ b/log_evaluator/log_evaluator/planning_control.py @@ -225,6 +225,7 @@ def set_frame(self, msg: DiagnosticArray) -> dict | None: # noqa "Result": {"Total": self.success_str(), "Frame": frame_success}, "Info": { "TotalPassed": self.passed, + "Decision": status0.values[0].value, "LaneInfo": lane_info_tuple, "KinematicState": kinetic_state_tuple, }, From 1d3aa67ff05acf93dfe3ee701589c53f1b17d3c6 Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Thu, 18 Jul 2024 13:41:17 +0900 Subject: [PATCH 12/28] chore: update sample --- sample/planning_control/result.json | 756 +++++++++++++++++++---- sample/planning_control/scenario.ja.yaml | 89 --- sample/planning_control/scenario.yaml | 22 +- 3 files changed, 638 insertions(+), 229 deletions(-) delete mode 100644 sample/planning_control/scenario.ja.yaml diff --git a/sample/planning_control/result.json b/sample/planning_control/result.json index 356d3f62..22d9e43f 100644 --- a/sample/planning_control/result.json +++ b/sample/planning_control/result.json @@ -1,50 +1,56 @@ [ { "Condition": { - "Hertz": 10, "ControlConditions": [ { - "TimeRange": { - "start": 1709009638.3, - "end": 1709009639.3 - }, - "Module": "autonomous_emergency_braking", - "Value0Key": "decision", - "Value0Value": "stop", - "DetailedConditions": null - }, - { - "TimeRange": { - "start": 1709009640, - "end": 1709009641 + "module": "autonomous_emergency_braking: aeb_emergency_stop", + "decision": "deceleration", + "condition_type": "all_of", + "lane_condition": { + "start": { + "id": 1500, + "s": null, + "t": null + }, + "end": { + "id": 1500, + "s": 2.3, + "t": null + }, + "started": false, + "ended": false }, - "Module": "autonomous_emergency_braking", - "Value0Key": "decision", - "Value0Value": "none", - "DetailedConditions": null + "kinematic_condition": { + "vel": { + "min": 2.5, + "max": 3 + }, + "acc": { + "min": -0.5, + "max": 0.5 + }, + "jerk": null + } }, { - "TimeRange": { - "start": 1709009640, - "end": 1709009641 - }, - "Module": "crosswalk", - "Value0Key": "decision", - "Value0Value": "slow_down", - "DetailedConditions": { - "pos_x": { - "lower": 1, - "upper": 2 + "module": "autonomous_emergency_braking: aeb_emergency_stop", + "decision": "none", + "condition_type": "all_of", + "lane_condition": { + "start": { + "id": 1500, + "s": 3, + "t": null }, - "pos_y": { - "lower": 3, - "upper": 4 + "end": { + "id": 1500, + "s": 10, + "t": null }, - "vel": { - "lower": 3, - "upper": 4 - } - } + "started": false, + "ended": false + }, + "kinematic_condition": null } ], "PlanningConditions": [] @@ -56,18 +62,18 @@ "Summary": "NoData" }, "Stamp": { - "System": 1717122177.6615398 + "System": 1721276989.222324 }, "Frame": {} }, { "Result": { "Success": false, - "Summary": "Control: Failed:condition0 (Success), condition1 (Fail), condition2 (Fail) Planning: Passed:NotTestTarget" + "Summary": "Control: Failed:control_0 (Success), control_1 (Fail) Planning: Passed:NotTestTarget" }, "Stamp": { - "System": 1717122206.1682308, - "ROS": 1717033424.612271 + "System": 1721277019.2600749, + "ROS": 1709009640.003256 }, "Frame": { "control_0": { @@ -77,7 +83,17 @@ }, "Info": { "TotalPassed": 1, - "RequiredSuccess": 0 + "Decision": "deceleration", + "LaneInfo": [ + 1500, + 0.254821, + -0.983676 + ], + "KinematicState": [ + 2.780202, + -0.322109, + 0.299525 + ] } } } @@ -85,11 +101,11 @@ { "Result": { "Success": false, - "Summary": "Control: Failed:condition0 (Success), condition1 (Fail), condition2 (Fail) Planning: Passed:NotTestTarget" + "Summary": "Control: Failed:control_0 (Success), control_1 (Fail) Planning: Passed:NotTestTarget" }, "Stamp": { - "System": 1717122206.2692165, - "ROS": 1717033424.7122746 + "System": 1721277019.3607328, + "ROS": 1709009640.1032677 }, "Frame": { "control_0": { @@ -99,7 +115,17 @@ }, "Info": { "TotalPassed": 2, - "RequiredSuccess": 1 + "Decision": "deceleration", + "LaneInfo": [ + 1500, + 0.524374, + -1.038678 + ], + "KinematicState": [ + 2.77897, + -0.193682, + 1.284198 + ] } } } @@ -107,11 +133,11 @@ { "Result": { "Success": false, - "Summary": "Control: Failed:condition0 (Success), condition1 (Fail), condition2 (Fail) Planning: Passed:NotTestTarget" + "Summary": "Control: Failed:control_0 (Success), control_1 (Fail) Planning: Passed:NotTestTarget" }, "Stamp": { - "System": 1717122206.3680265, - "ROS": 1717033424.81225 + "System": 1721277019.4600265, + "ROS": 1709009640.2032669 }, "Frame": { "control_0": { @@ -121,7 +147,17 @@ }, "Info": { "TotalPassed": 3, - "RequiredSuccess": 2 + "Decision": "deceleration", + "LaneInfo": [ + 1500, + 0.797716, + -1.089461 + ], + "KinematicState": [ + 2.766703, + -0.157067, + 0.374411 + ] } } } @@ -129,11 +165,11 @@ { "Result": { "Success": false, - "Summary": "Control: Failed:condition0 (Success), condition1 (Fail), condition2 (Fail) Planning: Passed:NotTestTarget" + "Summary": "Control: Failed:control_0 (Success), control_1 (Fail) Planning: Passed:NotTestTarget" }, "Stamp": { - "System": 1717122206.4701612, - "ROS": 1717033424.912282 + "System": 1721277019.560831, + "ROS": 1709009640.3032598 }, "Frame": { "control_0": { @@ -143,7 +179,17 @@ }, "Info": { "TotalPassed": 4, - "RequiredSuccess": 2 + "Decision": "deceleration", + "LaneInfo": [ + 1500, + 1.07291, + -1.137064 + ], + "KinematicState": [ + 2.774931, + -0.06495, + 0.919988 + ] } } } @@ -151,11 +197,11 @@ { "Result": { "Success": false, - "Summary": "Control: Failed:condition0 (Success), condition1 (Fail), condition2 (Fail) Planning: Passed:NotTestTarget" + "Summary": "Control: Failed:control_0 (Success), control_1 (Fail) Planning: Passed:NotTestTarget" }, "Stamp": { - "System": 1717122206.5757322, - "ROS": 1717033425.017296 + "System": 1721277019.6612196, + "ROS": 1709009640.403535 }, "Frame": { "control_0": { @@ -165,7 +211,17 @@ }, "Info": { "TotalPassed": 5, - "RequiredSuccess": 3 + "Decision": "deceleration", + "LaneInfo": [ + 1500, + 1.345795, + -1.181963 + ], + "KinematicState": [ + 2.785044, + 0.000635, + 0.654367 + ] } } } @@ -173,11 +229,11 @@ { "Result": { "Success": false, - "Summary": "Control: Failed:condition0 (Success), condition1 (Fail), condition2 (Fail) Planning: Passed:NotTestTarget" + "Summary": "Control: Failed:control_0 (Success), control_1 (Fail) Planning: Passed:NotTestTarget" }, "Stamp": { - "System": 1717122206.6726487, - "ROS": 1717033425.107275 + "System": 1721277019.7615428, + "ROS": 1709009640.5032952 }, "Frame": { "control_0": { @@ -187,7 +243,17 @@ }, "Info": { "TotalPassed": 6, - "RequiredSuccess": 4 + "Decision": "deceleration", + "LaneInfo": [ + 1500, + 1.619427, + -1.222165 + ], + "KinematicState": [ + 2.806327, + 0.093698, + 0.929944 + ] } } } @@ -195,11 +261,11 @@ { "Result": { "Success": false, - "Summary": "Control: Failed:condition0 (Success), condition1 (Fail), condition2 (Fail) Planning: Passed:NotTestTarget" + "Summary": "Control: Failed:control_0 (Success), control_1 (Fail) Planning: Passed:NotTestTarget" }, "Stamp": { - "System": 1717122206.8685193, - "ROS": 1717033425.3122783 + "System": 1721277019.8604515, + "ROS": 1709009640.6032755 }, "Frame": { "control_0": { @@ -209,7 +275,17 @@ }, "Info": { "TotalPassed": 7, - "RequiredSuccess": 6 + "Decision": "deceleration", + "LaneInfo": [ + 1500, + 1.899189, + -1.257947 + ], + "KinematicState": [ + 2.826436, + 0.134591, + 0.411654 + ] } } } @@ -217,11 +293,11 @@ { "Result": { "Success": false, - "Summary": "Control: Failed:condition0 (Success), condition1 (Fail), condition2 (Fail) Planning: Passed:NotTestTarget" + "Summary": "Control: Failed:control_0 (Success), control_1 (Fail) Planning: Passed:NotTestTarget" }, "Stamp": { - "System": 1717122206.9683797, - "ROS": 1717033425.4123263 + "System": 1721277019.9600542, + "ROS": 1709009640.7032664 }, "Frame": { "control_0": { @@ -231,41 +307,317 @@ }, "Info": { "TotalPassed": 8, - "RequiredSuccess": 7 + "Decision": "deceleration", + "LaneInfo": [ + 1500, + 2.180388, + -1.287927 + ], + "KinematicState": [ + 2.855254, + 0.206083, + 0.706992 + ] } } } }, { "Result": { - "Success": false, - "Summary": "Control: Failed:condition0 (Success), condition1 (Fail), condition2 (Fail) Planning: Passed:NotTestTarget" + "Success": true, + "Summary": "Control: Passed:control_0 (Success), control_1 (Success) Planning: Passed:NotTestTarget" }, "Stamp": { - "System": 1717122207.0700681, - "ROS": 1717033425.512249 + "System": 1721277020.2599468, + "ROS": 1709009641.0032742 }, "Frame": { - "control_0": { + "control_1": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 1, + "Decision": "none", + "LaneInfo": [ + 1500, + 3.048498, + -1.357804 + ], + "KinematicState": [ + 2.973334, + 0.388577, + 0.757059 + ] + } + } + } + }, + { + "Result": { + "Success": true, + "Summary": "Control: Passed:control_0 (Success), control_1 (Success) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1721277020.3603773, + "ROS": 1709009641.1032643 + }, + "Frame": { + "control_1": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 2, + "Decision": "none", + "LaneInfo": [ + 1500, + 3.348355, + -1.371031 + ], + "KinematicState": [ + 3.031645, + 0.492628, + 1.050884 + ] + } + } + } + }, + { + "Result": { + "Success": true, + "Summary": "Control: Passed:control_0 (Success), control_1 (Success) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1721277020.4598317, + "ROS": 1709009641.203264 + }, + "Frame": { + "control_1": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 3, + "Decision": "none", + "LaneInfo": [ + 1500, + 3.654895, + -1.378377 + ], + "KinematicState": [ + 3.088592, + 0.52498, + 0.322604 + ] + } + } + } + }, + { + "Result": { + "Success": true, + "Summary": "Control: Passed:control_0 (Success), control_1 (Success) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1721277020.5599344, + "ROS": 1709009641.3032653 + }, + "Frame": { + "control_1": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 4, + "Decision": "none", + "LaneInfo": [ + 1500, + 3.967671, + -1.380667 + ], + "KinematicState": [ + 3.152821, + 0.58422, + 0.590881 + ] + } + } + } + }, + { + "Result": { + "Success": true, + "Summary": "Control: Passed:control_0 (Success), control_1 (Success) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1721277020.6612742, + "ROS": 1709009641.4032772 + }, + "Frame": { + "control_1": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 5, + "Decision": "none", + "LaneInfo": [ + 1500, + 4.286699, + -1.37869 + ], + "KinematicState": [ + 3.220785, + 0.65566, + 0.710801 + ] + } + } + } + }, + { + "Result": { + "Success": true, + "Summary": "Control: Passed:control_0 (Success), control_1 (Success) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1721277020.7622206, + "ROS": 1709009641.5033162 + }, + "Frame": { + "control_1": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 6, + "Decision": "none", + "LaneInfo": [ + 1500, + 4.614102, + -1.371985 + ], + "KinematicState": [ + 3.287503, + 0.687749, + 0.320499 + ] + } + } + } + }, + { + "Result": { + "Success": true, + "Summary": "Control: Passed:control_0 (Success), control_1 (Success) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1721277020.8598855, + "ROS": 1709009641.603265 + }, + "Frame": { + "control_1": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 7, + "Decision": "none", + "LaneInfo": [ + 1500, + 4.954561, + -1.359024 + ], + "KinematicState": [ + 3.346353, + 0.642912, + -0.443885 + ] + } + } + } + }, + { + "Result": { + "Success": true, + "Summary": "Control: Passed:control_0 (Success), control_1 (Success) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1721277020.9627604, + "ROS": 1709009641.7032757 + }, + "Frame": { + "control_1": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 8, + "Decision": "none", + "LaneInfo": [ + 1500, + 5.289516, + -1.341692 + ], + "KinematicState": [ + 3.4079, + 0.626983, + -0.162374 + ] + } + } + } + }, + { + "Result": { + "Success": true, + "Summary": "Control: Passed:control_0 (Success), control_1 (Success) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1721277021.060883, + "ROS": 1709009641.8032632 + }, + "Frame": { + "control_1": { "Result": { "Total": "Success", "Frame": "Success" }, "Info": { "TotalPassed": 9, - "RequiredSuccess": 8 + "Decision": "none", + "LaneInfo": [ + 1500, + 5.636661, + -1.319875 + ], + "KinematicState": [ + 3.47503, + 0.605346, + -0.217098 + ] } } } }, { "Result": { - "Success": false, - "Summary": "Control: Failed:condition0 (Success), condition1 (Success), condition2 (Fail) Planning: Passed:NotTestTarget" + "Success": true, + "Summary": "Control: Passed:control_0 (Success), control_1 (Success) Planning: Passed:NotTestTarget" }, "Stamp": { - "System": 1717122207.868164, - "ROS": 1717033426.312265 + "System": 1721277021.1596808, + "ROS": 1709009641.9032614 }, "Frame": { "control_1": { @@ -274,20 +626,30 @@ "Frame": "Success" }, "Info": { - "TotalPassed": 1, - "RequiredSuccess": 0 + "TotalPassed": 10, + "Decision": "none", + "LaneInfo": [ + 1500, + 5.98997, + -1.294059 + ], + "KinematicState": [ + 3.537443, + 0.65008, + 0.445461 + ] } } } }, { "Result": { - "Success": false, - "Summary": "Control: Failed:condition0 (Success), condition1 (Success), condition2 (Fail) Planning: Passed:NotTestTarget" + "Success": true, + "Summary": "Control: Passed:control_0 (Success), control_1 (Success) Planning: Passed:NotTestTarget" }, "Stamp": { - "System": 1717122207.9685762, - "ROS": 1717033426.4122493 + "System": 1721277021.2599158, + "ROS": 1709009642.0032642 }, "Frame": { "control_1": { @@ -296,20 +658,30 @@ "Frame": "Success" }, "Info": { - "TotalPassed": 2, - "RequiredSuccess": 1 + "TotalPassed": 11, + "Decision": "none", + "LaneInfo": [ + 1500, + 6.348585, + -1.265829 + ], + "KinematicState": [ + 3.609332, + 0.664397, + 0.140656 + ] } } } }, { "Result": { - "Success": false, - "Summary": "Control: Failed:condition0 (Success), condition1 (Success), condition2 (Fail) Planning: Passed:NotTestTarget" + "Success": true, + "Summary": "Control: Passed:control_0 (Success), control_1 (Success) Planning: Passed:NotTestTarget" }, "Stamp": { - "System": 1717122208.0686288, - "ROS": 1717033426.5122614 + "System": 1721277021.3598413, + "ROS": 1709009642.1032693 }, "Frame": { "control_1": { @@ -318,20 +690,30 @@ "Frame": "Success" }, "Info": { - "TotalPassed": 3, - "RequiredSuccess": 1 + "TotalPassed": 12, + "Decision": "none", + "LaneInfo": [ + 1500, + 6.715403, + -1.232613 + ], + "KinematicState": [ + 3.693096, + 0.754094, + 0.908683 + ] } } } }, { "Result": { - "Success": false, - "Summary": "Control: Failed:condition0 (Success), condition1 (Success), condition2 (Fail) Planning: Passed:NotTestTarget" + "Success": true, + "Summary": "Control: Passed:control_0 (Success), control_1 (Success) Planning: Passed:NotTestTarget" }, "Stamp": { - "System": 1717122208.1686108, - "ROS": 1717033426.6122468 + "System": 1721277021.4612176, + "ROS": 1709009642.2032835 }, "Frame": { "control_1": { @@ -340,20 +722,30 @@ "Frame": "Success" }, "Info": { - "TotalPassed": 4, - "RequiredSuccess": 2 + "TotalPassed": 13, + "Decision": "none", + "LaneInfo": [ + 1500, + 7.089984, + -1.197086 + ], + "KinematicState": [ + 3.774627, + 0.811998, + 0.580573 + ] } } } }, { "Result": { - "Success": false, - "Summary": "Control: Failed:condition0 (Success), condition1 (Success), condition2 (Fail) Planning: Passed:NotTestTarget" + "Success": true, + "Summary": "Control: Passed:control_0 (Success), control_1 (Success) Planning: Passed:NotTestTarget" }, "Stamp": { - "System": 1717122208.2720394, - "ROS": 1717033426.7122464 + "System": 1721277021.5604, + "ROS": 1709009642.3032677 }, "Frame": { "control_1": { @@ -362,20 +754,30 @@ "Frame": "Success" }, "Info": { - "TotalPassed": 5, - "RequiredSuccess": 3 + "TotalPassed": 14, + "Decision": "none", + "LaneInfo": [ + 1500, + 7.473814, + -1.158361 + ], + "KinematicState": [ + 3.848118, + 0.791756, + -0.201294 + ] } } } }, { "Result": { - "Success": false, - "Summary": "Control: Failed:condition0 (Success), condition1 (Success), condition2 (Fail) Planning: Passed:NotTestTarget" + "Success": true, + "Summary": "Control: Passed:control_0 (Success), control_1 (Success) Planning: Passed:NotTestTarget" }, "Stamp": { - "System": 1717122208.3684468, - "ROS": 1717033426.8123136 + "System": 1721277021.6613028, + "ROS": 1709009642.4032865 }, "Frame": { "control_1": { @@ -384,20 +786,30 @@ "Frame": "Success" }, "Info": { - "TotalPassed": 6, - "RequiredSuccess": 4 + "TotalPassed": 15, + "Decision": "none", + "LaneInfo": [ + 1500, + 7.863955, + -1.116921 + ], + "KinematicState": [ + 3.930269, + 0.825974, + 0.344808 + ] } } } }, { "Result": { - "Success": false, - "Summary": "Control: Failed:condition0 (Success), condition1 (Success), condition2 (Fail) Planning: Passed:NotTestTarget" + "Success": true, + "Summary": "Control: Passed:control_0 (Success), control_1 (Success) Planning: Passed:NotTestTarget" }, "Stamp": { - "System": 1717122208.4684315, - "ROS": 1717033426.9122937 + "System": 1721277021.7604876, + "ROS": 1709009642.5035427 }, "Frame": { "control_1": { @@ -406,20 +818,30 @@ "Frame": "Success" }, "Info": { - "TotalPassed": 7, - "RequiredSuccess": 5 + "TotalPassed": 16, + "Decision": "none", + "LaneInfo": [ + 1500, + 8.264956, + -1.076771 + ], + "KinematicState": [ + 4.006945, + 0.811871, + -0.140155 + ] } } } }, { "Result": { - "Success": false, - "Summary": "Control: Failed:condition0 (Success), condition1 (Success), condition2 (Fail) Planning: Passed:NotTestTarget" + "Success": true, + "Summary": "Control: Passed:control_0 (Success), control_1 (Success) Planning: Passed:NotTestTarget" }, "Stamp": { - "System": 1717122208.5685694, - "ROS": 1717033427.0122683 + "System": 1721277021.8623214, + "ROS": 1709009642.6032639 }, "Frame": { "control_1": { @@ -428,20 +850,30 @@ "Frame": "Success" }, "Info": { - "TotalPassed": 8, - "RequiredSuccess": 6 + "TotalPassed": 17, + "Decision": "none", + "LaneInfo": [ + 1500, + 8.687818, + -1.034342 + ], + "KinematicState": [ + 4.083466, + 0.78916, + -0.220425 + ] } } } }, { "Result": { - "Success": false, - "Summary": "Control: Failed:condition0 (Success), condition1 (Success), condition2 (Fail) Planning: Passed:NotTestTarget" + "Success": true, + "Summary": "Control: Passed:control_0 (Success), control_1 (Success) Planning: Passed:NotTestTarget" }, "Stamp": { - "System": 1717122208.668613, - "ROS": 1717033427.1122494 + "System": 1721277021.9597435, + "ROS": 1709009642.7032695 }, "Frame": { "control_1": { @@ -450,20 +882,30 @@ "Frame": "Success" }, "Info": { - "TotalPassed": 9, - "RequiredSuccess": 7 + "TotalPassed": 18, + "Decision": "none", + "LaneInfo": [ + 1500, + 9.086423, + -0.993832 + ], + "KinematicState": [ + 4.153996, + 0.769382, + -0.205345 + ] } } } }, { "Result": { - "Success": false, - "Summary": "Control: Failed:condition0 (Success), condition1 (Success), condition2 (Fail) Planning: Passed:NotTestTarget" + "Success": true, + "Summary": "Control: Passed:control_0 (Success), control_1 (Success) Planning: Passed:NotTestTarget" }, "Stamp": { - "System": 1717122208.768232, - "ROS": 1717033427.2122433 + "System": 1721277022.0604632, + "ROS": 1709009642.8032649 }, "Frame": { "control_1": { @@ -472,8 +914,50 @@ "Frame": "Success" }, "Info": { - "TotalPassed": 10, - "RequiredSuccess": 8 + "TotalPassed": 19, + "Decision": "none", + "LaneInfo": [ + 1500, + 9.505482, + -0.951828 + ], + "KinematicState": [ + 4.233492, + 0.802354, + 0.328948 + ] + } + } + } + }, + { + "Result": { + "Success": true, + "Summary": "Control: Passed:control_0 (Success), control_1 (Success) Planning: Passed:NotTestTarget" + }, + "Stamp": { + "System": 1721277022.159759, + "ROS": 1709009642.9032645 + }, + "Frame": { + "control_1": { + "Result": { + "Total": "Success", + "Frame": "Success" + }, + "Info": { + "TotalPassed": 20, + "Decision": "none", + "LaneInfo": [ + 1500, + 9.943206, + -0.906019 + ], + "KinematicState": [ + 4.281736, + 0.657596, + -1.443561 + ] } } } diff --git a/sample/planning_control/scenario.ja.yaml b/sample/planning_control/scenario.ja.yaml deleted file mode 100644 index c87e366c..00000000 --- a/sample/planning_control/scenario.ja.yaml +++ /dev/null @@ -1,89 +0,0 @@ -ScenarioFormatVersion: 3.0.0 -ScenarioName: sample_planning_control -ScenarioDescription: sample_planning_control -SensorModel: aip_xx1 -VehicleModel: lexus -Evaluation: - UseCaseName: planning_control - UseCaseFormatVersion: 0.1.0 - Datasets: - - odaiba: - VehicleId: default - LaunchSensing: true - Conditions: - ControlConditions: - - module: aeb - decision: deceleration # module の KeyValueのkeyをkeyにvalueをvalueに指定。今後追加でdecision以外が評価したいとなったらkey-valueが追加して対応する - condition_type: any_of # start-endのいずれかの区間で満たせばよい。 - lane_info: - start: - id: 100 - s: 1.0 - t: {left: 0.0, right: 0.0} - end: - id: 101 - s: 3.0 - t: {left: 3.0, right: 3.0} - kinematic_state: null # optional. 何も指定しないと減速しているかをdriving log replayer側で判定。指定する場合はそれの制約内かを判定。 - # 一定速度まで減速する必要がある場合。一つのモジュールで複数の範囲で指定可能 - - module: aeb - decision: deceleration - condition_type: any_of - lane_info: - start: - id: 200 - s: 5.0 - t: {left: 0.0, right: 0.0} - end: - id: 201 - s: 10.0 - t: {left: 0.0, right: 0.0} - kinematic_state: - vel: {min: 0.0, max: 1.0} - # planningもcontrolとまとめる? - # crosswalkの場合は停止計画なので速度を指定する - - module: crosswalk - decision: deceleration - condition_type: any_of - lane_info: - start: - id: 100 - s: 1.0 - t: {left: 0.0, right: 0.0} - end: - id: 101 - s: 3.0 - t: {left: 3.0, right: 3.0} - kinematic_state: - vel: {min: 0.0, max: 0.1} - - module: crosswalk - decision: deceleration - condition_type: any_of - lane_info: - start: - id: 200 - s: 5.0 - t: {left: 0.0, right: 0.0} - end: - id: 201 - s: 10.0 - t: {left: 0.0, right: 0.0} - kinematic_state: - vel: {min: 0.0, vel: 0.1} - # slowdownの例 指定区間全てで減速している必要がある - - module: obstacle_cruise_planner - decision: deceleration - condition_type: all_of # start-endの全ての区間で満たす - lane_info: - start: - id: 100 - s: 1.0 - t: {left: 0.0, right: 0.0} - end: - id: 101 - s: 3.0 - t: {left: 3.0, right: 3.0} - kinematic_state: - vel: {min: 1.0, max: 5.0} - acc: {min: -1.0, max: 0.0} - jerk: {min: -0.5} diff --git a/sample/planning_control/scenario.yaml b/sample/planning_control/scenario.yaml index c7f50c80..6a0a8fd8 100644 --- a/sample/planning_control/scenario.yaml +++ b/sample/planning_control/scenario.yaml @@ -12,13 +12,27 @@ Evaluation: LaunchSensing: true Conditions: ControlConditions: - - module: aeb - decision: deceleration + - module: "autonomous_emergency_braking: aeb_emergency_stop" + decision: deceleration # module の KeyValueのkeyをkeyにvalueをvalueに指定。今後decision以外が評価したいとなったらkey-valueが追加して対応する condition_type: all_of lane_condition: start: id: 1500 end: id: 1500 - s: 2.5 - kinematic_condition: null + s: 2.3 + kinematic_condition: + vel: {min: 2.5, max: 3.0} + acc: {min: -0.5, max: 0.5} + jerk: {min: 0.2, max: 1.5} + - module: "autonomous_emergency_braking: aeb_emergency_stop" + decision: none + condition_type: all_of + lane_condition: # optional + start: + id: 1500 + s: 3.0 + end: + id: 1500 + s: 10.0 + kinematic_condition: null # optional From 686177b5fd86d90443bfd872476bd0cd34f76512 Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Thu, 18 Jul 2024 13:43:57 +0900 Subject: [PATCH 13/28] chore: pre-commit --- docs/use_case/planning_control.en.md | 18 +- sample/planning_control/result.json | 336 +++++--------------------- sample/planning_control/scenario.yaml | 6 +- 3 files changed, 68 insertions(+), 292 deletions(-) diff --git a/docs/use_case/planning_control.en.md b/docs/use_case/planning_control.en.md index 1c84acfd..b6ab22f4 100644 --- a/docs/use_case/planning_control.en.md +++ b/docs/use_case/planning_control.en.md @@ -49,9 +49,9 @@ When the normal condition is not met Subscribed topics: -| Topic name | Data type | -| ----------------------------------------- | ------------------------------------- | -| /diagnostic/control_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | +| Topic name | Data type | +| ------------------------------------------- | ------------------------------------- | +| /diagnostic/control_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | | /diagnostic/planning_evaluator/metrics (仮) | diagnostic_msgs::msg::DiagnosticArray | Published topics: @@ -73,7 +73,7 @@ State the information required to run the simulation. ### Topic to be included in the input rosbag -| Topic name | Data type | +| Topic name | Data type | | -------------------------------------- | -------------------------------------------- | | /gsm8/from_can_bus | can_msgs/msg/Frame | | /localization/kinematic_state | nav_msgs/msg/Odometry | @@ -84,7 +84,7 @@ State the information required to run the simulation. The vehicle topics can be included instead of CAN. -| Topic name | Data type | +| Topic name | Data type | | -------------------------------------- | --------------------------------------------------- | | /localization/kinematic_state | nav_msgs/msg/Odometry | | /localization/acceleration | geometry_msgs/msg/AccelWithCovarianceStamped | @@ -99,10 +99,10 @@ The vehicle topics can be included instead of CAN. ### Topics that must not be included in the input rosbag -| Topic name | Data type | -| -------------------------------------- | ------------------------------------------------- -| -------- | ----------------------- | -| /clock | rosgraph_msgs/msg/Clock | +| Topic name | Data type | +| ---------- | ----------------------- | +| -------- | ----------------------- | +| /clock | rosgraph_msgs/msg/Clock | The clock is output by the --clock option of ros2 bag play, so if it is recorded in the bag itself, it is output twice, so it is not included in the bag. diff --git a/sample/planning_control/result.json b/sample/planning_control/result.json index 22d9e43f..22987d57 100644 --- a/sample/planning_control/result.json +++ b/sample/planning_control/result.json @@ -84,16 +84,8 @@ "Info": { "TotalPassed": 1, "Decision": "deceleration", - "LaneInfo": [ - 1500, - 0.254821, - -0.983676 - ], - "KinematicState": [ - 2.780202, - -0.322109, - 0.299525 - ] + "LaneInfo": [1500, 0.254821, -0.983676], + "KinematicState": [2.780202, -0.322109, 0.299525] } } } @@ -116,16 +108,8 @@ "Info": { "TotalPassed": 2, "Decision": "deceleration", - "LaneInfo": [ - 1500, - 0.524374, - -1.038678 - ], - "KinematicState": [ - 2.77897, - -0.193682, - 1.284198 - ] + "LaneInfo": [1500, 0.524374, -1.038678], + "KinematicState": [2.77897, -0.193682, 1.284198] } } } @@ -148,16 +132,8 @@ "Info": { "TotalPassed": 3, "Decision": "deceleration", - "LaneInfo": [ - 1500, - 0.797716, - -1.089461 - ], - "KinematicState": [ - 2.766703, - -0.157067, - 0.374411 - ] + "LaneInfo": [1500, 0.797716, -1.089461], + "KinematicState": [2.766703, -0.157067, 0.374411] } } } @@ -180,16 +156,8 @@ "Info": { "TotalPassed": 4, "Decision": "deceleration", - "LaneInfo": [ - 1500, - 1.07291, - -1.137064 - ], - "KinematicState": [ - 2.774931, - -0.06495, - 0.919988 - ] + "LaneInfo": [1500, 1.07291, -1.137064], + "KinematicState": [2.774931, -0.06495, 0.919988] } } } @@ -212,16 +180,8 @@ "Info": { "TotalPassed": 5, "Decision": "deceleration", - "LaneInfo": [ - 1500, - 1.345795, - -1.181963 - ], - "KinematicState": [ - 2.785044, - 0.000635, - 0.654367 - ] + "LaneInfo": [1500, 1.345795, -1.181963], + "KinematicState": [2.785044, 0.000635, 0.654367] } } } @@ -244,16 +204,8 @@ "Info": { "TotalPassed": 6, "Decision": "deceleration", - "LaneInfo": [ - 1500, - 1.619427, - -1.222165 - ], - "KinematicState": [ - 2.806327, - 0.093698, - 0.929944 - ] + "LaneInfo": [1500, 1.619427, -1.222165], + "KinematicState": [2.806327, 0.093698, 0.929944] } } } @@ -276,16 +228,8 @@ "Info": { "TotalPassed": 7, "Decision": "deceleration", - "LaneInfo": [ - 1500, - 1.899189, - -1.257947 - ], - "KinematicState": [ - 2.826436, - 0.134591, - 0.411654 - ] + "LaneInfo": [1500, 1.899189, -1.257947], + "KinematicState": [2.826436, 0.134591, 0.411654] } } } @@ -308,16 +252,8 @@ "Info": { "TotalPassed": 8, "Decision": "deceleration", - "LaneInfo": [ - 1500, - 2.180388, - -1.287927 - ], - "KinematicState": [ - 2.855254, - 0.206083, - 0.706992 - ] + "LaneInfo": [1500, 2.180388, -1.287927], + "KinematicState": [2.855254, 0.206083, 0.706992] } } } @@ -340,16 +276,8 @@ "Info": { "TotalPassed": 1, "Decision": "none", - "LaneInfo": [ - 1500, - 3.048498, - -1.357804 - ], - "KinematicState": [ - 2.973334, - 0.388577, - 0.757059 - ] + "LaneInfo": [1500, 3.048498, -1.357804], + "KinematicState": [2.973334, 0.388577, 0.757059] } } } @@ -372,16 +300,8 @@ "Info": { "TotalPassed": 2, "Decision": "none", - "LaneInfo": [ - 1500, - 3.348355, - -1.371031 - ], - "KinematicState": [ - 3.031645, - 0.492628, - 1.050884 - ] + "LaneInfo": [1500, 3.348355, -1.371031], + "KinematicState": [3.031645, 0.492628, 1.050884] } } } @@ -404,16 +324,8 @@ "Info": { "TotalPassed": 3, "Decision": "none", - "LaneInfo": [ - 1500, - 3.654895, - -1.378377 - ], - "KinematicState": [ - 3.088592, - 0.52498, - 0.322604 - ] + "LaneInfo": [1500, 3.654895, -1.378377], + "KinematicState": [3.088592, 0.52498, 0.322604] } } } @@ -436,16 +348,8 @@ "Info": { "TotalPassed": 4, "Decision": "none", - "LaneInfo": [ - 1500, - 3.967671, - -1.380667 - ], - "KinematicState": [ - 3.152821, - 0.58422, - 0.590881 - ] + "LaneInfo": [1500, 3.967671, -1.380667], + "KinematicState": [3.152821, 0.58422, 0.590881] } } } @@ -468,16 +372,8 @@ "Info": { "TotalPassed": 5, "Decision": "none", - "LaneInfo": [ - 1500, - 4.286699, - -1.37869 - ], - "KinematicState": [ - 3.220785, - 0.65566, - 0.710801 - ] + "LaneInfo": [1500, 4.286699, -1.37869], + "KinematicState": [3.220785, 0.65566, 0.710801] } } } @@ -500,16 +396,8 @@ "Info": { "TotalPassed": 6, "Decision": "none", - "LaneInfo": [ - 1500, - 4.614102, - -1.371985 - ], - "KinematicState": [ - 3.287503, - 0.687749, - 0.320499 - ] + "LaneInfo": [1500, 4.614102, -1.371985], + "KinematicState": [3.287503, 0.687749, 0.320499] } } } @@ -532,16 +420,8 @@ "Info": { "TotalPassed": 7, "Decision": "none", - "LaneInfo": [ - 1500, - 4.954561, - -1.359024 - ], - "KinematicState": [ - 3.346353, - 0.642912, - -0.443885 - ] + "LaneInfo": [1500, 4.954561, -1.359024], + "KinematicState": [3.346353, 0.642912, -0.443885] } } } @@ -564,16 +444,8 @@ "Info": { "TotalPassed": 8, "Decision": "none", - "LaneInfo": [ - 1500, - 5.289516, - -1.341692 - ], - "KinematicState": [ - 3.4079, - 0.626983, - -0.162374 - ] + "LaneInfo": [1500, 5.289516, -1.341692], + "KinematicState": [3.4079, 0.626983, -0.162374] } } } @@ -596,16 +468,8 @@ "Info": { "TotalPassed": 9, "Decision": "none", - "LaneInfo": [ - 1500, - 5.636661, - -1.319875 - ], - "KinematicState": [ - 3.47503, - 0.605346, - -0.217098 - ] + "LaneInfo": [1500, 5.636661, -1.319875], + "KinematicState": [3.47503, 0.605346, -0.217098] } } } @@ -628,16 +492,8 @@ "Info": { "TotalPassed": 10, "Decision": "none", - "LaneInfo": [ - 1500, - 5.98997, - -1.294059 - ], - "KinematicState": [ - 3.537443, - 0.65008, - 0.445461 - ] + "LaneInfo": [1500, 5.98997, -1.294059], + "KinematicState": [3.537443, 0.65008, 0.445461] } } } @@ -660,16 +516,8 @@ "Info": { "TotalPassed": 11, "Decision": "none", - "LaneInfo": [ - 1500, - 6.348585, - -1.265829 - ], - "KinematicState": [ - 3.609332, - 0.664397, - 0.140656 - ] + "LaneInfo": [1500, 6.348585, -1.265829], + "KinematicState": [3.609332, 0.664397, 0.140656] } } } @@ -692,16 +540,8 @@ "Info": { "TotalPassed": 12, "Decision": "none", - "LaneInfo": [ - 1500, - 6.715403, - -1.232613 - ], - "KinematicState": [ - 3.693096, - 0.754094, - 0.908683 - ] + "LaneInfo": [1500, 6.715403, -1.232613], + "KinematicState": [3.693096, 0.754094, 0.908683] } } } @@ -724,16 +564,8 @@ "Info": { "TotalPassed": 13, "Decision": "none", - "LaneInfo": [ - 1500, - 7.089984, - -1.197086 - ], - "KinematicState": [ - 3.774627, - 0.811998, - 0.580573 - ] + "LaneInfo": [1500, 7.089984, -1.197086], + "KinematicState": [3.774627, 0.811998, 0.580573] } } } @@ -756,16 +588,8 @@ "Info": { "TotalPassed": 14, "Decision": "none", - "LaneInfo": [ - 1500, - 7.473814, - -1.158361 - ], - "KinematicState": [ - 3.848118, - 0.791756, - -0.201294 - ] + "LaneInfo": [1500, 7.473814, -1.158361], + "KinematicState": [3.848118, 0.791756, -0.201294] } } } @@ -788,16 +612,8 @@ "Info": { "TotalPassed": 15, "Decision": "none", - "LaneInfo": [ - 1500, - 7.863955, - -1.116921 - ], - "KinematicState": [ - 3.930269, - 0.825974, - 0.344808 - ] + "LaneInfo": [1500, 7.863955, -1.116921], + "KinematicState": [3.930269, 0.825974, 0.344808] } } } @@ -820,16 +636,8 @@ "Info": { "TotalPassed": 16, "Decision": "none", - "LaneInfo": [ - 1500, - 8.264956, - -1.076771 - ], - "KinematicState": [ - 4.006945, - 0.811871, - -0.140155 - ] + "LaneInfo": [1500, 8.264956, -1.076771], + "KinematicState": [4.006945, 0.811871, -0.140155] } } } @@ -852,16 +660,8 @@ "Info": { "TotalPassed": 17, "Decision": "none", - "LaneInfo": [ - 1500, - 8.687818, - -1.034342 - ], - "KinematicState": [ - 4.083466, - 0.78916, - -0.220425 - ] + "LaneInfo": [1500, 8.687818, -1.034342], + "KinematicState": [4.083466, 0.78916, -0.220425] } } } @@ -884,16 +684,8 @@ "Info": { "TotalPassed": 18, "Decision": "none", - "LaneInfo": [ - 1500, - 9.086423, - -0.993832 - ], - "KinematicState": [ - 4.153996, - 0.769382, - -0.205345 - ] + "LaneInfo": [1500, 9.086423, -0.993832], + "KinematicState": [4.153996, 0.769382, -0.205345] } } } @@ -916,16 +708,8 @@ "Info": { "TotalPassed": 19, "Decision": "none", - "LaneInfo": [ - 1500, - 9.505482, - -0.951828 - ], - "KinematicState": [ - 4.233492, - 0.802354, - 0.328948 - ] + "LaneInfo": [1500, 9.505482, -0.951828], + "KinematicState": [4.233492, 0.802354, 0.328948] } } } @@ -948,16 +732,8 @@ "Info": { "TotalPassed": 20, "Decision": "none", - "LaneInfo": [ - 1500, - 9.943206, - -0.906019 - ], - "KinematicState": [ - 4.281736, - 0.657596, - -1.443561 - ] + "LaneInfo": [1500, 9.943206, -0.906019], + "KinematicState": [4.281736, 0.657596, -1.443561] } } } diff --git a/sample/planning_control/scenario.yaml b/sample/planning_control/scenario.yaml index 6a0a8fd8..b2945f20 100644 --- a/sample/planning_control/scenario.yaml +++ b/sample/planning_control/scenario.yaml @@ -22,9 +22,9 @@ Evaluation: id: 1500 s: 2.3 kinematic_condition: - vel: {min: 2.5, max: 3.0} - acc: {min: -0.5, max: 0.5} - jerk: {min: 0.2, max: 1.5} + vel: { min: 2.5, max: 3.0 } + acc: { min: -0.5, max: 0.5 } + jerk: { min: 0.2, max: 1.5 } - module: "autonomous_emergency_braking: aeb_emergency_stop" decision: none condition_type: all_of From fa543a80e9a4db44e2d4e5485cb8dd2f35c3a8f0 Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Fri, 19 Jul 2024 12:00:24 +0900 Subject: [PATCH 14/28] feat: add remap /localization/acceleration --- log_evaluator/launch/log_evaluator.launch.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/log_evaluator/launch/log_evaluator.launch.py b/log_evaluator/launch/log_evaluator.launch.py index afce56cc..e21af35a 100644 --- a/log_evaluator/launch/log_evaluator.launch.py +++ b/log_evaluator/launch/log_evaluator.launch.py @@ -254,6 +254,9 @@ def launch_bag_player( remap_list.append( "/localization/kinematic_state:=/unused/localization/kinematic_state", ) + remap_list.append( + "/localization/acceleration:=/unused/localization/acceleration", + ) if len(remap_list) != 1: play_cmd.extend(remap_list) bag_player = ExecuteProcess(cmd=play_cmd, output="screen") From 233ac3bd1fdb8b4d146f1fcbd1da8cf6b03061f8 Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Fri, 19 Jul 2024 13:03:38 +0900 Subject: [PATCH 15/28] docs: update --- docs/use_case/planning_control.ja.md | 36 +- sample/planning_control/control_diag.txt | 6155 +--------------------- sample/planning_control/scenario.yaml | 2 +- 3 files changed, 33 insertions(+), 6160 deletions(-) diff --git a/docs/use_case/planning_control.ja.md b/docs/use_case/planning_control.ja.md index 585776c5..695b4b3b 100644 --- a/docs/use_case/planning_control.ja.md +++ b/docs/use_case/planning_control.ja.md @@ -1,45 +1,27 @@ # Planning Controlの評価 -Planning / ControlのMetricsが指定の時刻、条件で出力されているか評価する +Planning / ControlのMetricsが指定の条件で出力されているか評価する ## 評価方法 -`planning_control.launch.py` を使用して評価する。 launch を立ち上げると以下のことが実行され、評価される。 1. launch で評価ノード(`planning_control_evaluator_node`)と `logging_simulator.launch`、`ros2 bag play`コマンドを立ち上げる 2. bag から出力されたセンサーデータを autoware が受け取って、perception モジュールが認識を行う -3. perceptionの結果を使って、planningは `/diagnostic/planning_evaluator/metrics(仮)` に controlは `/diagnostic/control_evaluator/metrics`にMetricsを出力する +3. perceptionの結果を使って、planningは `/diagnostic/planning_evaluator/metrics` に controlは `/diagnostic/control_evaluator/metrics`にMetricsを出力する 4. 評価ノードが topic を subscribe して、各基準を満たしているかを判定して結果をファイルに記録する 5. bag の再生が終了すると自動で launch が終了して評価が終了する ## 評価結果 -controlが出力するtopicは以下のサンプルのような形式となっている。 -[control sample](https://github.com/tier4/driving_log_replayer/blob/main/sample/planning_control/control_diag.txt) - -headerの時刻で評価する条件があれば評価され判定結果が出力される。 -headerの時刻に該当する評価条件がない場合は捨てられるのでログも出力されない。 +topicのstatus[0].nameがシナリオで指定したモジュール名と一致し、且つ、status[0].value[0].keyがdecisionの場合に評価される。 +また、シナリオでレーン条件を追加した場合は、レーン条件も満たした場合に評価される。 +評価の条件を満たさない場合は、ログも出力されない。 ### 正常 -評価条件を満たすtopic が (現在時刻-評価開始時刻)\*Hertz\*AllowableRate(=0.95)個以上取得できた場合。 - -以下の例の場合、現在時刻が2だとすると、1秒からスタートして2秒の時点で (2-1)*10.0=10 topic程度metricsが出てくるはず。 -しかし、出力レートは厳密に指定のレートにはならない。 -よってAllowableRateをかけて floor(10*0.95)=9個以上 autonomous_emergency_braking: aeb_emergency_stop のdecisionの値stopが出ていたら成功とする -3秒時点では、floor(20\*0.95)=19以上で成功となる。 - -```yaml -Conditions: - Hertz: 10.0 # metricsが何Hzで来るか。 (現在時刻-評価開始時刻)* Hertz * AllowableRate(=0.95)以上条件に合致するtopicが出力される必要がある。AllowableRateは現在固定されている - ControlConditions: - - TimeRange: { start: 1, end: 3 } # 評価開始時間と終了時刻、endは省略可能で省略した場合はsys.float_info.max - Module: "autonomous_emergency_braking: aeb_emergency_stop" # 評価対象のモジュール - Value0Key: decision # 評価対象のキー - Value0Value: stop # 評価対象の値 - DetailedConditions: null # 位置、速度など、追加で判定したい条件。nullの場合はValue0Valueが一致した時点で成功。nullではない時はDetailedConditionsも条件を満たす必要がある -``` +status[0].values[0].valueがシナリオのdecisionと一致した場合に正常となる。 +kinematic_conditionを指定した場合は追加で、kinematic_stateが条件を満たしている必要がある。 ### 異常 @@ -52,7 +34,7 @@ Subscribed topics: | Topic name | Data type | | ------------------------------------------- | ------------------------------------- | | /diagnostic/control_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | -| /diagnostic/planning_evaluator/metrics (仮) | diagnostic_msgs::msg::DiagnosticArray | +| /diagnostic/planning_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | Published topics: @@ -64,7 +46,7 @@ Published topics: autoware の処理を軽くするため、評価に関係のないモジュールは launch の引数に false を渡すことで無効化する。以下を設定している。 -- sensing: true / false (launch引数で指定。現状true固定) +- sensing: true / false (シナリオにLaunchSensingのキーを指定することで切り替え可能) - localization: false ## simulation diff --git a/sample/planning_control/control_diag.txt b/sample/planning_control/control_diag.txt index cb26d934..92fdcd50 100644 --- a/sample/planning_control/control_diag.txt +++ b/sample/planning_control/control_diag.txt @@ -1,298 +1,11 @@ -# pos_x, pos_yでなくてstart_s, start_t, end_s, end_tとするのは区間指定・重複対応のため。 -# s,tは求めづらいのでrvizで可視化できると良い。 - -#---------- -# planning/control evaluator側 -# Decision -name: aeb # crosswalk, obstacle_cruise_planner.... - - key: decision - value: 'deceleration' # 'deceleration', 'none' - -name: crosswalk - - key: decision - value: 'none' # 複数ある場合は一番近いの計算して送る - -name: ... # その他色んなモジュールがdecisionを出す。 - -# 現在のvel, acc, jerkもだす -# planning/control evaluatorどちらから出すべき -name: kinematic_state # こっちは詳細条件で指定された場合に使うやつ - - key: vel - value: - - key: acc - value: - - key: jerk - value: -#---------- - -name: lane_info # kinematicでないので分離するほうがいいかも?これがモジュールの条件判定に使われる。lanelet2_extension_pythonで計算できるならlog_evaluatorで計算も可。sとtの計算はよくわからない。 - - key: lane_id - value: - - key: s # laneの開始からの縦距離 - value: - - key: t # laneの中心からの横距離 - value: - - ~/ros_ws/planning_control dlr/test-platform* 5m 49s ❯ ros2 topic echo /diagnostic/control_evaluator/metrics 1721114673.647621 [77] ros2: determined eno1 (udp/10.0.55.137) as highest quality interface, selected for automatic interface. -header: - stamp: - sec: 1709009632 - nanosec: 404397388 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '11.807869' - - key: t - value: '-0.027418' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '4.164290' - - key: acc - value: '-0.245304' - - key: jerk - value: '-0.860871' ---- -header: - stamp: - sec: 1709009632 - nanosec: 504355839 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '12.224617' - - key: t - value: '-0.018463' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '4.157930' - - key: acc - value: '-0.162705' - - key: jerk - value: '0.824320' ---- -header: - stamp: - sec: 1709009632 - nanosec: 604399852 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '12.638497' - - key: t - value: '-0.005600' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '4.114442' - - key: acc - value: '-0.262229' - - key: jerk - value: '-0.995871' ---- -header: - stamp: - sec: 1709009632 - nanosec: 704401222 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '13.048985' - - key: t - value: '-0.017200' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '4.077619' - - key: acc - value: '-0.306019' - - key: jerk - value: '-0.434886' ---- -header: - stamp: - sec: 1709009632 - nanosec: 804405494 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '13.459571' - - key: t - value: '-0.026677' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '4.051801' - - key: acc - value: '-0.290056' - - key: jerk - value: '0.159762' ---- -header: - stamp: - sec: 1709009632 - nanosec: 904397276 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '13.864332' - - key: t - value: '-0.032471' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '4.039792' - - key: acc - value: '-0.237908' - - key: jerk - value: '0.522073' ---- -header: - stamp: - sec: 1709009633 - nanosec: 4402718 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '14.268093' - - key: t - value: '-0.031601' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '4.024280' - - key: acc - value: '-0.192781' - - key: jerk - value: '0.450397' --- header: stamp: - sec: 1709009633 - nanosec: 104399187 + sec: 1709009638 + nanosec: 704405284 frame_id: '' status: - level: "\0" @@ -303,41 +16,19 @@ status: - key: decision value: none - level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '14.668894' - - key: t - value: '-0.027730' -- level: "\0" - name: kinematic_state + name: lateral_deviation message: '' hardware_id: '' values: - - key: vel - value: '3.993165' - - key: acc - value: '-0.238488' - - key: jerk - value: '-0.460506' ---- -header: - stamp: - sec: 1709009633 - nanosec: 204398359 - frame_id: '' -status: + - key: metric_value + value: '0.002404' - level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' + name: yaw_deviation message: '' hardware_id: '' values: - - key: decision - value: none + - key: metric_value + value: '0.109910' - level: "\0" name: ego_lane_info message: '' @@ -346,25 +37,25 @@ status: - key: lane_id value: '176472' - key: s - value: '15.068897' + value: '34.271024' - key: t - value: '-0.018027' + value: '-0.207536' - level: "\0" name: kinematic_state message: '' hardware_id: '' values: - key: vel - value: '3.987874' + value: '3.201738' - key: acc - value: '-0.164279' + value: '-0.424839' - key: jerk - value: '0.737804' + value: '-0.288387' --- header: stamp: - sec: 1709009633 - nanosec: 304349655 + sec: 1709009638 + nanosec: 804405072 frame_id: '' status: - level: "\0" @@ -373,21 +64,21 @@ status: hardware_id: '' values: - key: decision - value: none + value: deceleration - level: "\0" name: lateral_deviation message: '' hardware_id: '' values: - key: metric_value - value: '0.025369' + value: '0.038727' - level: "\0" name: yaw_deviation message: '' hardware_id: '' values: - key: metric_value - value: '0.004000' + value: '0.139692' - level: "\0" name: ego_lane_info message: '' @@ -396,5817 +87,17 @@ status: - key: lane_id value: '176472' - key: s - value: '15.465595' + value: '34.610130' - key: t - value: '-0.002923' + value: '-0.275624' - level: "\0" name: kinematic_state message: '' hardware_id: '' values: - key: vel - value: '3.988385' + value: '3.164714' - key: acc - value: '-0.093019' + value: '-0.400825' - key: jerk - value: '0.718444' ---- -header: - stamp: - sec: 1709009633 - nanosec: 404406859 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.026010' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.004765' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '15.860878' - - key: t - value: '0.018357' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.951453' - - key: acc - value: '-0.201406' - - key: jerk - value: '-1.084758' ---- -header: - stamp: - sec: 1709009633 - nanosec: 504402461 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.043618' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.001869' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '16.253703' - - key: t - value: '0.045773' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.933332' - - key: acc - value: '-0.190086' - - key: jerk - value: '0.112204' ---- -header: - stamp: - sec: 1709009633 - nanosec: 604397104 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.033925' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.005160' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '16.646073' - - key: t - value: '0.078742' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.924233' - - key: acc - value: '-0.147421' - - key: jerk - value: '0.427608' ---- -header: - stamp: - sec: 1709009633 - nanosec: 704398088 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.032928' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.003028' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '17.054920' - - key: t - value: '0.067871' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.897449' - - key: acc - value: '-0.176098' - - key: jerk - value: '-0.283933' ---- -header: - stamp: - sec: 1709009633 - nanosec: 804396573 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.034375' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.002316' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '17.438880' - - key: t - value: '0.033011' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.864558' - - key: acc - value: '-0.224534' - - key: jerk - value: '-0.484897' ---- -header: - stamp: - sec: 1709009633 - nanosec: 904370804 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.033854' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.000219' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '17.822643' - - key: t - value: '0.003604' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.815756' - - key: acc - value: '-0.324810' - - key: jerk - value: '-1.014564' ---- -header: - stamp: - sec: 1709009634 - nanosec: 4622345 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.032416' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.003169' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '18.202224' - - key: t - value: '-0.016596' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.793325' - - key: acc - value: '-0.269849' - - key: jerk - value: '0.551987' ---- -header: - stamp: - sec: 1709009634 - nanosec: 104403083 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.032518' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.017093' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '18.578890' - - key: t - value: '-0.029997' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.758273' - - key: acc - value: '-0.317572' - - key: jerk - value: '-0.474196' ---- -header: - stamp: - sec: 1709009634 - nanosec: 204407371 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.032112' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.015094' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '18.950500' - - key: t - value: '-0.035818' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.728484' - - key: acc - value: '-0.300998' - - key: jerk - value: '0.166093' ---- -header: - stamp: - sec: 1709009634 - nanosec: 304399499 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.027861' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.011690' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '19.317634' - - key: t - value: '-0.030101' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.693635' - - key: acc - value: '-0.332801' - - key: jerk - value: '-0.315577' ---- -header: - stamp: - sec: 1709009634 - nanosec: 404400912 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.020459' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.014390' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '19.683569' - - key: t - value: '-0.018609' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.644010' - - key: acc - value: '-0.417998' - - key: jerk - value: '-0.860537' ---- -header: - stamp: - sec: 1709009634 - nanosec: 504402082 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.033513' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.013516' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '20.047342' - - key: t - value: '0.001176' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.651010' - - key: acc - value: '-0.219605' - - key: jerk - value: '1.982136' ---- -header: - stamp: - sec: 1709009634 - nanosec: 604408766 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.036433' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.014549' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '20.411824' - - key: t - value: '0.028157' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.631270' - - key: acc - value: '-0.224491' - - key: jerk - value: '-0.048567' ---- -header: - stamp: - sec: 1709009634 - nanosec: 704401891 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.021742' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.012889' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '20.770255' - - key: t - value: '0.063837' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.609732' - - key: acc - value: '-0.223466' - - key: jerk - value: '0.010292' ---- -header: - stamp: - sec: 1709009634 - nanosec: 804402528 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.033043' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.010015' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '21.172657' - - key: t - value: '0.060088' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.602591' - - key: acc - value: '-0.176368' - - key: jerk - value: '0.444927' ---- -header: - stamp: - sec: 1709009634 - nanosec: 904401578 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.023385' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.009472' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '21.504707' - - key: t - value: '0.016219' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.563133' - - key: acc - value: '-0.277536' - - key: jerk - value: '-1.073808' ---- -header: - stamp: - sec: 1709009635 - nanosec: 4409379 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.028143' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.010353' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '21.855572' - - key: t - value: '-0.020629' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.547458' - - key: acc - value: '-0.228453' - - key: jerk - value: '0.490374' ---- -header: - stamp: - sec: 1709009635 - nanosec: 104402212 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.024038' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.009086' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '22.208145' - - key: t - value: '-0.049282' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.531702' - - key: acc - value: '-0.214168' - - key: jerk - value: '0.143816' ---- -header: - stamp: - sec: 1709009635 - nanosec: 204399984 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.027309' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.009630' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '22.558326' - - key: t - value: '-0.071643' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.516410' - - key: acc - value: '-0.189944' - - key: jerk - value: '0.237638' ---- -header: - stamp: - sec: 1709009635 - nanosec: 304401060 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.036380' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.009749' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '22.906186' - - key: t - value: '-0.087145' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.496249' - - key: acc - value: '-0.192153' - - key: jerk - value: '-0.022431' ---- -header: - stamp: - sec: 1709009635 - nanosec: 404403684 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.051493' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.006277' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '23.251555' - - key: t - value: '-0.092226' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.488161' - - key: acc - value: '-0.141204' - - key: jerk - value: '0.508395' ---- -header: - stamp: - sec: 1709009635 - nanosec: 504404540 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.034991' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.014021' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '23.596912' - - key: t - value: '-0.090172' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.472385' - - key: acc - value: '-0.165042' - - key: jerk - value: '-0.239460' ---- -header: - stamp: - sec: 1709009635 - nanosec: 604401859 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.069065' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.007616' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '23.943344' - - key: t - value: '-0.079462' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.464842' - - key: acc - value: '-0.133225' - - key: jerk - value: '0.316310' ---- -header: - stamp: - sec: 1709009635 - nanosec: 704401363 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.069201' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.002540' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '24.286892' - - key: t - value: '-0.059856' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.459577' - - key: acc - value: '-0.105967' - - key: jerk - value: '0.275366' ---- -header: - stamp: - sec: 1709009635 - nanosec: 804404624 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.065768' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.003422' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '24.632572' - - key: t - value: '-0.033874' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.459042' - - key: acc - value: '-0.065826' - - key: jerk - value: '0.398159' ---- -header: - stamp: - sec: 1709009635 - nanosec: 904385192 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.056024' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.006617' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '24.971668' - - key: t - value: '0.000769' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.431239' - - key: acc - value: '-0.159842' - - key: jerk - value: '-0.936098' ---- -header: - stamp: - sec: 1709009636 - nanosec: 4414142 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.078727' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.001546' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '25.314088' - - key: t - value: '0.007231' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.406308' - - key: acc - value: '-0.197551' - - key: jerk - value: '-0.378975' ---- -header: - stamp: - sec: 1709009636 - nanosec: 104402382 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.077044' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.003557' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '25.647174' - - key: t - value: '-0.029318' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.385903' - - key: acc - value: '-0.199265' - - key: jerk - value: '-0.017086' ---- -header: - stamp: - sec: 1709009636 - nanosec: 204404017 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.087602' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.000475' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '25.983543' - - key: t - value: '-0.058872' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.373357' - - key: acc - value: '-0.156002' - - key: jerk - value: '0.435549' ---- -header: - stamp: - sec: 1709009636 - nanosec: 304404689 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.083968' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.003294' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '26.317021' - - key: t - value: '-0.078753' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.339658' - - key: acc - value: '-0.234312' - - key: jerk - value: '-0.780355' ---- -header: - stamp: - sec: 1709009636 - nanosec: 404400526 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.090360' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.006444' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '26.646357' - - key: t - value: '-0.091089' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.318838' - - key: acc - value: '-0.227483' - - key: jerk - value: '0.067870' ---- -header: - stamp: - sec: 1709009636 - nanosec: 504401874 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.094138' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.010599' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '26.973981' - - key: t - value: '-0.094759' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.289312' - - key: acc - value: '-0.259603' - - key: jerk - value: '-0.323090' ---- -header: - stamp: - sec: 1709009636 - nanosec: 604399116 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.085571' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.014195' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '27.298338' - - key: t - value: '-0.089062' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.282849' - - key: acc - value: '-0.167568' - - key: jerk - value: '0.921623' ---- -header: - stamp: - sec: 1709009636 - nanosec: 704403027 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.076062' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.010848' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '27.624338' - - key: t - value: '-0.075814' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.276570' - - key: acc - value: '-0.116953' - - key: jerk - value: '0.507004' ---- -header: - stamp: - sec: 1709009636 - nanosec: 804409130 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.070814' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.015993' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '27.949007' - - key: t - value: '-0.056075' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.285428' - - key: acc - value: '-0.024339' - - key: jerk - value: '0.929589' ---- -header: - stamp: - sec: 1709009636 - nanosec: 904401159 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.063623' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.013067' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '28.274616' - - key: t - value: '-0.027441' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.294343' - - key: acc - value: '0.020471' - - key: jerk - value: '0.436154' ---- -header: - stamp: - sec: 1709009637 - nanosec: 4401350 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.060313' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.001066' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '28.602352' - - key: t - value: '0.009481' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.299993' - - key: acc - value: '0.033551' - - key: jerk - value: '0.134107' ---- -header: - stamp: - sec: 1709009637 - nanosec: 104377720 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.063324' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.006147' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '28.930982' - - key: t - value: '0.055127' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.310351' - - key: acc - value: '0.051750' - - key: jerk - value: '0.181860' ---- -header: - stamp: - sec: 1709009637 - nanosec: 204400741 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.065196' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.009482' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '29.253953' - - key: t - value: '0.107721' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.327083' - - key: acc - value: '0.110871' - - key: jerk - value: '0.581150' ---- -header: - stamp: - sec: 1709009637 - nanosec: 304399357 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.061152' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.010437' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '29.625718' - - key: t - value: '0.076836' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.322890' - - key: acc - value: '0.046393' - - key: jerk - value: '-0.633029' ---- -header: - stamp: - sec: 1709009637 - nanosec: 404402047 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.045513' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.009830' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '29.951530' - - key: t - value: '0.029930' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.332101' - - key: acc - value: '0.062972' - - key: jerk - value: '0.171483' ---- -header: - stamp: - sec: 1709009637 - nanosec: 504399264 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.027418' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.002446' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '30.282104' - - key: t - value: '-0.009942' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.348156' - - key: acc - value: '0.094798' - - key: jerk - value: '0.313989' ---- -header: - stamp: - sec: 1709009637 - nanosec: 604402430 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.067232' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.016803' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '30.617080' - - key: t - value: '-0.044809' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.376559' - - key: acc - value: '0.177190' - - key: jerk - value: '0.839564' ---- -header: - stamp: - sec: 1709009637 - nanosec: 704400683 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.077263' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.010312' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '30.955830' - - key: t - value: '-0.071936' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.403736' - - key: acc - value: '0.216875' - - key: jerk - value: '0.392260' ---- -header: - stamp: - sec: 1709009637 - nanosec: 804399832 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.103227' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.007414' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '31.295542' - - key: t - value: '-0.092534' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.422113' - - key: acc - value: '0.205161' - - key: jerk - value: '-0.116102' ---- -header: - stamp: - sec: 1709009637 - nanosec: 904404386 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.114550' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.006291' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '31.637928' - - key: t - value: '-0.106168' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.433946' - - key: acc - value: '0.164503' - - key: jerk - value: '-0.413887' ---- -header: - stamp: - sec: 1709009638 - nanosec: 4380889 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.097242' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.010474' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '31.976767' - - key: t - value: '-0.112751' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.423078' - - key: acc - value: '0.047411' - - key: jerk - value: '-1.155156' ---- -header: - stamp: - sec: 1709009638 - nanosec: 104401638 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.120685' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.015547' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '32.330131' - - key: t - value: '-0.110941' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.409248' - - key: acc - value: '-0.028400' - - key: jerk - value: '-0.739542' ---- -header: - stamp: - sec: 1709009638 - nanosec: 204401112 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.129125' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.012326' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '32.653723' - - key: t - value: '-0.103303' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.392227' - - key: acc - value: '-0.089833' - - key: jerk - value: '-0.636760' ---- -header: - stamp: - sec: 1709009638 - nanosec: 304399600 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.094222' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.004253' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '32.991292' - - key: t - value: '-0.092907' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.375724' - - key: acc - value: '-0.119411' - - key: jerk - value: '-0.292589' ---- -header: - stamp: - sec: 1709009638 - nanosec: 404406320 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.094543' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.030371' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '33.328334' - - key: t - value: '-0.080002' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.347397' - - key: acc - value: '-0.181810' - - key: jerk - value: '-0.624531' ---- -header: - stamp: - sec: 1709009638 - nanosec: 504404271 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.081011' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.057709' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '33.638464' - - key: t - value: '-0.090885' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.302839' - - key: acc - value: '-0.287816' - - key: jerk - value: '-1.071392' ---- -header: - stamp: - sec: 1709009638 - nanosec: 604400878 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.035806' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.083509' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '33.957364' - - key: t - value: '-0.146791' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.250613' - - key: acc - value: '-0.395964' - - key: jerk - value: '-1.082415' ---- -header: - stamp: - sec: 1709009638 - nanosec: 704405284 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.002404' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.109910' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '34.271024' - - key: t - value: '-0.207536' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.201738' - - key: acc - value: '-0.424839' - - key: jerk - value: '-0.288387' ---- -header: - stamp: - sec: 1709009638 - nanosec: 804405072 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: deceleration -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.038727' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.139692' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '34.610130' - - key: t - value: '-0.275624' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.164714' - - key: acc - value: '-0.400825' - - key: jerk - value: '0.217844' ---- -header: - stamp: - sec: 1709009638 - nanosec: 904416356 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: deceleration -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.196166' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.154997' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '34.882375' - - key: t - value: '-0.334608' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.133997' - - key: acc - value: '-0.404052' - - key: jerk - value: '-0.035990' ---- -header: - stamp: - sec: 1709009639 - nanosec: 4417901 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: deceleration -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.247082' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.168040' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '35.183540' - - key: t - value: '-0.399925' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.108041' - - key: acc - value: '-0.337578' - - key: jerk - value: '0.643050' ---- -header: - stamp: - sec: 1709009639 - nanosec: 104411118 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: deceleration -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.292116' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.176340' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '35.484670' - - key: t - value: '-0.464261' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.068601' - - key: acc - value: '-0.366837' - - key: jerk - value: '-0.304465' ---- -header: - stamp: - sec: 1709009639 - nanosec: 204407354 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: deceleration -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.341302' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.182917' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '35.778943' - - key: t - value: '-0.529533' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.023590' - - key: acc - value: '-0.409510' - - key: jerk - value: '-0.421688' ---- -header: - stamp: - sec: 1709009639 - nanosec: 304410525 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: deceleration -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.417672' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.186204' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '36.095905' - - key: t - value: '-0.597037' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '2.995624' - - key: acc - value: '-0.345813' - - key: jerk - value: '0.593408' ---- -header: - stamp: - sec: 1709009639 - nanosec: 404414696 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: deceleration -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.459117' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.189278' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '36.359724' - - key: t - value: '-0.654262' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '2.972544' - - key: acc - value: '-0.299326' - - key: jerk - value: '0.508477' ---- -header: - stamp: - sec: 1709009639 - nanosec: 504406939 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: deceleration -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.511652' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.191124' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '36.645451' - - key: t - value: '-0.712760' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '2.944074' - - key: acc - value: '-0.285829' - - key: jerk - value: '0.132708' ---- -header: - stamp: - sec: 1709009639 - nanosec: 604409723 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: deceleration -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.587826' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.188456' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '36.933826' - - key: t - value: '-0.770362' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '2.919497' - - key: acc - value: '-0.274788' - - key: jerk - value: '0.111478' ---- -header: - stamp: - sec: 1709009639 - nanosec: 704403639 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: deceleration -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.659352' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.184065' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '37.217586' - - key: t - value: '-0.824414' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '2.877049' - - key: acc - value: '-0.330259' - - key: jerk - value: '-0.558135' ---- -header: - stamp: - sec: 1709009639 - nanosec: 804407921 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: deceleration -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.710881' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.178507' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '37.496811' - - key: t - value: '-0.876442' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '2.849749' - - key: acc - value: '-0.320258' - - key: jerk - value: '0.099428' ---- -header: - stamp: - sec: 1709009639 - nanosec: 904405274 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: deceleration -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.765217' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.172269' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '176472' - - key: s - value: '37.738132' - - key: t - value: '-0.925174' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '2.809040' - - key: acc - value: '-0.352498' - - key: jerk - value: '-0.321446' ---- -header: - stamp: - sec: 1709009640 - nanosec: 4411217 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: deceleration -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.832975' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.161679' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '0.254821' - - key: t - value: '-0.983676' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '2.780202' - - key: acc - value: '-0.322109' - - key: jerk - value: '0.299525' ---- -header: - stamp: - sec: 1709009640 - nanosec: 104409667 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: deceleration -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.876415' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.153313' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '0.524374' - - key: t - value: '-1.038678' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '2.778970' - - key: acc - value: '-0.193682' - - key: jerk - value: '1.284198' ---- -header: - stamp: - sec: 1709009640 - nanosec: 204408500 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: deceleration -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.914800' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.142017' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '0.797716' - - key: t - value: '-1.089461' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '2.766703' - - key: acc - value: '-0.157067' - - key: jerk - value: '0.374411' ---- -header: - stamp: - sec: 1709009640 - nanosec: 304402334 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: deceleration -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.951588' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.128978' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '1.072910' - - key: t - value: '-1.137064' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '2.774931' - - key: acc - value: '-0.064950' - - key: jerk - value: '0.919988' ---- -header: - stamp: - sec: 1709009640 - nanosec: 404404029 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: deceleration -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '1.016150' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.118127' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '1.345795' - - key: t - value: '-1.181963' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '2.785044' - - key: acc - value: '0.000635' - - key: jerk - value: '0.654367' ---- -header: - stamp: - sec: 1709009640 - nanosec: 504402608 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: deceleration -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '1.043522' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.104031' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '1.619427' - - key: t - value: '-1.222165' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '2.806327' - - key: acc - value: '0.093698' - - key: jerk - value: '0.929944' ---- -header: - stamp: - sec: 1709009640 - nanosec: 604408011 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: deceleration -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '1.069969' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.091281' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '1.899189' - - key: t - value: '-1.257947' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '2.826436' - - key: acc - value: '0.134591' - - key: jerk - value: '0.411654' ---- -header: - stamp: - sec: 1709009640 - nanosec: 704403572 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: deceleration -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '1.103021' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.076999' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '2.180388' - - key: t - value: '-1.287927' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '2.855254' - - key: acc - value: '0.206083' - - key: jerk - value: '0.706992' ---- -header: - stamp: - sec: 1709009640 - nanosec: 804400090 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: deceleration -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '1.166697' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.064772' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '2.463578' - - key: t - value: '-1.315164' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '2.871829' - - key: acc - value: '0.189194' - - key: jerk - value: '-0.169536' ---- -header: - stamp: - sec: 1709009640 - nanosec: 904408423 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: deceleration -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '1.185643' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.049794' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '2.756252' - - key: t - value: '-1.339019' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '2.924632' - - key: acc - value: '0.313097' - - key: jerk - value: '1.232130' ---- -header: - stamp: - sec: 1709009641 - nanosec: 4410489 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '1.200281' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.034773' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '3.048498' - - key: t - value: '-1.357804' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '2.973334' - - key: acc - value: '0.388577' - - key: jerk - value: '0.757059' ---- -header: - stamp: - sec: 1709009641 - nanosec: 104403955 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '1.241443' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.020706' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '3.348355' - - key: t - value: '-1.371031' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.031645' - - key: acc - value: '0.492628' - - key: jerk - value: '1.050884' ---- -header: - stamp: - sec: 1709009641 - nanosec: 204406868 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '1.256049' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.005195' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '3.654895' - - key: t - value: '-1.378377' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.088592' - - key: acc - value: '0.524980' - - key: jerk - value: '0.322604' ---- -header: - stamp: - sec: 1709009641 - nanosec: 304403545 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '1.255756' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.010914' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '3.967671' - - key: t - value: '-1.380667' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.152821' - - key: acc - value: '0.584220' - - key: jerk - value: '0.590881' ---- -header: - stamp: - sec: 1709009641 - nanosec: 404414036 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '1.259759' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.025090' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '4.286699' - - key: t - value: '-1.378690' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.220785' - - key: acc - value: '0.655660' - - key: jerk - value: '0.710801' ---- -header: - stamp: - sec: 1709009641 - nanosec: 504407066 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '1.221319' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.040636' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '4.614102' - - key: t - value: '-1.371985' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.287503' - - key: acc - value: '0.687749' - - key: jerk - value: '0.320499' ---- -header: - stamp: - sec: 1709009641 - nanosec: 604411210 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '1.215403' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.052577' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '4.954561' - - key: t - value: '-1.359024' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.346353' - - key: acc - value: '0.642912' - - key: jerk - value: '-0.443885' ---- -header: - stamp: - sec: 1709009641 - nanosec: 704414774 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '1.227203' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.061235' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '5.289516' - - key: t - value: '-1.341692' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.407900' - - key: acc - value: '0.626983' - - key: jerk - value: '-0.162374' ---- -header: - stamp: - sec: 1709009641 - nanosec: 804408603 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '1.203615' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.071551' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '5.636661' - - key: t - value: '-1.319875' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.475030' - - key: acc - value: '0.605346' - - key: jerk - value: '-0.217098' ---- -header: - stamp: - sec: 1709009641 - nanosec: 904408132 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '1.175841' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.080601' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '5.989970' - - key: t - value: '-1.294059' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.537443' - - key: acc - value: '0.650080' - - key: jerk - value: '0.445461' ---- -header: - stamp: - sec: 1709009642 - nanosec: 4359569 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '1.152956' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.087397' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '6.348585' - - key: t - value: '-1.265829' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.609332' - - key: acc - value: '0.664397' - - key: jerk - value: '0.140656' ---- -header: - stamp: - sec: 1709009642 - nanosec: 104407311 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '1.118816' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.093438' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '6.715403' - - key: t - value: '-1.232613' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.693096' - - key: acc - value: '0.754094' - - key: jerk - value: '0.908683' ---- -header: - stamp: - sec: 1709009642 - nanosec: 204410579 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '1.083005' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.097700' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '7.089984' - - key: t - value: '-1.197086' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.774627' - - key: acc - value: '0.811998' - - key: jerk - value: '0.580573' ---- -header: - stamp: - sec: 1709009642 - nanosec: 304407858 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '1.048047' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.100630' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '7.473814' - - key: t - value: '-1.158361' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.848118' - - key: acc - value: '0.791756' - - key: jerk - value: '-0.201294' ---- -header: - stamp: - sec: 1709009642 - nanosec: 404405559 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '1.006286' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.102594' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '7.863955' - - key: t - value: '-1.116921' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '3.930269' - - key: acc - value: '0.825974' - - key: jerk - value: '0.344808' ---- -header: - stamp: - sec: 1709009642 - nanosec: 504405783 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.966912' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.102802' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '8.264956' - - key: t - value: '-1.076771' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '4.006945' - - key: acc - value: '0.811871' - - key: jerk - value: '-0.140155' ---- -header: - stamp: - sec: 1709009642 - nanosec: 604410778 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.927086' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.102103' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '8.687818' - - key: t - value: '-1.034342' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '4.083466' - - key: acc - value: '0.789160' - - key: jerk - value: '-0.220425' ---- -header: - stamp: - sec: 1709009642 - nanosec: 704406881 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.887594' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.101057' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '9.086423' - - key: t - value: '-0.993832' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '4.153996' - - key: acc - value: '0.769382' - - key: jerk - value: '-0.205345' ---- -header: - stamp: - sec: 1709009642 - nanosec: 804408753 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.847435' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.099233' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '9.505482' - - key: t - value: '-0.951828' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '4.233492' - - key: acc - value: '0.802354' - - key: jerk - value: '0.328948' ---- -header: - stamp: - sec: 1709009642 - nanosec: 904416934 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.802559' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.097481' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '9.943206' - - key: t - value: '-0.906019' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '4.281736' - - key: acc - value: '0.657596' - - key: jerk - value: '-1.443561' ---- -header: - stamp: - sec: 1709009643 - nanosec: 4414587 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.760994' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.095718' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '10.377127' - - key: t - value: '-0.859918' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '4.371687' - - key: acc - value: '0.765366' - - key: jerk - value: '1.085507' ---- -header: - stamp: - sec: 1709009643 - nanosec: 104420505 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.718341' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.093899' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '10.819839' - - key: t - value: '-0.813713' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '4.449620' - - key: acc - value: '0.759741' - - key: jerk - value: '-0.056001' ---- -header: - stamp: - sec: 1709009643 - nanosec: 204414143 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.677567' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.091658' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '11.269511' - - key: t - value: '-0.769288' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '4.515152' - - key: acc - value: '0.705259' - - key: jerk - value: '-0.547844' ---- -header: - stamp: - sec: 1709009643 - nanosec: 304409405 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.636199' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.089442' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '11.732517' - - key: t - value: '-0.723596' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '4.643522' - - key: acc - value: '0.936769' - - key: jerk - value: '2.295276' ---- -header: - stamp: - sec: 1709009643 - nanosec: 404408357 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.595805' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.086742' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '12.203680' - - key: t - value: '-0.679467' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '4.714383' - - key: acc - value: '0.870530' - - key: jerk - value: '-0.665125' ---- -header: - stamp: - sec: 1709009643 - nanosec: 504408288 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.556659' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.083749' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '12.681458' - - key: t - value: '-0.636197' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '4.781159' - - key: acc - value: '0.782888' - - key: jerk - value: '-0.871966' ---- -header: - stamp: - sec: 1709009643 - nanosec: 604416966 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.518422' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.080730' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '13.165103' - - key: t - value: '-0.594228' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '4.845298' - - key: acc - value: '0.875744' - - key: jerk - value: '0.938267' ---- -header: - stamp: - sec: 1709009643 - nanosec: 704412200 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.478444' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.077884' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '13.659722' - - key: t - value: '-0.550278' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '4.961584' - - key: acc - value: '0.963578' - - key: jerk - value: '0.874294' ---- -header: - stamp: - sec: 1709009643 - nanosec: 804416329 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.438143' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.075065' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '14.164645' - - key: t - value: '-0.506251' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '5.028357' - - key: acc - value: '0.830937' - - key: jerk - value: '-1.324163' ---- -header: - stamp: - sec: 1709009643 - nanosec: 904411958 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.399433' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.071776' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '14.675367' - - key: t - value: '-0.463699' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '5.105083' - - key: acc - value: '0.820178' - - key: jerk - value: '-0.107559' ---- -header: - stamp: - sec: 1709009644 - nanosec: 4412436 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.363026' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.067987' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '15.195114' - - key: t - value: '-0.423452' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '5.183570' - - key: acc - value: '0.803005' - - key: jerk - value: '-0.171691' ---- -header: - stamp: - sec: 1709009644 - nanosec: 104404806 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.327198' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.064287' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '15.720697' - - key: t - value: '-0.383685' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '5.263354' - - key: acc - value: '0.804745' - - key: jerk - value: '0.017441' ---- -header: - stamp: - sec: 1709009644 - nanosec: 204374578 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.294181' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.060668' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '16.255231' - - key: t - value: '-0.346902' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '5.344423' - - key: acc - value: '0.821352' - - key: jerk - value: '0.166395' ---- -header: - stamp: - sec: 1709009644 - nanosec: 304407810 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.264649' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.056752' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '16.797438' - - key: t - value: '-0.313619' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '5.409145' - - key: acc - value: '0.724561' - - key: jerk - value: '-0.960358' ---- -header: - stamp: - sec: 1709009644 - nanosec: 404406024 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.230520' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.052595' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '17.374075' - - key: t - value: '-0.275700' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '5.488134' - - key: acc - value: '0.744188' - - key: jerk - value: '0.188219' ---- -header: - stamp: - sec: 1709009644 - nanosec: 504406423 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.209591' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.049251' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '17.792559' - - key: t - value: '-0.252145' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '5.567167' - - key: acc - value: '0.861748' - - key: jerk - value: '1.555661' ---- -header: - stamp: - sec: 1709009644 - nanosec: 604407422 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.177184' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.044099' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '18.469470' - - key: t - value: '-0.215682' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '5.639301' - - key: acc - value: '1.686702' - - key: jerk - value: '6.896215' ---- -header: - stamp: - sec: 1709009644 - nanosec: 704407151 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.154012' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.039584' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '19.048558' - - key: t - value: '-0.189305' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '5.704660' - - key: acc - value: '1.253791' - - key: jerk - value: '-4.334988' ---- -header: - stamp: - sec: 1709009644 - nanosec: 804415775 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.134210' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.035080' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '19.624477' - - key: t - value: '-0.166634' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '5.789560' - - key: acc - value: '1.094605' - - key: jerk - value: '-1.583055' ---- -header: - stamp: - sec: 1709009644 - nanosec: 904406820 - frame_id: '' -status: -- level: "\0" - name: 'autonomous_emergency_braking: aeb_emergency_stop' - message: '' - hardware_id: '' - values: - - key: decision - value: none -- level: "\0" - name: lateral_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.112861' -- level: "\0" - name: yaw_deviation - message: '' - hardware_id: '' - values: - - key: metric_value - value: '0.031182' -- level: "\0" - name: ego_lane_info - message: '' - hardware_id: '' - values: - - key: lane_id - value: '1500' - - key: s - value: '20.211304' - - key: t - value: '-0.142367' -- level: "\0" - name: kinematic_state - message: '' - hardware_id: '' - values: - - key: vel - value: '5.862113' - - key: acc - value: '0.953421' - - key: jerk - value: '-1.418752' + value: '0.217844' diff --git a/sample/planning_control/scenario.yaml b/sample/planning_control/scenario.yaml index b2945f20..e0cd4e32 100644 --- a/sample/planning_control/scenario.yaml +++ b/sample/planning_control/scenario.yaml @@ -9,7 +9,7 @@ Evaluation: Datasets: - odaiba: VehicleId: default - LaunchSensing: true + LaunchSensing: true # trueの場合はbagの中に入っている/sensing/lidar/concatenated/pointcloudはremapされ、packetsから点群を作る。 Conditions: ControlConditions: - module: "autonomous_emergency_braking: aeb_emergency_stop" From 281e0e9503337811376a81751d6ff0a7abb265c7 Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Fri, 19 Jul 2024 14:07:13 +0900 Subject: [PATCH 16/28] docs: update can msg --- docs/use_case/planning_control.en.md | 2 +- docs/use_case/planning_control.ja.md | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/docs/use_case/planning_control.en.md b/docs/use_case/planning_control.en.md index b6ab22f4..7e9a186a 100644 --- a/docs/use_case/planning_control.en.md +++ b/docs/use_case/planning_control.en.md @@ -75,7 +75,7 @@ State the information required to run the simulation. | Topic name | Data type | | -------------------------------------- | -------------------------------------------- | -| /gsm8/from_can_bus | can_msgs/msg/Frame | +| /pacmod/from_can_bus | can_msgs/msg/Frame | | /localization/kinematic_state | nav_msgs/msg/Odometry | | /localization/acceleration | geometry_msgs/msg/AccelWithCovarianceStamped | | /sensing/lidar/concatenated/pointcloud | sensor_msgs/msg/PointCloud2 | diff --git a/docs/use_case/planning_control.ja.md b/docs/use_case/planning_control.ja.md index 695b4b3b..b798084f 100644 --- a/docs/use_case/planning_control.ja.md +++ b/docs/use_case/planning_control.ja.md @@ -31,9 +31,9 @@ kinematic_conditionを指定した場合は追加で、kinematic_stateが条件 Subscribed topics: -| Topic name | Data type | -| ------------------------------------------- | ------------------------------------- | -| /diagnostic/control_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | +| Topic name | Data type | +| -------------------------------------- | ------------------------------------- | +| /diagnostic/control_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | | /diagnostic/planning_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | Published topics: @@ -57,7 +57,7 @@ autoware の処理を軽くするため、評価に関係のないモジュー | topic 名 | データ型 | | -------------------------------------- | -------------------------------------------- | -| /gsm8/from_can_bus | can_msgs/msg/Frame | +| /pacmod/from_can_bus | can_msgs/msg/Frame | | /localization/kinematic_state | nav_msgs/msg/Odometry | | /localization/acceleration | geometry_msgs/msg/AccelWithCovarianceStamped | | /sensing/lidar/concatenated/pointcloud | sensor_msgs/msg/PointCloud2 | From d608bd117be64bca817a17a2f05abdce91ca6f48 Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Fri, 19 Jul 2024 15:17:57 +0900 Subject: [PATCH 17/28] feat: support LaunchPerception and LaunchPlanning --- docs/use_case/planning_control.en.md | 45 ++++++-------------- docs/use_case/planning_control.ja.md | 9 ++-- log_evaluator/launch/log_evaluator.launch.py | 20 +++++---- sample/planning_control/scenario.yaml | 4 +- 4 files changed, 34 insertions(+), 44 deletions(-) diff --git a/docs/use_case/planning_control.en.md b/docs/use_case/planning_control.en.md index 7e9a186a..71378da5 100644 --- a/docs/use_case/planning_control.en.md +++ b/docs/use_case/planning_control.en.md @@ -4,42 +4,24 @@ Evaluate whether Planning / Control metrics are output at specified times and co ## Evaluation Method -The planning_control evaluation is executed by launching the `planning_control.launch.py` file. Launching the file executes the following steps: 1. Execute launch of evaluation node (`planning_control_evaluator_node`), `logging_simulator.launch` file and `ros2 bag play` command 2. Autoware receives sensor data output from input rosbag and the perception module performs recognition. -3. Using the results of perception, Autoware output Metrics to `/diagnostic/planning_evaluator/metrics(temporary)` for planning and `/diagnostic/control_evaluator/metrics` for control. +3. Using the results of perception, Autoware output Metrics to `/diagnostic/planning_evaluator/metrics` for planning and `/diagnostic/control_evaluator/metrics` for control. 4. The evaluation node subscribes to the topic and evaluates data. The result is dumped into a file. 5. When the playback of the rosbag is finished, Autoware's launch is automatically terminated, and the evaluation is completed. ## Evaluation Result -The output from control_evaluator is in the form of the following sample TOPIC. -[control sample](https://github.com/tier4/driving_log_replayer/blob/main/sample/planning_control/control_diag.txt) - -If there is a condition to be evaluated at the time of the header, it is evaluated and the judgment result is output. -If there is no evaluation condition corresponding to the time of the header, it is discarded and no log is output. +It is evaluated when status[0].name of the topic matches the module name specified in the scenario and status[0].value[0].key is a decision. +If a lane condition is described in the scenario, it is evaluated when the lane condition is also satisfied. +If the conditions for evaluation are not met, no log is output. ### Normal -If more than (current time - evaluation start time)\*Hertz\*AllowableRate(=0.95) topics are obtained that satisfy the evaluation conditions. - -In the following example, if the current time is 2, starting from 1 second, at the 2 second mark, (2-1)*10.0=10 topics should be retrieved. -However, the output rate is not exactly the specified rate. -Therefore, if the AllowableRate is applied and floor(10*0.95)=9 or more autonomous_emergency_braking: aeb_emergency_stop decision value stop is obtained, it is considered a success. -At 3 seconds, floor(20\*0.95)=19 or more is success. - -```yaml -Conditions: - Hertz: 10.0 # How many Hz the METRICS will come in. (current time - evaluation start time)* Hertz * AllowableRate(=0.95) or more TOPICS that match the condition must be output. AllowableRate is currently fixed. - ControlConditions: - - TimeRange: { start: 1, end: 3 } # Evaluation start time and end time, end is optional and if omitted, sys.float_info.max - Module: "autonomous_emergency_braking: aeb_emergency_stop" # Modules to be evaluated - Value0Key: decision # Key to be evaluated - Value0Value: stop # Value to be evaluated - DetailedConditions: null # Additional conditions to be determined, such as position, speed, etc. If null, succeeds when Value0Value is matched. If not null, DetailedConditions must also satisfy the condition. -``` +Normal if status[0].values[0].value matches the decision in the scenario. +If kinematic_condition is specified, additionally, kinematic_state must meet the condition. ### Error @@ -49,10 +31,10 @@ When the normal condition is not met Subscribed topics: -| Topic name | Data type | -| ------------------------------------------- | ------------------------------------- | -| /diagnostic/control_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | -| /diagnostic/planning_evaluator/metrics (仮) | diagnostic_msgs::msg::DiagnosticArray | +| Topic name | Data type | +| -------------------------------------- | ------------------------------------- | +| /diagnostic/control_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | +| /diagnostic/planning_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | Published topics: @@ -126,12 +108,13 @@ Success is determined when all evaluation conditions set in planning and control ```json { "Frame": { - "CONDITION_INDEX": { - // Results are output for each evaluation condition. + "[Planning|Control]_CONDITION_INDEX": { "Result": { "Total": "Success or Fail", "Frame": "Success or Fail" }, "Info": { "TotalPassed": "Total number of topics that passed the evaluation criteria", - "RequiredSuccess": "Number of successes required at current time (TotalPassed >= RequiredSuccess makes Total a success)" + "Decision": "Decision of the acquired TOPIC", + "LaneInfo": "[lane_id, s, t]", + "KinematicState": "[vel, acc, jerk]" } } } diff --git a/docs/use_case/planning_control.ja.md b/docs/use_case/planning_control.ja.md index b798084f..61712c6d 100644 --- a/docs/use_case/planning_control.ja.md +++ b/docs/use_case/planning_control.ja.md @@ -15,7 +15,7 @@ launch を立ち上げると以下のことが実行され、評価される。 ## 評価結果 topicのstatus[0].nameがシナリオで指定したモジュール名と一致し、且つ、status[0].value[0].keyがdecisionの場合に評価される。 -また、シナリオでレーン条件を追加した場合は、レーン条件も満たした場合に評価される。 +また、シナリオでレーン条件を記述した場合は、レーン条件も満たした場合に評価される。 評価の条件を満たさない場合は、ログも出力されない。 ### 正常 @@ -107,12 +107,13 @@ planning と controlで設定した全ての評価条件で成功している場 ```json { "Frame": { - "CONDITION_INDEX": { - // 評価条件毎に結果が出力される + "[Planning|Control]_CONDITION_INDEX": { "Result": { "Total": "Success or Fail", "Frame": "Success or Fail" }, "Info": { "TotalPassed": "評価条件をパスしたtopicの総数", - "RequiredSuccess": "現在時刻で必要な成功数(TotalPassed >= RequiredSuccessでTotalが成功になる)" + "Decision": "取得したtopicのdecision", + "LaneInfo": "[lane_id, s, t]", + "KinematicState": "[vel, acc, jerk]" } } } diff --git a/log_evaluator/launch/log_evaluator.launch.py b/log_evaluator/launch/log_evaluator.launch.py index e21af35a..99eb3200 100644 --- a/log_evaluator/launch/log_evaluator.launch.py +++ b/log_evaluator/launch/log_evaluator.launch.py @@ -109,18 +109,22 @@ def ensure_arg_compatibility(context: LaunchContext) -> list: dataset_index = int(idx_str) for k, v in datasets[dataset_index].items(): dataset_path = dataset_dir.joinpath(k) - map_path_str: str | None = v.get("LocalMapPath") conf["vehicle_id"] = v["VehicleId"] - launch_sensing = yaml_obj["Evaluation"].get("LaunchSensing") - launch_localization = yaml_obj["Evaluation"].get("LaunchLocalization") + launch_sensing = v.get("LaunchSensing") + launch_localization = v.get("LaunchLocalization") + launch_perception = v.get("LaunchPerception") + launch_planning = v.get("LaunchPlanning") if launch_sensing is not None: - conf["sensing"] = str(launch_sensing) + # str(bool) だと True/Falseになって文字列比較で問題でるのでlowerで全小文字にする + conf["sensing"] = str(launch_sensing).lower() if launch_localization is not None: - conf["localization"] = str(launch_localization) + conf["localization"] = str(launch_localization).lower() + if launch_perception is not None: + conf["perception"] = str(launch_perception).lower() + if launch_planning is not None: + conf["planning"] = str(launch_planning).lower() - map_path = ( - dataset_path.joinpath("map") if map_path_str is None else Path(expandvars(map_path_str)) - ) + map_path = dataset_path.joinpath("map") conf["map_path"] = map_path.as_posix() conf["vehicle_model"] = yaml_obj["VehicleModel"] conf["sensor_model"] = yaml_obj["SensorModel"] diff --git a/sample/planning_control/scenario.yaml b/sample/planning_control/scenario.yaml index e0cd4e32..6548cebd 100644 --- a/sample/planning_control/scenario.yaml +++ b/sample/planning_control/scenario.yaml @@ -9,7 +9,9 @@ Evaluation: Datasets: - odaiba: VehicleId: default - LaunchSensing: true # trueの場合はbagの中に入っている/sensing/lidar/concatenated/pointcloudはremapされ、packetsから点群を作る。 + LaunchSensing: true # trueの場合はlidarのpacketsから点群を作る。falseの場合、bagに/sensing/lidar/concatenated/pointcloudが入っている必要がある + LaunchPerception: true # falseの場合はplanning/controlで使用するperceptionのtopicをbagに入れておく必要がある + LaunchPlanning: true # falseの場合はcontrolで使用するplanningのtopicをbagに入れておく必要がある Conditions: ControlConditions: - module: "autonomous_emergency_braking: aeb_emergency_stop" From 509c7156c3cab4d0403b8b953544b65c9276e7d3 Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Fri, 19 Jul 2024 16:55:27 +0900 Subject: [PATCH 18/28] feat: remap topic in bag --- log_evaluator/launch/log_evaluator.launch.py | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/log_evaluator/launch/log_evaluator.launch.py b/log_evaluator/launch/log_evaluator.launch.py index 99eb3200..de0c8999 100644 --- a/log_evaluator/launch/log_evaluator.launch.py +++ b/log_evaluator/launch/log_evaluator.launch.py @@ -261,6 +261,18 @@ def launch_bag_player( remap_list.append( "/localization/acceleration:=/unused/localization/acceleration", ) + if conf.get("perception", "true") == "true": + # remap perception msgs in bag + remap_list.append( + "/perception/obstacle_segmentation/pointcloud:=/unused/perception/obstacle_segmentation/pointcloud", + ) + remap_list.append( + "/perception/object_recognition/objects:=/unused/perception/object_recognition/objects", + ) + if conf.get("planning", "true") == "true": + remap_list.append( + "/planning/mission_planning/route:=/unused/planning/mission_planning/route", + ) if len(remap_list) != 1: play_cmd.extend(remap_list) bag_player = ExecuteProcess(cmd=play_cmd, output="screen") From 6b78be48a8e8e6c498251fc460748ecdc8e1701c Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Fri, 19 Jul 2024 16:58:24 +0900 Subject: [PATCH 19/28] fix: pre-commit --- log_evaluator/launch/log_evaluator.launch.py | 1 - 1 file changed, 1 deletion(-) diff --git a/log_evaluator/launch/log_evaluator.launch.py b/log_evaluator/launch/log_evaluator.launch.py index de0c8999..ca03656f 100644 --- a/log_evaluator/launch/log_evaluator.launch.py +++ b/log_evaluator/launch/log_evaluator.launch.py @@ -13,7 +13,6 @@ # limitations under the License. import datetime -from os.path import expandvars from pathlib import Path from ament_index_python.packages import get_package_share_directory From ec98b03297ca438ac25e55d228edd4ce0771b19d Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Mon, 22 Jul 2024 12:35:23 +0900 Subject: [PATCH 20/28] chore: update status length check --- log_evaluator/log_evaluator/planning_control.py | 7 +------ sample/planning_control/scenario.yaml | 8 ++++---- 2 files changed, 5 insertions(+), 10 deletions(-) diff --git a/log_evaluator/log_evaluator/planning_control.py b/log_evaluator/log_evaluator/planning_control.py index b3352332..1d41b597 100644 --- a/log_evaluator/log_evaluator/planning_control.py +++ b/log_evaluator/log_evaluator/planning_control.py @@ -160,12 +160,7 @@ def __post_init__(self) -> None: self.use_kinetic_condition = self.condition.kinematic_condition is not None def set_frame(self, msg: DiagnosticArray) -> dict | None: # noqa - if len(msg.status) == 0: - return None - - # temporary - if len(msg.status) == 1: - # to avoid local variable 'lane_info_tuple' referenced before assignment + if len(msg.status) <= 1: return None # key check diff --git a/sample/planning_control/scenario.yaml b/sample/planning_control/scenario.yaml index 6548cebd..de4a0834 100644 --- a/sample/planning_control/scenario.yaml +++ b/sample/planning_control/scenario.yaml @@ -9,13 +9,13 @@ Evaluation: Datasets: - odaiba: VehicleId: default - LaunchSensing: true # trueの場合はlidarのpacketsから点群を作る。falseの場合、bagに/sensing/lidar/concatenated/pointcloudが入っている必要がある - LaunchPerception: true # falseの場合はplanning/controlで使用するperceptionのtopicをbagに入れておく必要がある - LaunchPlanning: true # falseの場合はcontrolで使用するplanningのtopicをbagに入れておく必要がある + LaunchSensing: true # If true, make pointcloud from lidar packets; if false, publish from bag. Therefore, /sensing/lidar/concatenated/pointcloud must be in the bag. + LaunchPerception: true # If false, the TOPIC of PERCEPTION to be used in PLANNING / CONTROL must be in the BAG. + LaunchPlanning: true # If false, the TOPIC of PLANNING to be used in CONTROL must be in the BAG. Conditions: ControlConditions: - module: "autonomous_emergency_braking: aeb_emergency_stop" - decision: deceleration # module の KeyValueのkeyをkeyにvalueをvalueに指定。今後decision以外が評価したいとなったらkey-valueが追加して対応する + decision: deceleration # Specify key as key and value as value in KeyValue of module. condition_type: all_of lane_condition: start: From f0683186074e0753637482bfd4b90825cea8fa4f Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Mon, 22 Jul 2024 13:01:23 +0900 Subject: [PATCH 21/28] fix: remap --- log_evaluator/launch/log_evaluator.launch.py | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/log_evaluator/launch/log_evaluator.launch.py b/log_evaluator/launch/log_evaluator.launch.py index ca03656f..6e98c9a9 100644 --- a/log_evaluator/launch/log_evaluator.launch.py +++ b/log_evaluator/launch/log_evaluator.launch.py @@ -269,9 +269,7 @@ def launch_bag_player( "/perception/object_recognition/objects:=/unused/perception/object_recognition/objects", ) if conf.get("planning", "true") == "true": - remap_list.append( - "/planning/mission_planning/route:=/unused/planning/mission_planning/route", - ) + pass if len(remap_list) != 1: play_cmd.extend(remap_list) bag_player = ExecuteProcess(cmd=play_cmd, output="screen") From b0909a0dedf927a2e3250a34ea27a016c6e6545d Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Mon, 22 Jul 2024 13:55:45 +0900 Subject: [PATCH 22/28] docs: update document --- docs/use_case/planning_control.en.md | 7 ++++++- docs/use_case/planning_control.ja.md | 7 ++++++- 2 files changed, 12 insertions(+), 2 deletions(-) diff --git a/docs/use_case/planning_control.en.md b/docs/use_case/planning_control.en.md index 71378da5..d07c14b3 100644 --- a/docs/use_case/planning_control.en.md +++ b/docs/use_case/planning_control.en.md @@ -46,9 +46,14 @@ Published topics: To make Autoware processing less resource-consuming, modules that are not relevant to evaluation are disabled by passing the `false` parameter as a launch argument. -- sensing: true / false (Specified by the launch argument. Currently fixed to true.) - localization: false +### Arguments specified in the scenario or launch command + +- sensing: It can be disabled by specifying LaunchSensing: false in the scenario. Or specify sensing:=false in the launch command +- perception: It can be disabled by specifying LaunchPerception: false in the scenario. Or specify perception:=false in the launch command +- planning: It can be disabled by specifying LaunchPlanning: false in the scenario. Or specify planning:=false in the launch command + ## About simulation State the information required to run the simulation. diff --git a/docs/use_case/planning_control.ja.md b/docs/use_case/planning_control.ja.md index 61712c6d..1db2caac 100644 --- a/docs/use_case/planning_control.ja.md +++ b/docs/use_case/planning_control.ja.md @@ -46,9 +46,14 @@ Published topics: autoware の処理を軽くするため、評価に関係のないモジュールは launch の引数に false を渡すことで無効化する。以下を設定している。 -- sensing: true / false (シナリオにLaunchSensingのキーを指定することで切り替え可能) - localization: false +### シナリオまたはlaunchコマンドで指定する引数 + +- sensing: シナリオにLaunchSensing: falseを指定することで無効化できる。またはlaunchコマンドでsensing:=falseを指定する +- perception: シナリオにLaunchPerception: falseを指定することで無効化できる。またはlaunchコマンドでperception:=falseを指定する +- planning: シナリオにLaunchPlanning: falseを指定することで無効化できる。またはlaunchコマンドでplanning:=falseを指定する + ## simulation シミュレーション実行に必要な情報を述べる。 From 2c46423882fc4c62509af52731fa71944169d76e Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Mon, 22 Jul 2024 14:07:04 +0900 Subject: [PATCH 23/28] docs: update sample --- docs/use_case/planning_control.en.md | 4 ++++ docs/use_case/planning_control.ja.md | 4 ++++ sample/planning_control/scenario.yaml | 6 +++--- 3 files changed, 11 insertions(+), 3 deletions(-) diff --git a/docs/use_case/planning_control.en.md b/docs/use_case/planning_control.en.md index d07c14b3..9c0c7210 100644 --- a/docs/use_case/planning_control.en.md +++ b/docs/use_case/planning_control.en.md @@ -54,6 +54,10 @@ To make Autoware processing less resource-consuming, modules that are not releva - perception: It can be disabled by specifying LaunchPerception: false in the scenario. Or specify perception:=false in the launch command - planning: It can be disabled by specifying LaunchPlanning: false in the scenario. Or specify planning:=false in the launch command +```shell +ros2 launch log_evaluator log_evaluator.launch.py scenario_path:=${planning_control_scenario_path} sensing:=false perception:=false planning:=false +``` + ## About simulation State the information required to run the simulation. diff --git a/docs/use_case/planning_control.ja.md b/docs/use_case/planning_control.ja.md index 1db2caac..d1204ae0 100644 --- a/docs/use_case/planning_control.ja.md +++ b/docs/use_case/planning_control.ja.md @@ -54,6 +54,10 @@ autoware の処理を軽くするため、評価に関係のないモジュー - perception: シナリオにLaunchPerception: falseを指定することで無効化できる。またはlaunchコマンドでperception:=falseを指定する - planning: シナリオにLaunchPlanning: falseを指定することで無効化できる。またはlaunchコマンドでplanning:=falseを指定する +```shell +ros2 launch log_evaluator log_evaluator.launch.py scenario_path:=${planning_control_scenario_path} sensing:=false perception:=false planning:=false +``` + ## simulation シミュレーション実行に必要な情報を述べる。 diff --git a/sample/planning_control/scenario.yaml b/sample/planning_control/scenario.yaml index de4a0834..a9ac8ad6 100644 --- a/sample/planning_control/scenario.yaml +++ b/sample/planning_control/scenario.yaml @@ -9,9 +9,9 @@ Evaluation: Datasets: - odaiba: VehicleId: default - LaunchSensing: true # If true, make pointcloud from lidar packets; if false, publish from bag. Therefore, /sensing/lidar/concatenated/pointcloud must be in the bag. - LaunchPerception: true # If false, the TOPIC of PERCEPTION to be used in PLANNING / CONTROL must be in the BAG. - LaunchPlanning: true # If false, the TOPIC of PLANNING to be used in CONTROL must be in the BAG. + LaunchSensing: false # If false, the TOPIC of SENSING to be used in PERCEPTION must be in the BAG. + # LaunchPerception: false # If false, the TOPIC of PERCEPTION to be used in PLANNING / CONTROL must be in the BAG. + # LaunchPlanning: false # If false, the TOPIC of PLANNING to be used in CONTROL must be in the BAG. Conditions: ControlConditions: - module: "autonomous_emergency_braking: aeb_emergency_stop" From 89ef9dfb71dd9bcb3ad59c93e16509bbf371307a Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Mon, 22 Jul 2024 19:03:48 +0900 Subject: [PATCH 24/28] feat: update unit test --- .../log_evaluator/planning_control.py | 10 +- .../test/unittest/test_planning_control.py | 231 ++++++++++++++++++ 2 files changed, 236 insertions(+), 5 deletions(-) diff --git a/log_evaluator/log_evaluator/planning_control.py b/log_evaluator/log_evaluator/planning_control.py index 1d41b597..c3cfa2ad 100644 --- a/log_evaluator/log_evaluator/planning_control.py +++ b/log_evaluator/log_evaluator/planning_control.py @@ -60,7 +60,7 @@ def match_condition(self, lane_info: tuple, *, start_condition: bool = False) -> lane_id, s, t = lane_info if self.id != lane_id: return False - if self.s is not None and self.s >= s: # 超えたら開始、または終了 + if self.s is not None and self.s >= s: # Start or end when exceeded return False if start_condition and self.t is not None and not self.t.match_condition(t): return False @@ -87,13 +87,13 @@ def diag_lane_info(cls, lane_info: DiagnosticStatus) -> tuple[float, float, floa return (lane_id, s, t) def is_started(self, lane_info_tuple: tuple[float, float, float]) -> bool: - # 一度Trueになったら変更しない + # Once True, do not change. if not self.started: self.started = self.start.match_condition(lane_info_tuple, start_condition=True) return self.started def is_ended(self, lane_info_tuple: tuple[float, float, float]) -> bool: - # 一度Trueになったら変更しない + # Once True, do not change. if not self.ended: self.ended = self.end.match_condition(lane_info_tuple) return self.ended @@ -201,7 +201,7 @@ def set_frame(self, msg: DiagnosticArray) -> dict | None: # noqa self.total += 1 frame_success = "Fail" - # decisionが一致している、且つkinetic_stateが条件を満たしていればOK + # OK if decision matches and kinetic_state satisfies the condition if self.condition.decision == status0.values[0].value: if self.use_kinetic_condition: if self.condition.kinematic_condition.match_condition(kinetic_state_tuple): @@ -210,7 +210,7 @@ def set_frame(self, msg: DiagnosticArray) -> dict | None: # noqa else: frame_success = "Success" self.passed += 1 - # any_ofなら1個あればいい。all_ofは全部 + # any_of would only need one, all_of would need all of them. self.success = ( self.passed > 0 if self.condition.condition_type == "any_of" diff --git a/log_evaluator/test/unittest/test_planning_control.py b/log_evaluator/test/unittest/test_planning_control.py index df8987ab..2a2127f7 100644 --- a/log_evaluator/test/unittest/test_planning_control.py +++ b/log_evaluator/test/unittest/test_planning_control.py @@ -12,6 +12,21 @@ # See the License for the specific language governing permissions and # limitations under the License. +from typing import Literal + +from diagnostic_msgs.msg import DiagnosticArray +from diagnostic_msgs.msg import DiagnosticStatus +from diagnostic_msgs.msg import KeyValue +from pydantic import ValidationError +import pytest + +from log_evaluator.planning_control import KinematicCondition +from log_evaluator.planning_control import LaneCondition +from log_evaluator.planning_control import LaneInfo +from log_evaluator.planning_control import LeftRight +from log_evaluator.planning_control import Metrics +from log_evaluator.planning_control import MinMax +from log_evaluator.planning_control import PlanningControlCondition from log_evaluator.planning_control import PlanningControlScenario from log_evaluator.scenario import load_sample_scenario @@ -23,3 +38,219 @@ def test_scenario() -> None: ) assert scenario.ScenarioName == "sample_planning_control" assert scenario.Evaluation.Conditions.ControlConditions[0].condition_type == "all_of" + + +def test_min_max_validation() -> None: + with pytest.raises(ValidationError): + MinMax(min=3.0, max=1.0) + + +def test_left_right_validation() -> None: + with pytest.raises(ValidationError): + LeftRight(left=-3.0, right=1.0) + + +def test_left_right_match_condition() -> None: + left_right = LeftRight(left=1.0, right=1.0) + assert left_right.match_condition(0.5) + assert left_right.match_condition(2.0) is False + assert left_right.match_condition(-2.0) is False + + +def test_lane_info_match_condition() -> None: + lane_info = LaneInfo(id=1, s=1.0, t=LeftRight(left=1.0, right=1.0)) + assert lane_info.match_condition((1, 2.0, 0.5), start_condition=True) + assert lane_info.match_condition((2, 2.0, 0.5), start_condition=True) is False + assert lane_info.match_condition((1, 0.5, 0.5), start_condition=True) is False + assert lane_info.match_condition((1, 2.0, 3.0), start_condition=True) is False + assert lane_info.match_condition((1, 2.0, 3.0)) # if goal t is not used + + +def test_lane_condition_started_ended() -> None: + lane_condition = LaneCondition( + start=LaneInfo(id=1, s=1.0, t=LeftRight(left=1.0, right=1.0)), + end=LaneInfo(id=2, s=2.0), + ) + assert lane_condition.started is False + assert lane_condition.ended is False + assert lane_condition.is_started((1, 0.5, 0.5)) is False + assert lane_condition.is_started((1, 2.0, 0.5)) + assert lane_condition.is_started((2, 2.0)) # Once True, do not change. + assert lane_condition.is_ended((2, 1.0, 1.0)) is False + assert lane_condition.is_ended((2, 3.0, 1.0)) + + +def test_kinematic_state_match_condition() -> None: + kinematic_condition = KinematicCondition( + vel=MinMax(min=0.0, max=1.0), + acc=MinMax(min=0.0, max=2.0), + jerk=MinMax(min=0.0, max=3.0), + ) + assert kinematic_condition.match_condition((0.5, 1.0, 2.0)) + assert kinematic_condition.match_condition((2.0, 1.0, 2.0)) is False + assert kinematic_condition.match_condition((0.5, -1.0, 2.0)) is False + assert kinematic_condition.match_condition((0.5, 1.0, -1.0)) is False + + +def create_condition(condition_type: Literal["any_of", "all_of"]) -> PlanningControlCondition: + return PlanningControlCondition( + module="autonomous_emergency_braking: aeb_emergency_stop", + decision="deceleration", + condition_type=condition_type, + lane_condition=LaneCondition( + start=LaneInfo(id=1, s=1.0, t=LeftRight(left=1.0, right=1.0)), + end=LaneInfo(id=2, s=2.0), + ), + kinematic_condition=KinematicCondition( + vel=MinMax(min=0.0, max=1.0), + acc=MinMax(min=0.0, max=2.0), + jerk=MinMax(min=0.0, max=3.0), + ), + ) + + +def create_diag_msg( + *, + match_module: bool = True, + match_decision: bool = True, + is_started: bool = True, + is_ended: bool = False, + match_kinematic_state: bool = True, +) -> DiagnosticArray: + module = DiagnosticStatus( + name=( + "autonomous_emergency_braking: aeb_emergency_stop" + if match_module + else "module_not_matched" + ), + values=[ + KeyValue(key="decision" if match_decision else "not_decision", value="deceleration"), + ], + ) + lane_info = DiagnosticStatus( + name="ego_lane_info", + values=[ + KeyValue(key="lane_id", value="1" if is_ended is False else "2"), + KeyValue(key="s", value="2.0" if is_started else "1.0"), + KeyValue(key="t", value="0.5"), + ], + ) + kinematic_state = DiagnosticStatus( + name="kinematic_state", + values=[ + KeyValue(key="vel", value="0.5" if match_kinematic_state else "2.0"), + KeyValue(key="acc", value="1.0"), + KeyValue(key="jerk", value="2.0"), + ], + ) + return DiagnosticArray(status=[module, lane_info, kinematic_state]) + + +def test_msg_has_not_required_fields() -> None: + condition = create_condition("any_of") + evaluation_item: Metrics = Metrics(name="control_0", condition=condition) + diag_msg = DiagnosticArray(status=[]) + assert evaluation_item.set_frame(diag_msg) is None + + +def test_metrics_not_match_module_name() -> None: + condition = create_condition("any_of") + evaluation_item: Metrics = Metrics(name="control_0", condition=condition) + diag_msg = create_diag_msg(match_module=False) + assert evaluation_item.set_frame(diag_msg) is None + + +def test_metrics_not_match_decision() -> None: + condition = create_condition("any_of") + evaluation_item: Metrics = Metrics(name="control_0", condition=condition) + diag_msg = create_diag_msg(match_decision=False) + assert evaluation_item.set_frame(diag_msg) is None + + +def test_metrics_not_started() -> None: + condition = create_condition("any_of") + evaluation_item: Metrics = Metrics(name="control_0", condition=condition) + diag_msg = create_diag_msg(is_started=False) + assert evaluation_item.set_frame(diag_msg) is None + + +def test_metrics_finished() -> None: + condition = create_condition("any_of") + evaluation_item: Metrics = Metrics(name="control_0", condition=condition) + diag_msg = create_diag_msg(is_ended=True) + assert evaluation_item.set_frame(diag_msg) is None + + +def test_metrics_success_any_of() -> None: + condition = create_condition("any_of") + evaluation_item: Metrics = Metrics(name="control_0", condition=condition) + diag_msg = create_diag_msg() + frame_dict = evaluation_item.set_frame(diag_msg) + assert evaluation_item.success is True + assert frame_dict == { + "Result": {"Total": "Success", "Frame": "Success"}, + "Info": { + "TotalPassed": 1, + "Decision": "deceleration", + "LaneInfo": (1, 2.0, 0.5), + "KinematicState": (0.5, 1.0, 2.0), + }, + } + diag_msg = create_diag_msg(match_kinematic_state=False) + frame_dict = evaluation_item.set_frame(diag_msg) # any_of is OK if one of them succeeds. + assert evaluation_item.success is True + assert frame_dict == { + "Result": {"Total": "Success", "Frame": "Fail"}, + "Info": { + "TotalPassed": 1, + "Decision": "deceleration", + "LaneInfo": (1, 2.0, 0.5), + "KinematicState": (2.0, 1.0, 2.0), + }, + } + + +def test_metrics_fail_any_of() -> None: + condition = create_condition("any_of") + evaluation_item: Metrics = Metrics(name="control_0", condition=condition) + diag_msg = create_diag_msg(match_kinematic_state=False) + frame_dict = evaluation_item.set_frame(diag_msg) # any_of is OK if one of them succeeds. + assert evaluation_item.success is False + assert frame_dict == { + "Result": {"Total": "Fail", "Frame": "Fail"}, + "Info": { + "TotalPassed": 0, + "Decision": "deceleration", + "LaneInfo": (1, 2.0, 0.5), + "KinematicState": (2.0, 1.0, 2.0), + }, + } + + +def test_metrics_fail_all_of() -> None: + condition = create_condition("all_of") + evaluation_item: Metrics = Metrics(name="control_0", condition=condition) + diag_msg = create_diag_msg() + frame_dict = evaluation_item.set_frame(diag_msg) + assert evaluation_item.success is True + assert frame_dict == { + "Result": {"Total": "Success", "Frame": "Success"}, + "Info": { + "TotalPassed": 1, + "Decision": "deceleration", + "LaneInfo": (1, 2.0, 0.5), + "KinematicState": (0.5, 1.0, 2.0), + }, + } + diag_msg = create_diag_msg(match_kinematic_state=False) + frame_dict = evaluation_item.set_frame(diag_msg) # ALL_OF is not allowed if even one fails. + assert evaluation_item.success is False + assert frame_dict == { + "Result": {"Total": "Fail", "Frame": "Fail"}, + "Info": { + "TotalPassed": 1, + "Decision": "deceleration", + "LaneInfo": (1, 2.0, 0.5), + "KinematicState": (2.0, 1.0, 2.0), + }, + } From 2ffc651c1bf410343f8b07ffea622e387e11a1da Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Mon, 22 Jul 2024 19:16:39 +0900 Subject: [PATCH 25/28] fix: local variable lane_info_tuple referenced before assignment --- log_evaluator/log_evaluator/planning_control.py | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/log_evaluator/log_evaluator/planning_control.py b/log_evaluator/log_evaluator/planning_control.py index c3cfa2ad..8ff73385 100644 --- a/log_evaluator/log_evaluator/planning_control.py +++ b/log_evaluator/log_evaluator/planning_control.py @@ -175,6 +175,9 @@ def set_frame(self, msg: DiagnosticArray) -> dict | None: # noqa if status0.values[0].key != "decision": return None + lane_info_tuple = None + kinetic_state_tuple = None + # get additional condition for _, status in enumerate(msg.status, 1): status: DiagnosticStatus @@ -183,6 +186,9 @@ def set_frame(self, msg: DiagnosticArray) -> dict | None: # noqa if status.name == "kinematic_state": kinetic_state_tuple = KinematicCondition.diag_kinematic_state(status) + if lane_info_tuple is None or kinetic_state_tuple is None: + return None + if self.use_lane_condition: started = self.condition.lane_condition.is_started(lane_info_tuple) ended = self.condition.lane_condition.is_ended(lane_info_tuple) From 4b07ff19db5a593f9c617727d7b44d4182172327 Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Wed, 24 Jul 2024 18:21:03 +0900 Subject: [PATCH 26/28] feat: update scenario format and enable/disable component --- docs/use_case/planning_control.en.md | 9 ++------- docs/use_case/planning_control.ja.md | 9 ++------- sample/planning_control/scenario.yaml | 3 --- 3 files changed, 4 insertions(+), 17 deletions(-) diff --git a/docs/use_case/planning_control.en.md b/docs/use_case/planning_control.en.md index 9c0c7210..1822ecde 100644 --- a/docs/use_case/planning_control.en.md +++ b/docs/use_case/planning_control.en.md @@ -44,15 +44,10 @@ Published topics: ## Arguments passed to logging_simulator.launch -To make Autoware processing less resource-consuming, modules that are not relevant to evaluation are disabled by passing the `false` parameter as a launch argument. - - localization: false -### Arguments specified in the scenario or launch command - -- sensing: It can be disabled by specifying LaunchSensing: false in the scenario. Or specify sensing:=false in the launch command -- perception: It can be disabled by specifying LaunchPerception: false in the scenario. Or specify perception:=false in the launch command -- planning: It can be disabled by specifying LaunchPlanning: false in the scenario. Or specify planning:=false in the launch command +To use /sensing/lidar/concatenated/pointcloud in the bag, add sensing:=false to the launch argument. +If you want to use perception and planning from the bag as well, add “perception:=false planning:=false” to the “launch” argument. ```shell ros2 launch log_evaluator log_evaluator.launch.py scenario_path:=${planning_control_scenario_path} sensing:=false perception:=false planning:=false diff --git a/docs/use_case/planning_control.ja.md b/docs/use_case/planning_control.ja.md index d1204ae0..0d9a18e6 100644 --- a/docs/use_case/planning_control.ja.md +++ b/docs/use_case/planning_control.ja.md @@ -44,15 +44,10 @@ Published topics: ## logging_simulator.launch に渡す引数 -autoware の処理を軽くするため、評価に関係のないモジュールは launch の引数に false を渡すことで無効化する。以下を設定している。 - - localization: false -### シナリオまたはlaunchコマンドで指定する引数 - -- sensing: シナリオにLaunchSensing: falseを指定することで無効化できる。またはlaunchコマンドでsensing:=falseを指定する -- perception: シナリオにLaunchPerception: falseを指定することで無効化できる。またはlaunchコマンドでperception:=falseを指定する -- planning: シナリオにLaunchPlanning: falseを指定することで無効化できる。またはlaunchコマンドでplanning:=falseを指定する +bagの中に入っている、/sensing/lidar/concatenated/pointcloudを利用する場合は、launchの引数にsensing:=falseを追加する +perception、planningも同様にbagから出力する場合は、launchの引数にperception:=false planning:=falseを追加する ```shell ros2 launch log_evaluator log_evaluator.launch.py scenario_path:=${planning_control_scenario_path} sensing:=false perception:=false planning:=false diff --git a/sample/planning_control/scenario.yaml b/sample/planning_control/scenario.yaml index a9ac8ad6..5c9f9304 100644 --- a/sample/planning_control/scenario.yaml +++ b/sample/planning_control/scenario.yaml @@ -9,9 +9,6 @@ Evaluation: Datasets: - odaiba: VehicleId: default - LaunchSensing: false # If false, the TOPIC of SENSING to be used in PERCEPTION must be in the BAG. - # LaunchPerception: false # If false, the TOPIC of PERCEPTION to be used in PLANNING / CONTROL must be in the BAG. - # LaunchPlanning: false # If false, the TOPIC of PLANNING to be used in CONTROL must be in the BAG. Conditions: ControlConditions: - module: "autonomous_emergency_braking: aeb_emergency_stop" From f87670d0455898e9a2da56d03dd80073479ca28b Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Wed, 31 Jul 2024 16:00:28 +0900 Subject: [PATCH 27/28] feat: update topic name https://github.com/autowarefoundation/autoware.universe/pull/8152 --- docs/use_case/planning_control.en.md | 6 +++--- docs/use_case/planning_control.ja.md | 6 +++--- log_evaluator/log_evaluator/launch_config.py | 4 ++-- log_evaluator/scripts/planning_control_evaluator_node.py | 4 ++-- sample/planning_control/control_diag.txt | 2 +- 5 files changed, 11 insertions(+), 11 deletions(-) diff --git a/docs/use_case/planning_control.en.md b/docs/use_case/planning_control.en.md index 1822ecde..1d8eb388 100644 --- a/docs/use_case/planning_control.en.md +++ b/docs/use_case/planning_control.en.md @@ -8,7 +8,7 @@ Launching the file executes the following steps: 1. Execute launch of evaluation node (`planning_control_evaluator_node`), `logging_simulator.launch` file and `ros2 bag play` command 2. Autoware receives sensor data output from input rosbag and the perception module performs recognition. -3. Using the results of perception, Autoware output Metrics to `/diagnostic/planning_evaluator/metrics` for planning and `/diagnostic/control_evaluator/metrics` for control. +3. Using the results of perception, Autoware output Metrics to `/planning/planning_evaluator/metrics` for planning and `/control/control_evaluator/metrics` for control. 4. The evaluation node subscribes to the topic and evaluates data. The result is dumped into a file. 5. When the playback of the rosbag is finished, Autoware's launch is automatically terminated, and the evaluation is completed. @@ -33,8 +33,8 @@ Subscribed topics: | Topic name | Data type | | -------------------------------------- | ------------------------------------- | -| /diagnostic/control_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | -| /diagnostic/planning_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | +| /control/control_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | +| /planning/planning_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | Published topics: diff --git a/docs/use_case/planning_control.ja.md b/docs/use_case/planning_control.ja.md index 0d9a18e6..3feee473 100644 --- a/docs/use_case/planning_control.ja.md +++ b/docs/use_case/planning_control.ja.md @@ -8,7 +8,7 @@ launch を立ち上げると以下のことが実行され、評価される。 1. launch で評価ノード(`planning_control_evaluator_node`)と `logging_simulator.launch`、`ros2 bag play`コマンドを立ち上げる 2. bag から出力されたセンサーデータを autoware が受け取って、perception モジュールが認識を行う -3. perceptionの結果を使って、planningは `/diagnostic/planning_evaluator/metrics` に controlは `/diagnostic/control_evaluator/metrics`にMetricsを出力する +3. perceptionの結果を使って、planningは `/planning/planning_evaluator/metrics` に controlは `/control/control_evaluator/metrics`にMetricsを出力する 4. 評価ノードが topic を subscribe して、各基準を満たしているかを判定して結果をファイルに記録する 5. bag の再生が終了すると自動で launch が終了して評価が終了する @@ -33,8 +33,8 @@ Subscribed topics: | Topic name | Data type | | -------------------------------------- | ------------------------------------- | -| /diagnostic/control_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | -| /diagnostic/planning_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | +| /control/control_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | +| /planning/planning_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | Published topics: diff --git a/log_evaluator/log_evaluator/launch_config.py b/log_evaluator/log_evaluator/launch_config.py index fc39c513..65fbdad3 100644 --- a/log_evaluator/log_evaluator/launch_config.py +++ b/log_evaluator/log_evaluator/launch_config.py @@ -178,8 +178,8 @@ PERFORMANCE_DIAG_NODE_PARAMS = {} PLANNING_CONTROL_RECORD_TOPIC = """^/tf$\ -|^/diagnostic/control_evaluator/metrics$\ -|^/diagnostic/planning_evaluator/metrics$\ +|^/control/control_evaluator/metrics$\ +|^/planning/planning_evaluator/metrics$\ """ PLANNING_CONTROL_AUTOWARE_DISABLE = { diff --git a/log_evaluator/scripts/planning_control_evaluator_node.py b/log_evaluator/scripts/planning_control_evaluator_node.py index 41f0aa18..97d175c1 100755 --- a/log_evaluator/scripts/planning_control_evaluator_node.py +++ b/log_evaluator/scripts/planning_control_evaluator_node.py @@ -31,14 +31,14 @@ def __init__(self, name: str) -> None: self.__sub_planning_diagnostics = self.create_subscription( DiagnosticArray, - "/diagnostic/planning_evaluator/metrics", + "/planning/planning_evaluator/metrics", lambda msg, module_type="planning": self.diagnostics_cb(msg, module_type), 1, ) self.__sub_control_diagnostics = self.create_subscription( DiagnosticArray, - "/diagnostic/control_evaluator/metrics", + "/control/control_evaluator/metrics", lambda msg, module_type="control": self.diagnostics_cb(msg, module_type), 1, ) diff --git a/sample/planning_control/control_diag.txt b/sample/planning_control/control_diag.txt index 92fdcd50..7790a640 100644 --- a/sample/planning_control/control_diag.txt +++ b/sample/planning_control/control_diag.txt @@ -1,5 +1,5 @@ ~/ros_ws/planning_control dlr/test-platform* 5m 49s -❯ ros2 topic echo /diagnostic/control_evaluator/metrics +❯ ros2 topic echo /control/control_evaluator/metrics 1721114673.647621 [77] ros2: determined eno1 (udp/10.0.55.137) as highest quality interface, selected for automatic interface. --- header: From 16e32ae0ab9c54655706528aa72537f55cfb866c Mon Sep 17 00:00:00 2001 From: Hayato Mizushima Date: Fri, 2 Aug 2024 16:57:06 +0900 Subject: [PATCH 28/28] fix: pre-commit --- docs/use_case/planning_control.en.md | 6 +++--- docs/use_case/planning_control.ja.md | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/docs/use_case/planning_control.en.md b/docs/use_case/planning_control.en.md index 1d8eb388..c622c4a0 100644 --- a/docs/use_case/planning_control.en.md +++ b/docs/use_case/planning_control.en.md @@ -31,9 +31,9 @@ When the normal condition is not met Subscribed topics: -| Topic name | Data type | -| -------------------------------------- | ------------------------------------- | -| /control/control_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | +| Topic name | Data type | +| ------------------------------------ | ------------------------------------- | +| /control/control_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | | /planning/planning_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | Published topics: diff --git a/docs/use_case/planning_control.ja.md b/docs/use_case/planning_control.ja.md index 3feee473..0542a943 100644 --- a/docs/use_case/planning_control.ja.md +++ b/docs/use_case/planning_control.ja.md @@ -31,9 +31,9 @@ kinematic_conditionを指定した場合は追加で、kinematic_stateが条件 Subscribed topics: -| Topic name | Data type | -| -------------------------------------- | ------------------------------------- | -| /control/control_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | +| Topic name | Data type | +| ------------------------------------ | ------------------------------------- | +| /control/control_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | | /planning/planning_evaluator/metrics | diagnostic_msgs::msg::DiagnosticArray | Published topics: