Skip to content

Commit

Permalink
refactor(emergency_handler): rework parameters
Browse files Browse the repository at this point in the history
Signed-off-by: Yuqi Huai <yhuai@uci.edu>
  • Loading branch information
YuqiHuai committed Oct 5, 2023
1 parent b0310e7 commit eb09504
Show file tree
Hide file tree
Showing 3 changed files with 91 additions and 21 deletions.
15 changes: 1 addition & 14 deletions system/emergency_handler/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -35,20 +35,7 @@ Emergency Handler is a node to select proper MRM from from system failure state

## Parameters

### Node Parameters

| Name | Type | Default Value | Explanation |
| ----------- | ---- | ------------- | ---------------------- |
| update_rate | int | `10` | Timer callback period. |

### Core Parameters

| Name | Type | Default Value | Explanation |
| --------------------------- | ------ | ------------- | --------------------------------------------------------------------------------------------------------------------------------- |
| timeout_hazard_status | double | `0.5` | If the input `hazard_status` topic cannot be received for more than `timeout_hazard_status`, vehicle will make an emergency stop. |
| use_parking_after_stopped | bool | `false` | If this parameter is true, it will publish PARKING shift command. |
| turning_hazard_on.emergency | bool | `true` | If this parameter is true, hazard lamps will be turned on during emergency state. |
| use_comfortable_stop | bool | `false` | If this parameter is true, operate comfortable stop when latent faults occur. |
{{ json_to_markdown("system/emergency_handler/schema/emergency_handler.schema.json") }}

## Assumptions / Known limits

Expand Down
83 changes: 83 additions & 0 deletions system/emergency_handler/schema/emergency_handler.schema.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,83 @@
{
"$schema": "http://json-schema.org/draft-07/schema#",
"title": "Parameters for emergency handler",
"type": "object",
"definitions": {
"emergency_handler": {
"type": "object",
"properties": {
"update_rate": {
"type": "integer",
"description": "Timer callback period.",
"default": 10
},
"timeout_hazard_status": {
"type": "number",
"description": "If the input `hazard_status` topic cannot be received for more than `timeout_hazard_status`, vehicle will make an emergency stop.",
"default": 0.5
},
"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_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_hazard_status",
"timeout_takeover_request",
"use_takeover_request",
"use_parking_after_stopped",
"use_comfortable_stop",
"turning_hazard_on"
],
"additionalProperties": false
}
},
"properties": {
"/**": {
"type": "object",
"properties": {
"ros__parameters": {
"$ref": "#/definitions/emergency_handler"
}
},
"required": [
"ros__parameters"
],
"additionalProperties": false
}
},
"required": [
"/**"
],
"additionalProperties": false
}
Original file line number Diff line number Diff line change
Expand Up @@ -21,13 +21,13 @@
EmergencyHandler::EmergencyHandler() : Node("emergency_handler")
{
// Parameter
param_.update_rate = declare_parameter<int>("update_rate", 10);
param_.timeout_hazard_status = declare_parameter<double>("timeout_hazard_status", 0.5);
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_comfortable_stop = declare_parameter<bool>("use_comfortable_stop", false);
param_.turning_hazard_on.emergency = declare_parameter<bool>("turning_hazard_on.emergency", true);
param_.update_rate = declare_parameter<int>("update_rate");
param_.timeout_hazard_status = declare_parameter<double>("timeout_hazard_status");
param_.timeout_takeover_request = declare_parameter<double>("timeout_takeover_request");
param_.use_takeover_request = declare_parameter<bool>("use_takeover_request");
param_.use_parking_after_stopped = declare_parameter<bool>("use_parking_after_stopped");
param_.use_comfortable_stop = declare_parameter<bool>("use_comfortable_stop");
param_.turning_hazard_on.emergency = declare_parameter<bool>("turning_hazard_on.emergency");

using std::placeholders::_1;

Expand Down

0 comments on commit eb09504

Please sign in to comment.