diff --git a/system/mrm_handler/CMakeLists.txt b/system/mrm_handler/CMakeLists.txt new file mode 100644 index 0000000000000..7c2174f03a6f3 --- /dev/null +++ b/system/mrm_handler/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 3.14) +project(mrm_handler) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_executable(mrm_handler + src/mrm_handler/mrm_handler_node.cpp + src/mrm_handler/mrm_handler_core.cpp +) + +ament_auto_package(INSTALL_TO_SHARE + launch + config +) diff --git a/system/mrm_handler/README.md b/system/mrm_handler/README.md new file mode 100644 index 0000000000000..4944d8a833643 --- /dev/null +++ b/system/mrm_handler/README.md @@ -0,0 +1,44 @@ +# mrm_handler + +## Purpose + +MRM Handler is a node to select a proper MRM from a system failure state contained in OperationModeAvailability. + +## Inner-workings / Algorithms + +### State Transitions + + + +## Inputs / Outputs + +### Input + +| Name | Type | Description | +| -------------------------------------- | ---------------------------------------------------- | --------------------------------------------------------------------------------------------------- | +| `/localization/kinematic_state` | `nav_msgs::msg::Odometry` | Used to decide whether vehicle is stopped or not | +| `/system/operation_mode/availability` | `tier4_system_msgs::msg::OperationModeAvailability` | Used to select proper MRM from system available mrm behavior contained in operationModeAvailability | +| `/vehicle/status/control_mode` | `autoware_auto_vehicle_msgs::msg::ControlModeReport` | Used to check vehicle mode: autonomous or manual | +| `/system/mrm/emergency_stop/status` | `tier4_system_msgs::msg::MrmBehaviorStatus` | Used to check if MRM emergency stop operation is available | +| `/system/mrm/comfortable_stop/status` | `tier4_system_msgs::msg::MrmBehaviorStatus` | Used to check if MRM comfortable stop operation is available | +| `/system/mrm/pull_over_manager/status` | `tier4_system_msgs::msg::MrmBehaviorStatus` | Used to check if MRM pull over operation is available | +| `/api/operation_mode/state` | `autoware_adapi_v1_msgs::msg::OperationModeState` | Used to check whether the current operation mode is AUTO or STOP. | + +### Output + +| Name | Type | Description | +| --------------------------------------- | ------------------------------------------------------ | ----------------------------------------------------- | +| `/system/emergency/gear_cmd` | `autoware_auto_vehicle_msgs::msg::GearCommand` | Required to execute proper MRM (send gear cmd) | +| `/system/emergency/hazard_lights_cmd` | `autoware_auto_vehicle_msgs::msg::HazardLightsCommand` | Required to execute proper MRM (send turn signal cmd) | +| `/system/fail_safe/mrm_state` | `autoware_adapi_v1_msgs::msg::MrmState` | Inform MRM execution state and selected MRM behavior | +| `/system/mrm/emergency_stop/operate` | `tier4_system_msgs::srv::OperateMrm` | Execution order for MRM emergency stop | +| `/system/mrm/comfortable_stop/operate` | `tier4_system_msgs::srv::OperateMrm` | Execution order for MRM comfortable stop | +| `/system/mrm/pull_over_manager/operate` | `tier4_system_msgs::srv::OperateMrm` | Execution order for MRM pull over | + +## Parameters + +{{ json_to_markdown("system/mrm_handler/schema/mrm_handler.schema.json") }} + +## Assumptions / Known limits + +TBD. diff --git a/system/mrm_handler/config/mrm_handler.param.yaml b/system/mrm_handler/config/mrm_handler.param.yaml new file mode 100644 index 0000000000000..292d459f69d88 --- /dev/null +++ b/system/mrm_handler/config/mrm_handler.param.yaml @@ -0,0 +1,17 @@ +# Default configuration for mrm handler +--- +/**: + ros__parameters: + update_rate: 10 + timeout_operation_mode_availability: 0.5 + use_emergency_holding: false + timeout_emergency_recovery: 5.0 + timeout_takeover_request: 10.0 + use_takeover_request: false + use_parking_after_stopped: false + use_pull_over: false + use_comfortable_stop: false + + # setting whether to turn hazard lamp on for each situation + turning_hazard_on: + emergency: true diff --git a/system/mrm_handler/image/mrm-state.svg b/system/mrm_handler/image/mrm-state.svg new file mode 100644 index 0000000000000..13a2956b6f15c --- /dev/null +++ b/system/mrm_handler/image/mrm-state.svg @@ -0,0 +1,362 @@ +<?xml version="1.0" encoding="UTF-8"?> +<!-- Do not edit this file with editors other than draw.io --> +<!DOCTYPE svg PUBLIC "-//W3C//DTD SVG 1.1//EN" "http://www.w3.org/Graphics/SVG/1.1/DTD/svg11.dtd"> +<svg + xmlns="http://www.w3.org/2000/svg" + xmlns:xlink="http://www.w3.org/1999/xlink" + version="1.1" + width="958px" + height="341px" + viewBox="-0.5 -0.5 958 341" + content="<mxfile host="app.diagrams.net" modified="2024-02-07T09:48:58.193Z" agent="Mozilla/5.0 (X11; Linux x86_64) AppleWebKit/537.36 (KHTML, like Gecko) Chrome/118.0.0.0 Safari/537.36" etag="JzfBIbSx-UshJtjtpS4o" version="23.1.1" type="device"> <diagram id="C5RBs43oDa-KdzZeNtuy" name="Page-1"> <mxGraphModel dx="1364" dy="771" grid="1" gridSize="10" guides="1" tooltips="1" connect="1" arrows="1" fold="1" page="1" pageScale="1" pageWidth="1169" pageHeight="827" math="0" shadow="0"> <root> <mxCell id="WIyWlLk6GJQsqaUBKTNV-0" /> <mxCell id="WIyWlLk6GJQsqaUBKTNV-1" parent="WIyWlLk6GJQsqaUBKTNV-0" /> <mxCell id="6FWRLcRsoSDiZ6vq709X-284" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;" edge="1" parent="WIyWlLk6GJQsqaUBKTNV-1" source="6FWRLcRsoSDiZ6vq709X-281" target="6FWRLcRsoSDiZ6vq709X-3"> <mxGeometry relative="1" as="geometry"> <Array as="points"> <mxPoint x="230" y="360" /> <mxPoint x="230" y="360" /> </Array> </mxGeometry> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-285" value="not emergency" style="edgeLabel;html=1;align=center;verticalAlign=middle;resizable=0;points=[];" vertex="1" connectable="0" parent="6FWRLcRsoSDiZ6vq709X-284"> <mxGeometry x="0.02" relative="1" as="geometry"> <mxPoint x="1" y="-10" as="offset" /> </mxGeometry> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-281" value="" style="rounded=0;whiteSpace=wrap;html=1;" vertex="1" parent="WIyWlLk6GJQsqaUBKTNV-1"> <mxGeometry x="280" y="140" width="720" height="340" as="geometry" /> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-4" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=1;exitY=0.5;exitDx=0;exitDy=0;entryX=0;entryY=0.5;entryDx=0;entryDy=0;" edge="1" parent="WIyWlLk6GJQsqaUBKTNV-1" source="6FWRLcRsoSDiZ6vq709X-2" target="6FWRLcRsoSDiZ6vq709X-3"> <mxGeometry relative="1" as="geometry" /> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-2" value="" style="ellipse;whiteSpace=wrap;html=1;fillColor=#000000;" vertex="1" parent="WIyWlLk6GJQsqaUBKTNV-1"> <mxGeometry x="50" y="305" width="30" height="30" as="geometry" /> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-19" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=1;exitY=0.25;exitDx=0;exitDy=0;" edge="1" parent="WIyWlLk6GJQsqaUBKTNV-1" source="6FWRLcRsoSDiZ6vq709X-3" target="6FWRLcRsoSDiZ6vq709X-281"> <mxGeometry relative="1" as="geometry"> <mxPoint x="270" y="290" as="targetPoint" /> <Array as="points"> <mxPoint x="260" y="290" /> <mxPoint x="260" y="290" /> </Array> </mxGeometry> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-21" value="emergency" style="edgeLabel;html=1;align=center;verticalAlign=middle;resizable=0;points=[];" vertex="1" connectable="0" parent="6FWRLcRsoSDiZ6vq709X-19"> <mxGeometry x="-0.0719" y="-3" relative="1" as="geometry"> <mxPoint y="-13" as="offset" /> </mxGeometry> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-3" value="&lt;b&gt;NORMAL&lt;/b&gt;" style="rounded=0;whiteSpace=wrap;html=1;" vertex="1" parent="WIyWlLk6GJQsqaUBKTNV-1"> <mxGeometry x="120" y="260" width="60" height="120" as="geometry" /> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-274" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;" edge="1" parent="WIyWlLk6GJQsqaUBKTNV-1" source="6FWRLcRsoSDiZ6vq709X-5" target="6FWRLcRsoSDiZ6vq709X-272"> <mxGeometry relative="1" as="geometry"> <Array as="points"> <mxPoint x="810" y="260" /> <mxPoint x="810" y="260" /> </Array> </mxGeometry> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-275" value="succeeded" style="edgeLabel;html=1;align=center;verticalAlign=middle;resizable=0;points=[];" vertex="1" connectable="0" parent="6FWRLcRsoSDiZ6vq709X-274"> <mxGeometry x="-0.0667" y="-3" relative="1" as="geometry"> <mxPoint y="-13" as="offset" /> </mxGeometry> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-278" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;" edge="1" parent="WIyWlLk6GJQsqaUBKTNV-1" source="6FWRLcRsoSDiZ6vq709X-5" target="6FWRLcRsoSDiZ6vq709X-273"> <mxGeometry relative="1" as="geometry"> <Array as="points"> <mxPoint x="810" y="400" /> <mxPoint x="810" y="400" /> </Array> </mxGeometry> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-279" value="failed" style="edgeLabel;html=1;align=center;verticalAlign=middle;resizable=0;points=[];" vertex="1" connectable="0" parent="6FWRLcRsoSDiZ6vq709X-278"> <mxGeometry x="0.2222" y="-3" relative="1" as="geometry"> <mxPoint x="-15" y="-13" as="offset" /> </mxGeometry> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-5" value="MRM_OPERATING" style="swimlane;whiteSpace=wrap;html=1;gradientColor=none;swimlaneFillColor=default;fillColor=default;" vertex="1" parent="WIyWlLk6GJQsqaUBKTNV-1"> <mxGeometry x="310" y="160" width="460" height="300" as="geometry" /> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-23" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=1;exitY=0.5;exitDx=0;exitDy=0;entryX=0;entryY=0.5;entryDx=0;entryDy=0;" edge="1" parent="6FWRLcRsoSDiZ6vq709X-5" source="6FWRLcRsoSDiZ6vq709X-12" target="6FWRLcRsoSDiZ6vq709X-14"> <mxGeometry relative="1" as="geometry" /> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-31" value="pull over unavailable&lt;br&gt;comfortable_stop available (ca)" style="edgeLabel;html=1;align=center;verticalAlign=middle;resizable=0;points=[];" vertex="1" connectable="0" parent="6FWRLcRsoSDiZ6vq709X-23"> <mxGeometry x="-0.12" y="-1" relative="1" as="geometry"> <mxPoint x="9" y="-24" as="offset" /> </mxGeometry> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-24" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;entryX=0;entryY=0.5;entryDx=0;entryDy=0;" edge="1" parent="6FWRLcRsoSDiZ6vq709X-5" source="6FWRLcRsoSDiZ6vq709X-12" target="6FWRLcRsoSDiZ6vq709X-13"> <mxGeometry relative="1" as="geometry"> <Array as="points"> <mxPoint x="35" y="80" /> </Array> </mxGeometry> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-26" value="pull over available (pa)" style="edgeLabel;html=1;align=center;verticalAlign=middle;resizable=0;points=[];" vertex="1" connectable="0" parent="6FWRLcRsoSDiZ6vq709X-24"> <mxGeometry x="0.1529" y="-1" relative="1" as="geometry"> <mxPoint x="13" y="-11" as="offset" /> </mxGeometry> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-25" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;" edge="1" parent="6FWRLcRsoSDiZ6vq709X-5" source="6FWRLcRsoSDiZ6vq709X-12" target="6FWRLcRsoSDiZ6vq709X-17"> <mxGeometry relative="1" as="geometry"> <Array as="points"> <mxPoint x="35" y="240" /> </Array> </mxGeometry> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-33" value="pull over unavailable&lt;br style=&quot;border-color: var(--border-color);&quot;&gt;comfortable_stop unavailable&lt;br&gt;emergency_stop available (ea)" style="edgeLabel;html=1;align=center;verticalAlign=middle;resizable=0;points=[];" vertex="1" connectable="0" parent="6FWRLcRsoSDiZ6vq709X-25"> <mxGeometry x="0.3217" relative="1" as="geometry"> <mxPoint x="-4" y="-26" as="offset" /> </mxGeometry> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-12" value="" style="ellipse;whiteSpace=wrap;html=1;fillColor=#000000;" vertex="1" parent="6FWRLcRsoSDiZ6vq709X-5"> <mxGeometry x="20" y="143.75" width="30" height="30" as="geometry" /> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-27" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=0.5;exitY=1;exitDx=0;exitDy=0;" edge="1" parent="6FWRLcRsoSDiZ6vq709X-5" source="6FWRLcRsoSDiZ6vq709X-13" target="6FWRLcRsoSDiZ6vq709X-14"> <mxGeometry relative="1" as="geometry" /> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-30" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;" edge="1" parent="6FWRLcRsoSDiZ6vq709X-5" source="6FWRLcRsoSDiZ6vq709X-13" target="6FWRLcRsoSDiZ6vq709X-17"> <mxGeometry relative="1" as="geometry"> <Array as="points"> <mxPoint x="420" y="80" /> <mxPoint x="420" y="240" /> </Array> </mxGeometry> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-13" value="pull_over" style="rounded=1;whiteSpace=wrap;html=1;" vertex="1" parent="6FWRLcRsoSDiZ6vq709X-5"> <mxGeometry x="240" y="60" width="150" height="40" as="geometry" /> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-28" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=0.5;exitY=1;exitDx=0;exitDy=0;" edge="1" parent="6FWRLcRsoSDiZ6vq709X-5" source="6FWRLcRsoSDiZ6vq709X-14" target="6FWRLcRsoSDiZ6vq709X-17"> <mxGeometry relative="1" as="geometry" /> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-152" value="ea" style="edgeLabel;html=1;align=center;verticalAlign=middle;resizable=0;points=[];" vertex="1" connectable="0" parent="6FWRLcRsoSDiZ6vq709X-28"> <mxGeometry x="-0.1294" y="-1" relative="1" as="geometry"> <mxPoint x="9" as="offset" /> </mxGeometry> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-156" value="ea" style="edgeLabel;html=1;align=center;verticalAlign=middle;resizable=0;points=[];" vertex="1" connectable="0" parent="6FWRLcRsoSDiZ6vq709X-28"> <mxGeometry x="-0.1294" y="-1" relative="1" as="geometry"> <mxPoint x="116" y="-36" as="offset" /> </mxGeometry> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-15" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=0.5;exitY=1;exitDx=0;exitDy=0;" edge="1" parent="6FWRLcRsoSDiZ6vq709X-5" source="6FWRLcRsoSDiZ6vq709X-13" target="6FWRLcRsoSDiZ6vq709X-13"> <mxGeometry relative="1" as="geometry" /> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-17" value="emergency_stop" style="rounded=1;whiteSpace=wrap;html=1;" vertex="1" parent="6FWRLcRsoSDiZ6vq709X-5"> <mxGeometry x="240" y="220" width="150" height="37.5" as="geometry" /> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-32" value="" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;" edge="1" parent="6FWRLcRsoSDiZ6vq709X-5" source="6FWRLcRsoSDiZ6vq709X-13" target="6FWRLcRsoSDiZ6vq709X-14"> <mxGeometry relative="1" as="geometry"> <mxPoint x="585" y="260" as="sourcePoint" /> <mxPoint x="585" y="380" as="targetPoint" /> <Array as="points" /> </mxGeometry> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-150" value="ca" style="edgeLabel;html=1;align=center;verticalAlign=middle;resizable=0;points=[];" vertex="1" connectable="0" parent="6FWRLcRsoSDiZ6vq709X-32"> <mxGeometry x="-0.1" y="1" relative="1" as="geometry"> <mxPoint x="7" as="offset" /> </mxGeometry> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-14" value="comfortable_stop" style="rounded=1;whiteSpace=wrap;html=1;" vertex="1" parent="6FWRLcRsoSDiZ6vq709X-5"> <mxGeometry x="240" y="140" width="150" height="37.5" as="geometry" /> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-18" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;exitX=0;exitY=0.5;exitDx=0;exitDy=0;entryX=0;entryY=1;entryDx=0;entryDy=0;" edge="1" parent="WIyWlLk6GJQsqaUBKTNV-1" source="6FWRLcRsoSDiZ6vq709X-2" target="6FWRLcRsoSDiZ6vq709X-2"> <mxGeometry relative="1" as="geometry" /> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-276" style="edgeStyle=orthogonalEdgeStyle;rounded=0;orthogonalLoop=1;jettySize=auto;html=1;" edge="1" parent="WIyWlLk6GJQsqaUBKTNV-1" source="6FWRLcRsoSDiZ6vq709X-272" target="6FWRLcRsoSDiZ6vq709X-5"> <mxGeometry relative="1" as="geometry"> <Array as="points"> <mxPoint x="780" y="220" /> <mxPoint x="780" y="220" /> </Array> </mxGeometry> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-277" value="pa" style="edgeLabel;html=1;align=center;verticalAlign=middle;resizable=0;points=[];" vertex="1" connectable="0" parent="6FWRLcRsoSDiZ6vq709X-276"> <mxGeometry x="-0.1556" y="-2" relative="1" as="geometry"> <mxPoint x="-6" y="-8" as="offset" /> </mxGeometry> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-272" value="&lt;b&gt;MRM_SUCCEEDED&lt;/b&gt;" style="rounded=0;whiteSpace=wrap;html=1;" vertex="1" parent="WIyWlLk6GJQsqaUBKTNV-1"> <mxGeometry x="850" y="200" width="130" height="80" as="geometry" /> </mxCell> <mxCell id="6FWRLcRsoSDiZ6vq709X-273" value="&lt;b&gt;MRM_FAILED&lt;/b&gt;" style="rounded=0;whiteSpace=wrap;html=1;" vertex="1" parent="WIyWlLk6GJQsqaUBKTNV-1"> <mxGeometry x="850" y="350" width="130" height="80" as="geometry" /> </mxCell> </root> </mxGraphModel> </diagram> </mxfile> " +> + <defs/> + <g> + <path d="M 237 220 L 187 220 L 143.37 220" fill="none" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="stroke"/> + <path d="M 138.12 220 L 145.12 216.5 L 143.37 220 L 145.12 223.5 Z" fill="rgb(0, 0, 0)" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="all"/> + <g transform="translate(-0.5 -0.5)"> + <switch> + <foreignObject pointer-events="none" width="100%" height="100%" requiredFeatures="http://www.w3.org/TR/SVG11/feature#Extensibility" style="overflow: visible; text-align: left;"> + <div xmlns="http://www.w3.org/1999/xhtml" style="display: flex; align-items: unsafe center; justify-content: unsafe center; width: 1px; height: 1px; padding-top: 211px; margin-left: 188px;"> + <div data-drawio-colors="color: rgb(0, 0, 0); background-color: rgb(255, 255, 255); " style="box-sizing: border-box; font-size: 0px; text-align: center;"> + <div + style="display: inline-block; font-size: 11px; font-family: Helvetica; color: rgb(0, 0, 0); line-height: 1.2; pointer-events: all; background-color: rgb(255, 255, 255); white-space: nowrap;" + > + not emergency + </div> + </div> + </div> + </foreignObject> + <text x="188" y="214" fill="rgb(0, 0, 0)" font-family="Helvetica" font-size="11px" text-anchor="middle">not emergency</text> + </switch> + </g> + <rect x="237" y="0" width="720" height="340" fill="rgb(255, 255, 255)" stroke="rgb(0, 0, 0)" pointer-events="all"/> + <path d="M 37 180 L 70.63 180" fill="none" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="stroke"/> + <path d="M 75.88 180 L 68.88 183.5 L 70.63 180 L 68.88 176.5 Z" fill="rgb(0, 0, 0)" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="all"/> + <ellipse cx="22" cy="180" rx="15" ry="15" fill="#000000" stroke="rgb(0, 0, 0)" pointer-events="all"/> + <path d="M 137 150 L 217 150 L 230.63 150" fill="none" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="stroke"/> + <path d="M 235.88 150 L 228.88 153.5 L 230.63 150 L 228.88 146.5 Z" fill="rgb(0, 0, 0)" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="all"/> + <g transform="translate(-0.5 -0.5)"> + <switch> + <foreignObject pointer-events="none" width="100%" height="100%" requiredFeatures="http://www.w3.org/TR/SVG11/feature#Extensibility" style="overflow: visible; text-align: left;"> + <div xmlns="http://www.w3.org/1999/xhtml" style="display: flex; align-items: unsafe center; justify-content: unsafe center; width: 1px; height: 1px; padding-top: 141px; margin-left: 184px;"> + <div data-drawio-colors="color: rgb(0, 0, 0); background-color: rgb(255, 255, 255); " style="box-sizing: border-box; font-size: 0px; text-align: center;"> + <div + style="display: inline-block; font-size: 11px; font-family: Helvetica; color: rgb(0, 0, 0); line-height: 1.2; pointer-events: all; background-color: rgb(255, 255, 255); white-space: nowrap;" + > + emergency + </div> + </div> + </div> + </foreignObject> + <text x="184" y="144" fill="rgb(0, 0, 0)" font-family="Helvetica" font-size="11px" text-anchor="middle">emergency</text> + </switch> + </g> + <rect x="77" y="120" width="60" height="120" fill="rgb(255, 255, 255)" stroke="rgb(0, 0, 0)" pointer-events="all"/> + <g transform="translate(-0.5 -0.5)"> + <switch> + <foreignObject pointer-events="none" width="100%" height="100%" requiredFeatures="http://www.w3.org/TR/SVG11/feature#Extensibility" style="overflow: visible; text-align: left;"> + <div xmlns="http://www.w3.org/1999/xhtml" style="display: flex; align-items: unsafe center; justify-content: unsafe center; width: 58px; height: 1px; padding-top: 180px; margin-left: 78px;"> + <div data-drawio-colors="color: rgb(0, 0, 0); " style="box-sizing: border-box; font-size: 0px; text-align: center;"> + <div style="display: inline-block; font-size: 12px; font-family: Helvetica; color: rgb(0, 0, 0); line-height: 1.2; pointer-events: all; white-space: normal; overflow-wrap: normal;"> + <b>NORMAL</b> + </div> + </div> + </div> + </foreignObject> + <text x="107" y="184" fill="rgb(0, 0, 0)" font-family="Helvetica" font-size="12px" text-anchor="middle">NORMAL</text> + </switch> + </g> + <path d="M 727 120 L 767 120 L 800.63 120" fill="none" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="stroke"/> + <path d="M 805.88 120 L 798.88 123.5 L 800.63 120 L 798.88 116.5 Z" fill="rgb(0, 0, 0)" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="all"/> + <g transform="translate(-0.5 -0.5)"> + <switch> + <foreignObject pointer-events="none" width="100%" height="100%" requiredFeatures="http://www.w3.org/TR/SVG11/feature#Extensibility" style="overflow: visible; text-align: left;"> + <div xmlns="http://www.w3.org/1999/xhtml" style="display: flex; align-items: unsafe center; justify-content: unsafe center; width: 1px; height: 1px; padding-top: 111px; margin-left: 765px;"> + <div data-drawio-colors="color: rgb(0, 0, 0); background-color: rgb(255, 255, 255); " style="box-sizing: border-box; font-size: 0px; text-align: center;"> + <div + style="display: inline-block; font-size: 11px; font-family: Helvetica; color: rgb(0, 0, 0); line-height: 1.2; pointer-events: all; background-color: rgb(255, 255, 255); white-space: nowrap;" + > + succeeded + </div> + </div> + </div> + </foreignObject> + <text x="765" y="114" fill="rgb(0, 0, 0)" font-family="Helvetica" font-size="11px" text-anchor="middle">succeeded</text> + </switch> + </g> + <path d="M 727 260 L 767 260 L 800.63 260" fill="none" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="stroke"/> + <path d="M 805.88 260 L 798.88 263.5 L 800.63 260 L 798.88 256.5 Z" fill="rgb(0, 0, 0)" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="all"/> + <g transform="translate(-0.5 -0.5)"> + <switch> + <foreignObject pointer-events="none" width="100%" height="100%" requiredFeatures="http://www.w3.org/TR/SVG11/feature#Extensibility" style="overflow: visible; text-align: left;"> + <div xmlns="http://www.w3.org/1999/xhtml" style="display: flex; align-items: unsafe center; justify-content: unsafe center; width: 1px; height: 1px; padding-top: 251px; margin-left: 762px;"> + <div data-drawio-colors="color: rgb(0, 0, 0); background-color: rgb(255, 255, 255); " style="box-sizing: border-box; font-size: 0px; text-align: center;"> + <div + style="display: inline-block; font-size: 11px; font-family: Helvetica; color: rgb(0, 0, 0); line-height: 1.2; pointer-events: all; background-color: rgb(255, 255, 255); white-space: nowrap;" + > + failed + </div> + </div> + </div> + </foreignObject> + <text x="762" y="254" fill="rgb(0, 0, 0)" font-family="Helvetica" font-size="11px" text-anchor="middle">failed</text> + </switch> + </g> + <path d="M 267 43 L 267 20 L 727 20 L 727 43" fill="rgb(255, 255, 255)" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="all"/> + <path d="M 267 43 L 267 320 L 727 320 L 727 43" fill="rgb(255, 255, 255)" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="all"/> + <path d="M 267 43 L 727 43" fill="none" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="all"/> + <g transform="translate(-0.5 -0.5)"> + <switch> + <foreignObject pointer-events="none" width="100%" height="100%" requiredFeatures="http://www.w3.org/TR/SVG11/feature#Extensibility" style="overflow: visible; text-align: left;"> + <div + xmlns="http://www.w3.org/1999/xhtml" + style="display: flex; align-items: unsafe center; justify-content: unsafe center; width: 458px; height: 1px; padding-top: 32px; margin-left: 268px;" + > + <div data-drawio-colors="color: rgb(0, 0, 0); " style="box-sizing: border-box; font-size: 0px; text-align: center;"> + <div + style="display: inline-block; font-size: 12px; font-family: Helvetica; color: rgb(0, 0, 0); line-height: 1.2; pointer-events: all; font-weight: bold; white-space: normal; overflow-wrap: normal;" + > + MRM_OPERATING + </div> + </div> + </div> + </foreignObject> + <text x="497" y="35" fill="rgb(0, 0, 0)" font-family="Helvetica" font-size="12px" text-anchor="middle" font-weight="bold">MRM_OPERATING</text> + </switch> + </g> + <path d="M 317 178.75 L 500.63 178.75" fill="none" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="stroke"/> + <path d="M 505.88 178.75 L 498.88 182.25 L 500.63 178.75 L 498.88 175.25 Z" fill="rgb(0, 0, 0)" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="all"/> + <g transform="translate(-0.5 -0.5)"> + <switch> + <foreignObject pointer-events="none" width="100%" height="100%" requiredFeatures="http://www.w3.org/TR/SVG11/feature#Extensibility" style="overflow: visible; text-align: left;"> + <div xmlns="http://www.w3.org/1999/xhtml" style="display: flex; align-items: unsafe center; justify-content: unsafe center; width: 1px; height: 1px; padding-top: 156px; margin-left: 411px;"> + <div data-drawio-colors="color: rgb(0, 0, 0); background-color: rgb(255, 255, 255); " style="box-sizing: border-box; font-size: 0px; text-align: center;"> + <div + style="display: inline-block; font-size: 11px; font-family: Helvetica; color: rgb(0, 0, 0); line-height: 1.2; pointer-events: all; background-color: rgb(255, 255, 255); white-space: nowrap;" + > + pull over unavailable + <br/> + comfortable_stop available (ca) + </div> + </div> + </div> + </foreignObject> + <text x="411" y="160" fill="rgb(0, 0, 0)" font-family="Helvetica" font-size="11px" text-anchor="middle">pull over unavailable...</text> + </switch> + </g> + <path d="M 302 163.75 L 302 100 L 500.63 100" fill="none" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="stroke"/> + <path d="M 505.88 100 L 498.88 103.5 L 500.63 100 L 498.88 96.5 Z" fill="rgb(0, 0, 0)" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="all"/> + <g transform="translate(-0.5 -0.5)"> + <switch> + <foreignObject pointer-events="none" width="100%" height="100%" requiredFeatures="http://www.w3.org/TR/SVG11/feature#Extensibility" style="overflow: visible; text-align: left;"> + <div xmlns="http://www.w3.org/1999/xhtml" style="display: flex; align-items: unsafe center; justify-content: unsafe center; width: 1px; height: 1px; padding-top: 91px; margin-left: 407px;"> + <div data-drawio-colors="color: rgb(0, 0, 0); background-color: rgb(255, 255, 255); " style="box-sizing: border-box; font-size: 0px; text-align: center;"> + <div + style="display: inline-block; font-size: 11px; font-family: Helvetica; color: rgb(0, 0, 0); line-height: 1.2; pointer-events: all; background-color: rgb(255, 255, 255); white-space: nowrap;" + > + pull over available (pa) + </div> + </div> + </div> + </foreignObject> + <text x="407" y="94" fill="rgb(0, 0, 0)" font-family="Helvetica" font-size="11px" text-anchor="middle">pull over available (pa)</text> + </switch> + </g> + <path d="M 302 193.75 L 302 260 L 500.63 260" fill="none" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="stroke"/> + <path d="M 505.88 260 L 498.88 263.5 L 500.63 260 L 498.88 256.5 Z" fill="rgb(0, 0, 0)" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="all"/> + <g transform="translate(-0.5 -0.5)"> + <switch> + <foreignObject pointer-events="none" width="100%" height="100%" requiredFeatures="http://www.w3.org/TR/SVG11/feature#Extensibility" style="overflow: visible; text-align: left;"> + <div xmlns="http://www.w3.org/1999/xhtml" style="display: flex; align-items: unsafe center; justify-content: unsafe center; width: 1px; height: 1px; padding-top: 235px; margin-left: 411px;"> + <div data-drawio-colors="color: rgb(0, 0, 0); background-color: rgb(255, 255, 255); " style="box-sizing: border-box; font-size: 0px; text-align: center;"> + <div + style="display: inline-block; font-size: 11px; font-family: Helvetica; color: rgb(0, 0, 0); line-height: 1.2; pointer-events: all; background-color: rgb(255, 255, 255); white-space: nowrap;" + > + pull over unavailable + <br style="border-color: var(--border-color);"/> + comfortable_stop unavailable + <br/> + emergency_stop available (ea) + </div> + </div> + </div> + </foreignObject> + <text x="411" y="238" fill="rgb(0, 0, 0)" font-family="Helvetica" font-size="11px" text-anchor="middle">pull over unavailable...</text> + </switch> + </g> + <ellipse cx="302" cy="178.75" rx="15" ry="15" fill="#000000" stroke="rgb(0, 0, 0)" pointer-events="all"/> + <path d="M 582 120 L 582 153.63" fill="none" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="stroke"/> + <path d="M 582 158.88 L 578.5 151.88 L 582 153.63 L 585.5 151.88 Z" fill="rgb(0, 0, 0)" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="all"/> + <path d="M 657 100 L 687 100 L 687 260 L 663.37 260" fill="none" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="stroke"/> + <path d="M 658.12 260 L 665.12 256.5 L 663.37 260 L 665.12 263.5 Z" fill="rgb(0, 0, 0)" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="all"/> + <rect x="507" y="80" width="150" height="40" rx="6" ry="6" fill="rgb(255, 255, 255)" stroke="rgb(0, 0, 0)" pointer-events="all"/> + <g transform="translate(-0.5 -0.5)"> + <switch> + <foreignObject pointer-events="none" width="100%" height="100%" requiredFeatures="http://www.w3.org/TR/SVG11/feature#Extensibility" style="overflow: visible; text-align: left;"> + <div + xmlns="http://www.w3.org/1999/xhtml" + style="display: flex; align-items: unsafe center; justify-content: unsafe center; width: 148px; height: 1px; padding-top: 100px; margin-left: 508px;" + > + <div data-drawio-colors="color: rgb(0, 0, 0); " style="box-sizing: border-box; font-size: 0px; text-align: center;"> + <div style="display: inline-block; font-size: 12px; font-family: Helvetica; color: rgb(0, 0, 0); line-height: 1.2; pointer-events: all; white-space: normal; overflow-wrap: normal;"> + pull_over + </div> + </div> + </div> + </foreignObject> + <text x="582" y="104" fill="rgb(0, 0, 0)" font-family="Helvetica" font-size="12px" text-anchor="middle">pull_over</text> + </switch> + </g> + <path d="M 582 197.5 L 582 233.63" fill="none" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="stroke"/> + <path d="M 582 238.88 L 578.5 231.88 L 582 233.63 L 585.5 231.88 Z" fill="rgb(0, 0, 0)" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="all"/> + <g transform="translate(-0.5 -0.5)"> + <switch> + <foreignObject pointer-events="none" width="100%" height="100%" requiredFeatures="http://www.w3.org/TR/SVG11/feature#Extensibility" style="overflow: visible; text-align: left;"> + <div xmlns="http://www.w3.org/1999/xhtml" style="display: flex; align-items: unsafe center; justify-content: unsafe center; width: 1px; height: 1px; padding-top: 217px; margin-left: 591px;"> + <div data-drawio-colors="color: rgb(0, 0, 0); background-color: rgb(255, 255, 255); " style="box-sizing: border-box; font-size: 0px; text-align: center;"> + <div + style="display: inline-block; font-size: 11px; font-family: Helvetica; color: rgb(0, 0, 0); line-height: 1.2; pointer-events: all; background-color: rgb(255, 255, 255); white-space: nowrap;" + > + ea + </div> + </div> + </div> + </foreignObject> + <text x="591" y="220" fill="rgb(0, 0, 0)" font-family="Helvetica" font-size="11px" text-anchor="middle">ea</text> + </switch> + </g> + <g transform="translate(-0.5 -0.5)"> + <switch> + <foreignObject pointer-events="none" width="100%" height="100%" requiredFeatures="http://www.w3.org/TR/SVG11/feature#Extensibility" style="overflow: visible; text-align: left;"> + <div xmlns="http://www.w3.org/1999/xhtml" style="display: flex; align-items: unsafe center; justify-content: unsafe center; width: 1px; height: 1px; padding-top: 181px; margin-left: 698px;"> + <div data-drawio-colors="color: rgb(0, 0, 0); background-color: rgb(255, 255, 255); " style="box-sizing: border-box; font-size: 0px; text-align: center;"> + <div + style="display: inline-block; font-size: 11px; font-family: Helvetica; color: rgb(0, 0, 0); line-height: 1.2; pointer-events: all; background-color: rgb(255, 255, 255); white-space: nowrap;" + > + ea + </div> + </div> + </div> + </foreignObject> + <text x="698" y="184" fill="rgb(0, 0, 0)" font-family="Helvetica" font-size="11px" text-anchor="middle">ea</text> + </switch> + </g> + <rect x="507" y="240" width="150" height="37.5" rx="5.63" ry="5.63" fill="rgb(255, 255, 255)" stroke="rgb(0, 0, 0)" pointer-events="all"/> + <g transform="translate(-0.5 -0.5)"> + <switch> + <foreignObject pointer-events="none" width="100%" height="100%" requiredFeatures="http://www.w3.org/TR/SVG11/feature#Extensibility" style="overflow: visible; text-align: left;"> + <div + xmlns="http://www.w3.org/1999/xhtml" + style="display: flex; align-items: unsafe center; justify-content: unsafe center; width: 148px; height: 1px; padding-top: 259px; margin-left: 508px;" + > + <div data-drawio-colors="color: rgb(0, 0, 0); " style="box-sizing: border-box; font-size: 0px; text-align: center;"> + <div style="display: inline-block; font-size: 12px; font-family: Helvetica; color: rgb(0, 0, 0); line-height: 1.2; pointer-events: all; white-space: normal; overflow-wrap: normal;"> + emergency_stop + </div> + </div> + </div> + </foreignObject> + <text x="582" y="262" fill="rgb(0, 0, 0)" font-family="Helvetica" font-size="12px" text-anchor="middle">emergency_stop</text> + </switch> + </g> + <path d="M 582 120 L 582 153.63" fill="none" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="stroke"/> + <path d="M 582 158.88 L 578.5 151.88 L 582 153.63 L 585.5 151.88 Z" fill="rgb(0, 0, 0)" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="all"/> + <g transform="translate(-0.5 -0.5)"> + <switch> + <foreignObject pointer-events="none" width="100%" height="100%" requiredFeatures="http://www.w3.org/TR/SVG11/feature#Extensibility" style="overflow: visible; text-align: left;"> + <div xmlns="http://www.w3.org/1999/xhtml" style="display: flex; align-items: unsafe center; justify-content: unsafe center; width: 1px; height: 1px; padding-top: 139px; margin-left: 591px;"> + <div data-drawio-colors="color: rgb(0, 0, 0); background-color: rgb(255, 255, 255); " style="box-sizing: border-box; font-size: 0px; text-align: center;"> + <div + style="display: inline-block; font-size: 11px; font-family: Helvetica; color: rgb(0, 0, 0); line-height: 1.2; pointer-events: all; background-color: rgb(255, 255, 255); white-space: nowrap;" + > + ca + </div> + </div> + </div> + </foreignObject> + <text x="591" y="142" fill="rgb(0, 0, 0)" font-family="Helvetica" font-size="11px" text-anchor="middle">ca</text> + </switch> + </g> + <rect x="507" y="160" width="150" height="37.5" rx="5.63" ry="5.63" fill="rgb(255, 255, 255)" stroke="rgb(0, 0, 0)" pointer-events="all"/> + <g transform="translate(-0.5 -0.5)"> + <switch> + <foreignObject pointer-events="none" width="100%" height="100%" requiredFeatures="http://www.w3.org/TR/SVG11/feature#Extensibility" style="overflow: visible; text-align: left;"> + <div + xmlns="http://www.w3.org/1999/xhtml" + style="display: flex; align-items: unsafe center; justify-content: unsafe center; width: 148px; height: 1px; padding-top: 179px; margin-left: 508px;" + > + <div data-drawio-colors="color: rgb(0, 0, 0); " style="box-sizing: border-box; font-size: 0px; text-align: center;"> + <div style="display: inline-block; font-size: 12px; font-family: Helvetica; color: rgb(0, 0, 0); line-height: 1.2; pointer-events: all; white-space: normal; overflow-wrap: normal;"> + comfortable_stop + </div> + </div> + </div> + </foreignObject> + <text x="582" y="182" fill="rgb(0, 0, 0)" font-family="Helvetica" font-size="12px" text-anchor="middle">comfortable_stop</text> + </switch> + </g> + <path d="M 7 180 L 11.4 180 L 11.4 184.24" fill="none" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="stroke"/> + <path d="M 11.39 189.49 L 7.9 182.49 L 11.4 184.24 L 14.9 182.49 Z" fill="rgb(0, 0, 0)" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="all"/> + <path d="M 807 80 L 737 80 L 733.37 80" fill="none" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="stroke"/> + <path d="M 728.12 80 L 735.12 76.5 L 733.37 80 L 735.12 83.5 Z" fill="rgb(0, 0, 0)" stroke="rgb(0, 0, 0)" stroke-miterlimit="10" pointer-events="all"/> + <g transform="translate(-0.5 -0.5)"> + <switch> + <foreignObject pointer-events="none" width="100%" height="100%" requiredFeatures="http://www.w3.org/TR/SVG11/feature#Extensibility" style="overflow: visible; text-align: left;"> + <div xmlns="http://www.w3.org/1999/xhtml" style="display: flex; align-items: unsafe center; justify-content: unsafe center; width: 1px; height: 1px; padding-top: 71px; margin-left: 768px;"> + <div data-drawio-colors="color: rgb(0, 0, 0); background-color: rgb(255, 255, 255); " style="box-sizing: border-box; font-size: 0px; text-align: center;"> + <div + style="display: inline-block; font-size: 11px; font-family: Helvetica; color: rgb(0, 0, 0); line-height: 1.2; pointer-events: all; background-color: rgb(255, 255, 255); white-space: nowrap;" + > + pa + </div> + </div> + </div> + </foreignObject> + <text x="768" y="74" fill="rgb(0, 0, 0)" font-family="Helvetica" font-size="11px" text-anchor="middle">pa</text> + </switch> + </g> + <rect x="807" y="60" width="130" height="80" fill="rgb(255, 255, 255)" stroke="rgb(0, 0, 0)" pointer-events="all"/> + <g transform="translate(-0.5 -0.5)"> + <switch> + <foreignObject pointer-events="none" width="100%" height="100%" requiredFeatures="http://www.w3.org/TR/SVG11/feature#Extensibility" style="overflow: visible; text-align: left;"> + <div + xmlns="http://www.w3.org/1999/xhtml" + style="display: flex; align-items: unsafe center; justify-content: unsafe center; width: 128px; height: 1px; padding-top: 100px; margin-left: 808px;" + > + <div data-drawio-colors="color: rgb(0, 0, 0); " style="box-sizing: border-box; font-size: 0px; text-align: center;"> + <div style="display: inline-block; font-size: 12px; font-family: Helvetica; color: rgb(0, 0, 0); line-height: 1.2; pointer-events: all; white-space: normal; overflow-wrap: normal;"> + <b>MRM_SUCCEEDED</b> + </div> + </div> + </div> + </foreignObject> + <text x="872" y="104" fill="rgb(0, 0, 0)" font-family="Helvetica" font-size="12px" text-anchor="middle">MRM_SUCCEEDED</text> + </switch> + </g> + <rect x="807" y="210" width="130" height="80" fill="rgb(255, 255, 255)" stroke="rgb(0, 0, 0)" pointer-events="all"/> + <g transform="translate(-0.5 -0.5)"> + <switch> + <foreignObject pointer-events="none" width="100%" height="100%" requiredFeatures="http://www.w3.org/TR/SVG11/feature#Extensibility" style="overflow: visible; text-align: left;"> + <div + xmlns="http://www.w3.org/1999/xhtml" + style="display: flex; align-items: unsafe center; justify-content: unsafe center; width: 128px; height: 1px; padding-top: 250px; margin-left: 808px;" + > + <div data-drawio-colors="color: rgb(0, 0, 0); " style="box-sizing: border-box; font-size: 0px; text-align: center;"> + <div style="display: inline-block; font-size: 12px; font-family: Helvetica; color: rgb(0, 0, 0); line-height: 1.2; pointer-events: all; white-space: normal; overflow-wrap: normal;"> + <b>MRM_FAILED</b> + </div> + </div> + </div> + </foreignObject> + <text x="872" y="254" fill="rgb(0, 0, 0)" font-family="Helvetica" font-size="12px" text-anchor="middle">MRM_FAILED</text> + </switch> + </g> + </g> + <switch> + <g requiredFeatures="http://www.w3.org/TR/SVG11/feature#Extensibility"/> + <a transform="translate(0,-5)" xlink:href="https://www.drawio.com/doc/faq/svg-export-text-problems" target="_blank"> + <text text-anchor="middle" font-size="10px" x="50%" y="100%">Text is not SVG - cannot display</text> + </a> + </switch> +</svg> diff --git a/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp b/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp new file mode 100644 index 0000000000000..8a6ec81cbafff --- /dev/null +++ b/system/mrm_handler/include/mrm_handler/mrm_handler_core.hpp @@ -0,0 +1,160 @@ +// Copyright 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. + +#ifndef MRM_HANDLER__MRM_HANDLER_CORE_HPP_ +#define MRM_HANDLER__MRM_HANDLER_CORE_HPP_ + +// Core +#include <memory> +#include <optional> +#include <string> +#include <variant> + +// Autoware +#include <autoware_adapi_v1_msgs/msg/mrm_state.hpp> +#include <autoware_adapi_v1_msgs/msg/operation_mode_state.hpp> +#include <autoware_auto_vehicle_msgs/msg/control_mode_report.hpp> +#include <autoware_auto_vehicle_msgs/msg/gear_command.hpp> +#include <autoware_auto_vehicle_msgs/msg/hazard_lights_command.hpp> +#include <tier4_system_msgs/msg/mrm_behavior_status.hpp> +#include <tier4_system_msgs/msg/operation_mode_availability.hpp> +#include <tier4_system_msgs/srv/operate_mrm.hpp> + +// ROS 2 core +#include <rclcpp/create_timer.hpp> +#include <rclcpp/rclcpp.hpp> + +#include <diagnostic_msgs/msg/diagnostic_array.hpp> +#include <nav_msgs/msg/odometry.hpp> + +struct HazardLampPolicy +{ + bool emergency; +}; + +struct Param +{ + int update_rate; + double timeout_operation_mode_availability; + bool use_emergency_holding; + double timeout_emergency_recovery; + double timeout_takeover_request; + bool use_takeover_request; + bool use_parking_after_stopped; + bool use_pull_over; + bool use_comfortable_stop; + HazardLampPolicy turning_hazard_on{}; +}; + +class MrmHandler : public rclcpp::Node +{ +public: + MrmHandler(); + +private: + // Subscribers + rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_odom_; + rclcpp::Subscription<autoware_auto_vehicle_msgs::msg::ControlModeReport>::SharedPtr + sub_control_mode_; + rclcpp::Subscription<tier4_system_msgs::msg::OperationModeAvailability>::SharedPtr + sub_operation_mode_availability_; + rclcpp::Subscription<tier4_system_msgs::msg::MrmBehaviorStatus>::SharedPtr + sub_mrm_pull_over_status_; + rclcpp::Subscription<tier4_system_msgs::msg::MrmBehaviorStatus>::SharedPtr + sub_mrm_comfortable_stop_status_; + rclcpp::Subscription<tier4_system_msgs::msg::MrmBehaviorStatus>::SharedPtr + sub_mrm_emergency_stop_status_; + rclcpp::Subscription<autoware_adapi_v1_msgs::msg::OperationModeState>::SharedPtr + sub_operation_mode_state_; + + nav_msgs::msg::Odometry::ConstSharedPtr odom_; + autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr control_mode_; + tier4_system_msgs::msg::OperationModeAvailability::ConstSharedPtr operation_mode_availability_; + tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr mrm_pull_over_status_; + tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr mrm_comfortable_stop_status_; + tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr mrm_emergency_stop_status_; + autoware_adapi_v1_msgs::msg::OperationModeState::ConstSharedPtr operation_mode_state_; + + void onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg); + void onControlMode(const autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg); + void onOperationModeAvailability( + const tier4_system_msgs::msg::OperationModeAvailability::ConstSharedPtr msg); + void onMrmPullOverStatus(const tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr msg); + void onMrmComfortableStopStatus( + const tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr msg); + void onMrmEmergencyStopStatus( + const tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr msg); + void onOperationModeState( + const autoware_adapi_v1_msgs::msg::OperationModeState::ConstSharedPtr msg); + + // Publisher + + // rclcpp::Publisher<tier4_vehicle_msgs::msg::ShiftStamped>::SharedPtr pub_shift_; + // rclcpp::Publisher<tier4_vehicle_msgs::msg::TurnSignal>::SharedPtr pub_turn_signal_; + rclcpp::Publisher<autoware_auto_vehicle_msgs::msg::HazardLightsCommand>::SharedPtr + pub_hazard_cmd_; + rclcpp::Publisher<autoware_auto_vehicle_msgs::msg::GearCommand>::SharedPtr pub_gear_cmd_; + + autoware_auto_vehicle_msgs::msg::HazardLightsCommand createHazardCmdMsg(); + autoware_auto_vehicle_msgs::msg::GearCommand createGearCmdMsg(); + void publishControlCommands(); + + rclcpp::Publisher<autoware_adapi_v1_msgs::msg::MrmState>::SharedPtr pub_mrm_state_; + + autoware_adapi_v1_msgs::msg::MrmState mrm_state_; + void publishMrmState(); + + // Clients + rclcpp::CallbackGroup::SharedPtr client_mrm_pull_over_group_; + rclcpp::Client<tier4_system_msgs::srv::OperateMrm>::SharedPtr client_mrm_pull_over_; + rclcpp::CallbackGroup::SharedPtr client_mrm_comfortable_stop_group_; + rclcpp::Client<tier4_system_msgs::srv::OperateMrm>::SharedPtr client_mrm_comfortable_stop_; + rclcpp::CallbackGroup::SharedPtr client_mrm_emergency_stop_group_; + rclcpp::Client<tier4_system_msgs::srv::OperateMrm>::SharedPtr client_mrm_emergency_stop_; + + void callMrmBehavior( + const autoware_adapi_v1_msgs::msg::MrmState::_behavior_type & mrm_behavior) const; + void cancelMrmBehavior( + const autoware_adapi_v1_msgs::msg::MrmState::_behavior_type & mrm_behavior) const; + void logMrmCallingResult( + const tier4_system_msgs::srv::OperateMrm::Response & result, const std::string & behavior, + bool is_call) const; + + // Timer + rclcpp::TimerBase::SharedPtr timer_; + + // Parameters + Param param_; + + bool isDataReady(); + void onTimer(); + + // Heartbeat + rclcpp::Time stamp_operation_mode_availability_; + std::optional<rclcpp::Time> stamp_autonomous_become_unavailable_ = std::nullopt; + + // Algorithm + rclcpp::Time takeover_requested_time_; + bool is_takeover_request_ = false; + bool is_emergency_holding_ = false; + void transitionTo(const int new_state); + void updateMrmState(); + void operateMrm(); + autoware_adapi_v1_msgs::msg::MrmState::_behavior_type getCurrentMrmBehavior(); + bool isStopped(); + bool isEmergency() const; + bool isArrivedAtGoal(); +}; + +#endif // MRM_HANDLER__MRM_HANDLER_CORE_HPP_ diff --git a/system/mrm_handler/launch/mrm_handler.launch.xml b/system/mrm_handler/launch/mrm_handler.launch.xml new file mode 100644 index 0000000000000..562134f5301e2 --- /dev/null +++ b/system/mrm_handler/launch/mrm_handler.launch.xml @@ -0,0 +1,39 @@ +<launch> + <arg name="input_operation_mode_availability" default="/system/operation_mode/availability"/> + <!-- To be replaced by ControlCommand --> + <arg name="input_odometry" default="/localization/kinematic_state"/> + <arg name="input_control_mode" default="/vehicle/status/control_mode"/> + <arg name="input_mrm_pull_over_state" default="/system/mrm/pull_over_manager/status"/> + <arg name="input_mrm_comfortable_stop_state" default="/system/mrm/comfortable_stop/status"/> + <arg name="input_mrm_emergency_stop_state" default="/system/mrm/emergency_stop/status"/> + <arg name="input_api_operation_mode_state" default="/api/operation_mode/state"/> + + <arg name="output_gear" default="/system/emergency/gear_cmd"/> + <arg name="output_hazard" default="/system/emergency/hazard_lights_cmd"/> + <arg name="output_mrm_state" default="/system/fail_safe/mrm_state"/> + <arg name="output_mrm_pull_over_operate" default="/system/mrm/pull_over_manager/operate"/> + <arg name="output_mrm_comfortable_stop_operate" default="/system/mrm/comfortable_stop/operate"/> + <arg name="output_mrm_emergency_stop_operate" default="/system/mrm/emergency_stop/operate"/> + + <arg name="config_file" default="$(find-pkg-share mrm_handler)/config/mrm_handler.param.yaml"/> + + <!-- mrm_handler --> + <node pkg="mrm_handler" exec="mrm_handler" name="mrm_handler" output="screen"> + <remap from="~/input/operation_mode_availability" to="$(var input_operation_mode_availability)"/> + <remap from="~/input/odometry" to="$(var input_odometry)"/> + <remap from="~/input/control_mode" to="$(var input_control_mode)"/> + <remap from="~/input/mrm/pull_over/status" to="$(var input_mrm_pull_over_state)"/> + <remap from="~/input/mrm/comfortable_stop/status" to="$(var input_mrm_comfortable_stop_state)"/> + <remap from="~/input/mrm/emergency_stop/status" to="$(var input_mrm_emergency_stop_state)"/> + <remap from="~/input/api/operation_mode/state" to="$(var input_api_operation_mode_state)"/> + + <remap from="~/output/gear" to="$(var output_gear)"/> + <remap from="~/output/hazard" to="$(var output_hazard)"/> + <remap from="~/output/mrm/state" to="$(var output_mrm_state)"/> + <remap from="~/output/mrm/pull_over/operate" to="$(var output_mrm_pull_over_operate)"/> + <remap from="~/output/mrm/comfortable_stop/operate" to="$(var output_mrm_comfortable_stop_operate)"/> + <remap from="~/output/mrm/emergency_stop/operate" to="$(var output_mrm_emergency_stop_operate)"/> + + <param from="$(var config_file)"/> + </node> +</launch> diff --git a/system/mrm_handler/package.xml b/system/mrm_handler/package.xml new file mode 100644 index 0000000000000..e62091f2984e6 --- /dev/null +++ b/system/mrm_handler/package.xml @@ -0,0 +1,31 @@ +<?xml version="1.0"?> +<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?> +<package format="3"> + <name>mrm_handler</name> + <version>0.1.0</version> + <description>The mrm_handler ROS 2 package</description> + <maintainer email="makoto.kurihara@tier4.jp">Makoto Kurihara</maintainer> + <maintainer email="ryuta.kambe@tier4.jp">Ryuta Kambe</maintainer> + <maintainer email="tetsuhiro.kawaguchi@tier4.jp">Tetsuhiro Kawaguchi</maintainer> + <license>Apache License 2.0</license> + + <buildtool_depend>ament_cmake_auto</buildtool_depend> + <buildtool_depend>autoware_cmake</buildtool_depend> + + <depend>autoware_adapi_v1_msgs</depend> + <depend>autoware_auto_control_msgs</depend> + <depend>autoware_auto_system_msgs</depend> + <depend>autoware_auto_vehicle_msgs</depend> + <depend>nav_msgs</depend> + <depend>rclcpp</depend> + <depend>std_msgs</depend> + <depend>std_srvs</depend> + <depend>tier4_system_msgs</depend> + + <test_depend>ament_lint_auto</test_depend> + <test_depend>autoware_lint_common</test_depend> + + <export> + <build_type>ament_cmake</build_type> + </export> +</package> diff --git a/system/mrm_handler/schema/mrm_handler.schema.json b/system/mrm_handler/schema/mrm_handler.schema.json new file mode 100644 index 0000000000000..86b18449cb734 --- /dev/null +++ b/system/mrm_handler/schema/mrm_handler.schema.json @@ -0,0 +1,95 @@ +{ + "$schema": "http://json-schema.org/draft-07/schema#", + "title": "Parameters for mrm handler", + "type": "object", + "definitions": { + "mrm_handler": { + "type": "object", + "properties": { + "update_rate": { + "type": "integer", + "description": "Timer callback period.", + "default": 10 + }, + "timeout_operation_mode_availability": { + "type": "number", + "description": "If the input `operation_mode_availability` topic cannot be received for more than `timeout_operation_mode_availability`, vehicle will make an emergency stop.", + "default": 0.5 + }, + "use_emergency_holding": { + "type": "boolean", + "description": "If this parameter is true, the handler does not recover to the NORMAL state.", + "default": false + }, + "timeout_emergency_recovery": { + "type": "number", + "description": "If the duration of the EMERGENCY state is longer than `timeout_emergency_recovery`, it does not recover to the NORMAL state.", + "default": 5.0 + }, + "timeout_takeover_request": { + "type": "number", + "description": "Transition to MRR_OPERATING if the time from the last takeover request exceeds `timeout_takeover_request`.", + "default": 10.0 + }, + "use_takeover_request": { + "type": "boolean", + "description": "If this parameter is true, the handler will record the time and make take over request to the driver when emergency state occurs.", + "default": "false" + }, + "use_parking_after_stopped": { + "type": "boolean", + "description": "If this parameter is true, it will publish PARKING shift command.", + "default": "false" + }, + "use_pull_over": { + "type": "boolean", + "description": "If this parameter is true, operate pull over when latent faults occur.", + "default": "false" + }, + "use_comfortable_stop": { + "type": "boolean", + "description": "If this parameter is true, operate comfortable stop when latent faults occur.", + "default": "false" + }, + "turning_hazard_on": { + "type": "object", + "properties": { + "emergency": { + "type": "boolean", + "description": "If this parameter is true, hazard lamps will be turned on during emergency state.", + "default": "true" + } + }, + "required": ["emergency"] + } + }, + "required": [ + "update_rate", + "timeout_operation_mode_availability", + "use_emergency_holding", + "timeout_emergency_recovery", + "timeout_takeover_request", + "use_takeover_request", + "use_parking_after_stopped", + "use_pull_over", + "use_comfortable_stop", + "turning_hazard_on" + ], + "additionalProperties": false + } + }, + "properties": { + "/**": { + "type": "object", + "properties": { + "ros__parameters": { + "$ref": "#/definitions/mrm_handler" + } + }, + "required": ["ros__parameters"], + "additionalProperties": false + } + }, + "required": ["/**"], + "additionalProperties": false +} diff --git a/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp b/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp new file mode 100644 index 0000000000000..976f5b3164abd --- /dev/null +++ b/system/mrm_handler/src/mrm_handler/mrm_handler_core.cpp @@ -0,0 +1,587 @@ +// Copyright 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. + +#include "mrm_handler/mrm_handler_core.hpp" + +#include <chrono> +#include <memory> +#include <string> +#include <utility> + +MrmHandler::MrmHandler() : Node("mrm_handler") +{ + // Parameter + param_.update_rate = declare_parameter<int>("update_rate", 10); + param_.timeout_operation_mode_availability = + declare_parameter<double>("timeout_operation_mode_availability", 0.5); + param_.use_emergency_holding = declare_parameter<bool>("use_emergency_holding", false); + param_.timeout_emergency_recovery = declare_parameter<double>("timeout_emergency_recovery", 5.0); + param_.timeout_takeover_request = declare_parameter<double>("timeout_takeover_request", 10.0); + param_.use_takeover_request = declare_parameter<bool>("use_takeover_request", false); + param_.use_parking_after_stopped = declare_parameter<bool>("use_parking_after_stopped", false); + param_.use_pull_over = declare_parameter<bool>("use_pull_over", false); + param_.use_comfortable_stop = declare_parameter<bool>("use_comfortable_stop", false); + param_.turning_hazard_on.emergency = declare_parameter<bool>("turning_hazard_on.emergency", true); + + using std::placeholders::_1; + + // Subscriber + sub_odom_ = create_subscription<nav_msgs::msg::Odometry>( + "~/input/odometry", rclcpp::QoS{1}, std::bind(&MrmHandler::onOdometry, this, _1)); + // subscribe control mode + sub_control_mode_ = create_subscription<autoware_auto_vehicle_msgs::msg::ControlModeReport>( + "~/input/control_mode", rclcpp::QoS{1}, std::bind(&MrmHandler::onControlMode, this, _1)); + sub_operation_mode_availability_ = + create_subscription<tier4_system_msgs::msg::OperationModeAvailability>( + "~/input/operation_mode_availability", rclcpp::QoS{1}, + std::bind(&MrmHandler::onOperationModeAvailability, this, _1)); + sub_mrm_pull_over_status_ = create_subscription<tier4_system_msgs::msg::MrmBehaviorStatus>( + "~/input/mrm/pull_over/status", rclcpp::QoS{1}, + std::bind(&MrmHandler::onMrmPullOverStatus, this, _1)); + sub_mrm_comfortable_stop_status_ = create_subscription<tier4_system_msgs::msg::MrmBehaviorStatus>( + "~/input/mrm/comfortable_stop/status", rclcpp::QoS{1}, + std::bind(&MrmHandler::onMrmComfortableStopStatus, this, _1)); + sub_mrm_emergency_stop_status_ = create_subscription<tier4_system_msgs::msg::MrmBehaviorStatus>( + "~/input/mrm/emergency_stop/status", rclcpp::QoS{1}, + std::bind(&MrmHandler::onMrmEmergencyStopStatus, this, _1)); + sub_operation_mode_state_ = create_subscription<autoware_adapi_v1_msgs::msg::OperationModeState>( + "~/input/api/operation_mode/state", rclcpp::QoS{1}, + std::bind(&MrmHandler::onOperationModeState, this, _1)); + + // Publisher + pub_hazard_cmd_ = create_publisher<autoware_auto_vehicle_msgs::msg::HazardLightsCommand>( + "~/output/hazard", rclcpp::QoS{1}); + pub_gear_cmd_ = + create_publisher<autoware_auto_vehicle_msgs::msg::GearCommand>("~/output/gear", rclcpp::QoS{1}); + pub_mrm_state_ = + create_publisher<autoware_adapi_v1_msgs::msg::MrmState>("~/output/mrm/state", rclcpp::QoS{1}); + + // Clients + client_mrm_pull_over_group_ = create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + client_mrm_pull_over_ = create_client<tier4_system_msgs::srv::OperateMrm>( + "~/output/mrm/pull_over/operate", rmw_qos_profile_services_default, + client_mrm_pull_over_group_); + client_mrm_comfortable_stop_group_ = + create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + client_mrm_comfortable_stop_ = create_client<tier4_system_msgs::srv::OperateMrm>( + "~/output/mrm/comfortable_stop/operate", rmw_qos_profile_services_default, + client_mrm_comfortable_stop_group_); + client_mrm_emergency_stop_group_ = + create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); + client_mrm_emergency_stop_ = create_client<tier4_system_msgs::srv::OperateMrm>( + "~/output/mrm/emergency_stop/operate", rmw_qos_profile_services_default, + client_mrm_emergency_stop_group_); + + // Initialize + odom_ = std::make_shared<const nav_msgs::msg::Odometry>(); + control_mode_ = std::make_shared<const autoware_auto_vehicle_msgs::msg::ControlModeReport>(); + mrm_pull_over_status_ = std::make_shared<const tier4_system_msgs::msg::MrmBehaviorStatus>(); + mrm_comfortable_stop_status_ = + std::make_shared<const tier4_system_msgs::msg::MrmBehaviorStatus>(); + mrm_emergency_stop_status_ = std::make_shared<const tier4_system_msgs::msg::MrmBehaviorStatus>(); + operation_mode_state_ = std::make_shared<const autoware_adapi_v1_msgs::msg::OperationModeState>(); + mrm_state_.stamp = this->now(); + mrm_state_.state = autoware_adapi_v1_msgs::msg::MrmState::NORMAL; + mrm_state_.behavior = autoware_adapi_v1_msgs::msg::MrmState::NONE; + + // Timer + const auto update_period_ns = rclcpp::Rate(param_.update_rate).period(); + timer_ = rclcpp::create_timer( + this, get_clock(), update_period_ns, std::bind(&MrmHandler::onTimer, this)); +} + +void MrmHandler::onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg) +{ + odom_ = msg; +} + +void MrmHandler::onControlMode( + const autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg) +{ + control_mode_ = msg; +} + +void MrmHandler::onOperationModeAvailability( + const tier4_system_msgs::msg::OperationModeAvailability::ConstSharedPtr msg) +{ + stamp_operation_mode_availability_ = this->now(); + + if (!param_.use_emergency_holding) { + operation_mode_availability_ = msg; + return; + } + + if (!is_emergency_holding_) { + if (msg->autonomous) { + stamp_autonomous_become_unavailable_.reset(); + } else if (!msg->autonomous) { + if (!stamp_autonomous_become_unavailable_.has_value()) { + stamp_autonomous_become_unavailable_.emplace(this->now()); + } else { + const auto emergency_duration = + (this->now() - stamp_autonomous_become_unavailable_.value()).seconds(); + if (emergency_duration > param_.timeout_emergency_recovery) { + is_emergency_holding_ = true; + } + } + } + } + operation_mode_availability_ = msg; +} + +void MrmHandler::onMrmPullOverStatus( + const tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr msg) +{ + mrm_pull_over_status_ = msg; +} + +void MrmHandler::onMrmComfortableStopStatus( + const tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr msg) +{ + mrm_comfortable_stop_status_ = msg; +} + +void MrmHandler::onMrmEmergencyStopStatus( + const tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr msg) +{ + mrm_emergency_stop_status_ = msg; +} + +void MrmHandler::onOperationModeState( + const autoware_adapi_v1_msgs::msg::OperationModeState::ConstSharedPtr msg) +{ + operation_mode_state_ = msg; +} + +autoware_auto_vehicle_msgs::msg::HazardLightsCommand MrmHandler::createHazardCmdMsg() +{ + using autoware_auto_vehicle_msgs::msg::HazardLightsCommand; + HazardLightsCommand msg; + + // Check emergency + const bool is_emergency = isEmergency(); + + if (is_emergency_holding_) { + // turn hazard on during emergency holding + msg.command = HazardLightsCommand::ENABLE; + } else if (is_emergency && param_.turning_hazard_on.emergency) { + // turn hazard on if vehicle is in emergency state and + // turning hazard on if emergency flag is true + msg.command = HazardLightsCommand::ENABLE; + } else { + msg.command = HazardLightsCommand::NO_COMMAND; + } + return msg; +} + +void MrmHandler::publishControlCommands() +{ + using autoware_auto_vehicle_msgs::msg::GearCommand; + + // Create timestamp + const auto stamp = this->now(); + + // Publish hazard command + pub_hazard_cmd_->publish(createHazardCmdMsg()); + + // Publish gear + { + GearCommand msg; + msg.stamp = stamp; + if (param_.use_parking_after_stopped && isStopped()) { + msg.command = GearCommand::PARK; + } else { + msg.command = GearCommand::DRIVE; + } + pub_gear_cmd_->publish(msg); + } +} + +void MrmHandler::publishMrmState() +{ + mrm_state_.stamp = this->now(); + pub_mrm_state_->publish(mrm_state_); +} + +void MrmHandler::operateMrm() +{ + using autoware_adapi_v1_msgs::msg::MrmState; + + if (mrm_state_.state == MrmState::NORMAL) { + // Cancel MRM behavior when returning to NORMAL state + const auto current_mrm_behavior = MrmState::NONE; + if (current_mrm_behavior != mrm_state_.behavior) { + cancelMrmBehavior(mrm_state_.behavior); + mrm_state_.behavior = current_mrm_behavior; + } + return; + } + if (mrm_state_.state == MrmState::MRM_OPERATING) { + const auto current_mrm_behavior = getCurrentMrmBehavior(); + if (current_mrm_behavior != mrm_state_.behavior) { + cancelMrmBehavior(mrm_state_.behavior); + callMrmBehavior(current_mrm_behavior); + mrm_state_.behavior = current_mrm_behavior; + } + return; + } + if (mrm_state_.state == MrmState::MRM_SUCCEEDED) { + // TODO(mkuri): operate MRC behavior + // Do nothing + return; + } + if (mrm_state_.state == MrmState::MRM_FAILED) { + // Do nothing + return; + } + RCLCPP_WARN(this->get_logger(), "invalid MRM state: %d", mrm_state_.state); +} + +void MrmHandler::callMrmBehavior( + const autoware_adapi_v1_msgs::msg::MrmState::_behavior_type & mrm_behavior) const +{ + using autoware_adapi_v1_msgs::msg::MrmState; + + auto request = std::make_shared<tier4_system_msgs::srv::OperateMrm::Request>(); + request->operate = true; + + if (mrm_behavior == MrmState::NONE) { + RCLCPP_WARN(this->get_logger(), "MRM behavior is None. Do nothing."); + return; + } + if (mrm_behavior == MrmState::PULL_OVER) { + auto result = client_mrm_pull_over_->async_send_request(request).get(); + if (result->response.success == true) { + RCLCPP_WARN(this->get_logger(), "Pull over is operated"); + } else { + RCLCPP_ERROR(this->get_logger(), "Pull over failed to operate"); + } + return; + } + if (mrm_behavior == MrmState::COMFORTABLE_STOP) { + auto result = client_mrm_comfortable_stop_->async_send_request(request).get(); + if (result->response.success == true) { + RCLCPP_WARN(this->get_logger(), "Comfortable stop is operated"); + } else { + RCLCPP_ERROR(this->get_logger(), "Comfortable stop failed to operate"); + } + return; + } + if (mrm_behavior == MrmState::EMERGENCY_STOP) { + auto result = client_mrm_emergency_stop_->async_send_request(request).get(); + if (result->response.success == true) { + RCLCPP_WARN(this->get_logger(), "Emergency stop is operated"); + } else { + RCLCPP_ERROR(this->get_logger(), "Emergency stop failed to operate"); + } + return; + } + RCLCPP_WARN(this->get_logger(), "invalid MRM behavior: %d", mrm_behavior); +} + +void MrmHandler::cancelMrmBehavior( + const autoware_adapi_v1_msgs::msg::MrmState::_behavior_type & mrm_behavior) const +{ + using autoware_adapi_v1_msgs::msg::MrmState; + + auto request = std::make_shared<tier4_system_msgs::srv::OperateMrm::Request>(); + request->operate = false; + + if (mrm_behavior == MrmState::NONE) { + // Do nothing + return; + } + if (mrm_behavior == MrmState::PULL_OVER) { + auto result = client_mrm_pull_over_->async_send_request(request).get(); + if (result->response.success == true) { + RCLCPP_WARN(this->get_logger(), "Pull over is canceled"); + } else { + RCLCPP_ERROR(this->get_logger(), "Pull over failed to cancel"); + } + return; + } + if (mrm_behavior == MrmState::COMFORTABLE_STOP) { + auto result = client_mrm_comfortable_stop_->async_send_request(request).get(); + if (result->response.success == true) { + RCLCPP_WARN(this->get_logger(), "Comfortable stop is canceled"); + } else { + RCLCPP_ERROR(this->get_logger(), "Comfortable stop failed to cancel"); + } + return; + } + if (mrm_behavior == MrmState::EMERGENCY_STOP) { + auto result = client_mrm_emergency_stop_->async_send_request(request).get(); + if (result->response.success == true) { + RCLCPP_WARN(this->get_logger(), "Emergency stop is canceled"); + } else { + RCLCPP_ERROR(this->get_logger(), "Emergency stop failed to cancel"); + } + return; + } + RCLCPP_WARN(this->get_logger(), "invalid MRM behavior: %d", mrm_behavior); +} + +bool MrmHandler::isDataReady() +{ + if (!operation_mode_availability_) { + RCLCPP_INFO_THROTTLE( + this->get_logger(), *this->get_clock(), std::chrono::milliseconds(5000).count(), + "waiting for operation_mode_availability msg..."); + return false; + } + + if ( + param_.use_pull_over && + mrm_pull_over_status_->state == tier4_system_msgs::msg::MrmBehaviorStatus::NOT_AVAILABLE) { + RCLCPP_INFO_THROTTLE( + this->get_logger(), *this->get_clock(), std::chrono::milliseconds(5000).count(), + "waiting for mrm pull over to become available..."); + return false; + } + + if ( + param_.use_comfortable_stop && mrm_comfortable_stop_status_->state == + tier4_system_msgs::msg::MrmBehaviorStatus::NOT_AVAILABLE) { + RCLCPP_INFO_THROTTLE( + this->get_logger(), *this->get_clock(), std::chrono::milliseconds(5000).count(), + "waiting for mrm comfortable stop to become available..."); + return false; + } + + if ( + mrm_emergency_stop_status_->state == tier4_system_msgs::msg::MrmBehaviorStatus::NOT_AVAILABLE) { + RCLCPP_INFO_THROTTLE( + this->get_logger(), *this->get_clock(), std::chrono::milliseconds(5000).count(), + "waiting for mrm emergency stop to become available..."); + return false; + } + + return true; +} + +void MrmHandler::onTimer() +{ + if (!isDataReady()) { + return; + } + const bool is_operation_mode_availability_timeout = + (this->now() - stamp_operation_mode_availability_).seconds() > + param_.timeout_operation_mode_availability; + if (is_operation_mode_availability_timeout) { + RCLCPP_WARN_THROTTLE( + this->get_logger(), *this->get_clock(), std::chrono::milliseconds(1000).count(), + "heartbeat operation_mode_availability is timeout"); + mrm_state_.state = autoware_adapi_v1_msgs::msg::MrmState::MRM_OPERATING; + publishControlCommands(); + return; + } + + // Update Emergency State + updateMrmState(); + + // Publish control commands + publishControlCommands(); + operateMrm(); + publishMrmState(); +} + +void MrmHandler::transitionTo(const int new_state) +{ + using autoware_adapi_v1_msgs::msg::MrmState; + + const auto state2string = [](const int state) { + if (state == MrmState::NORMAL) { + return "NORMAL"; + } + if (state == MrmState::MRM_OPERATING) { + return "MRM_OPERATING"; + } + if (state == MrmState::MRM_SUCCEEDED) { + return "MRM_SUCCEEDED"; + } + if (state == MrmState::MRM_FAILED) { + return "MRM_FAILED"; + } + + const auto msg = "invalid state: " + std::to_string(state); + throw std::runtime_error(msg); + }; + + RCLCPP_INFO( + this->get_logger(), "MRM State changed: %s -> %s", state2string(mrm_state_.state), + state2string(new_state)); + + mrm_state_.state = new_state; +} + +void MrmHandler::updateMrmState() +{ + using autoware_adapi_v1_msgs::msg::MrmState; + using autoware_auto_vehicle_msgs::msg::ControlModeReport; + + // Check emergency + const bool is_emergency = isEmergency(); + + // Get mode + const bool is_auto_mode = control_mode_->mode == ControlModeReport::AUTONOMOUS; + const bool is_takeover_done = control_mode_->mode == ControlModeReport::MANUAL; + + // State Machine + if (mrm_state_.state == MrmState::NORMAL) { + // NORMAL + if (is_auto_mode && is_emergency) { + if (param_.use_takeover_request) { + takeover_requested_time_ = this->get_clock()->now(); + is_takeover_request_ = true; + return; + } else { + transitionTo(MrmState::MRM_OPERATING); + return; + } + } + } else { + // Emergency + // Send recovery events if "not emergency" or "takeover done" + if (!is_emergency) { + transitionTo(MrmState::NORMAL); + return; + } + // TODO(TetsuKawa): Check if human can safely override, for example using DSM + if (is_takeover_done) { + transitionTo(MrmState::NORMAL); + return; + } + + if (is_takeover_request_) { + const auto time_from_takeover_request = this->get_clock()->now() - takeover_requested_time_; + if (time_from_takeover_request.seconds() > param_.timeout_takeover_request) { + transitionTo(MrmState::MRM_OPERATING); + return; + } + } else if (mrm_state_.state == MrmState::MRM_OPERATING) { + // TODO(TetsuKawa): Check MRC is accomplished + if (mrm_state_.behavior == MrmState::PULL_OVER) { + if (isStopped() && isArrivedAtGoal()) { + transitionTo(MrmState::MRM_SUCCEEDED); + return; + } + } else { + if (isStopped()) { + transitionTo(MrmState::MRM_SUCCEEDED); + return; + } + } + } else if (mrm_state_.state == MrmState::MRM_SUCCEEDED) { + const auto current_mrm_behavior = getCurrentMrmBehavior(); + if (current_mrm_behavior != mrm_state_.behavior) { + transitionTo(MrmState::MRM_OPERATING); + } + } else if (mrm_state_.state == MrmState::MRM_FAILED) { + // Do nothing(only checking common recovery events) + } else { + const auto msg = "invalid state: " + std::to_string(mrm_state_.state); + throw std::runtime_error(msg); + } + } +} + +autoware_adapi_v1_msgs::msg::MrmState::_behavior_type MrmHandler::getCurrentMrmBehavior() +{ + using autoware_adapi_v1_msgs::msg::MrmState; + using tier4_system_msgs::msg::OperationModeAvailability; + + // State machine + if (mrm_state_.behavior == MrmState::NONE) { + if (operation_mode_availability_->pull_over) { + if (param_.use_pull_over) { + return MrmState::PULL_OVER; + } + } + if (operation_mode_availability_->comfortable_stop) { + if (param_.use_comfortable_stop) { + return MrmState::COMFORTABLE_STOP; + } + } + if (!operation_mode_availability_->emergency_stop) { + RCLCPP_WARN(this->get_logger(), "no mrm operation available: operate emergency_stop"); + } + return MrmState::EMERGENCY_STOP; + } + if (mrm_state_.behavior == MrmState::PULL_OVER) { + if (operation_mode_availability_->pull_over) { + if (param_.use_pull_over) { + return MrmState::PULL_OVER; + } + } + if (operation_mode_availability_->comfortable_stop) { + if (param_.use_comfortable_stop) { + return MrmState::COMFORTABLE_STOP; + } + } + if (!operation_mode_availability_->emergency_stop) { + RCLCPP_WARN(this->get_logger(), "no mrm operation available: operate emergency_stop"); + } + return MrmState::EMERGENCY_STOP; + } + if (mrm_state_.behavior == MrmState::COMFORTABLE_STOP) { + if (isStopped() && operation_mode_availability_->pull_over) { + if (param_.use_pull_over) { + return MrmState::PULL_OVER; + } + } + if (operation_mode_availability_->comfortable_stop) { + if (param_.use_comfortable_stop) { + return MrmState::COMFORTABLE_STOP; + } + } + if (!operation_mode_availability_->emergency_stop) { + RCLCPP_WARN(this->get_logger(), "no mrm operation available: operate emergency_stop"); + } + return MrmState::EMERGENCY_STOP; + } + if (mrm_state_.behavior == MrmState::EMERGENCY_STOP) { + if (isStopped() && operation_mode_availability_->pull_over) { + if (param_.use_pull_over) { + return MrmState::PULL_OVER; + } + } + if (!operation_mode_availability_->emergency_stop) { + RCLCPP_WARN(this->get_logger(), "no mrm operation available: operate emergency_stop"); + } + return MrmState::EMERGENCY_STOP; + } + + return mrm_state_.behavior; +} + +bool MrmHandler::isStopped() +{ + constexpr auto th_stopped_velocity = 0.001; + if (odom_->twist.twist.linear.x < th_stopped_velocity) { + return true; + } + + return false; +} + +bool MrmHandler::isEmergency() const +{ + return !operation_mode_availability_->autonomous || is_emergency_holding_; +} + +bool MrmHandler::isArrivedAtGoal() +{ + using autoware_adapi_v1_msgs::msg::OperationModeState; + + return operation_mode_state_->mode == OperationModeState::STOP; +} diff --git a/system/mrm_handler/src/mrm_handler/mrm_handler_node.cpp b/system/mrm_handler/src/mrm_handler/mrm_handler_node.cpp new file mode 100644 index 0000000000000..4aaab3296f64b --- /dev/null +++ b/system/mrm_handler/src/mrm_handler/mrm_handler_node.cpp @@ -0,0 +1,32 @@ +// Copyright 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. + +#include "mrm_handler/mrm_handler_core.hpp" + +#include <rclcpp/rclcpp.hpp> + +#include <memory> + +int main(int argc, char ** argv) +{ + rclcpp::init(argc, argv); + rclcpp::executors::MultiThreadedExecutor executor; + auto node = std::make_shared<MrmHandler>(); + executor.add_node(node); + executor.spin(); + executor.remove_node(node); + rclcpp::shutdown(); + + return 0; +}