Skip to content

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#

mrm-state

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#

Name Type Description Default Range
update_rate integer Timer callback period. 10 N/A
timeout_operation_mode_availability float If the input operation_mode_availability topic cannot be received for more than timeout_operation_mode_availability, vehicle will make an emergency stop. 0.5 N/A
timeout_call_mrm_behavior float If a service is requested to the mrm operator and the response is not returned by timeout_call_mrm_behavior, the timeout occurs. 0.01 N/A
timeout_cancel_mrm_behavior float If a service is requested to the mrm operator and the response is not returned by timeout_cancel_mrm_behavior, the timeout occurs. 0.01 N/A
use_emergency_holding boolean If this parameter is true, the handler does not recover to the NORMAL state. False N/A
timeout_emergency_recovery float If the duration of the EMERGENCY state is longer than timeout_emergency_recovery, it does not recover to the NORMAL state. 5.0 N/A
use_parking_after_stopped boolean If this parameter is true, it will publish PARKING shift command. false N/A
use_pull_over boolean If this parameter is true, operate pull over when latent faults occur. false N/A
use_comfortable_stop boolean If this parameter is true, operate comfortable stop when latent faults occur. false N/A
turning_hazard_on.emergency boolean If this parameter is true, hazard lamps will be turned on during emergency state. true N/A

Assumptions / Known limits#

TBD.