Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(emergency_handler): add a selector for multiple MRM behaviors #2070

Merged
merged 63 commits into from
Nov 10, 2022
Merged
Show file tree
Hide file tree
Changes from 62 commits
Commits
Show all changes
63 commits
Select commit Hold shift + click to select a range
594aae9
feat(emergency_handler): add mrm command and status publishers
mkuri Jul 6, 2022
4970772
feat(autoware_ad_api_msgs): define mrm operation srv and mrm status msg
mkuri Jul 11, 2022
be575ce
feat(emergency_handler): add mrm clients and subscribers
mkuri Jul 11, 2022
d612d03
feat(mrm_comfortable_stop_operator): ready ros2 node template
mkuri Jul 11, 2022
31e33bd
feat(mrm_comfortable_stop_operator): implemented
mkuri Jul 11, 2022
389906b
feat(mrm_comfortable_stop_operator): implement as component
mkuri Jul 11, 2022
3f3a8d4
chore(mrm_comfortable_stop_operator): add a launch script
mkuri Jul 11, 2022
11fa390
refactor(mrm_comfortable_stop_operator): remove a xml launch file
mkuri Jul 11, 2022
1a02169
feat(autoware_ad_api_msgs): change mrm status msg
mkuri Jul 12, 2022
ef1c406
feat(emergency_handler): add mrm operator and mrm behavior updater
mkuri Jul 12, 2022
4f67eb6
feat(emergency_handler): add mrm behavior state machine
mkuri Jul 13, 2022
5dbe60a
feat(emergency_handler): remap io names
mkuri Jul 13, 2022
739f846
fix(emergency_handler): fix request generation
mkuri Jul 13, 2022
26503c8
fix(emergency_handler): add multi thread execution for service
mkuri Jul 13, 2022
12ecf2c
feat(vehicle_cmd_gate): add mrm operation service and status publisher
mkuri Jul 13, 2022
729a7d9
refactor(mrm_comfortable_stop_operator): use MRMBehaviorStatus struct
mkuri Jul 13, 2022
c465dfc
fix(mrm_comfortable_stop_operator): add time stamp for status
mkuri Jul 14, 2022
c896729
feat(vehicle_cmd_gate): change system emergency state by mrm operation
mkuri Jul 14, 2022
7764104
chore(autoware_ad_api_msgs): remove rti_operating state from mrm status
mkuri Jul 15, 2022
25afcea
feat(mrm_sudden_stop_operator): add mrm_sudden_stop_operator
mkuri Jul 19, 2022
29d035b
refactor(autoware_ad_api_msgs): rename from mrm status to mrm state
mkuri Jul 19, 2022
1b5b4e6
fix(mrm_comfortable_stop_operator): set qos for velocity limit publisher
mkuri Jul 19, 2022
6a0240a
feat(emergency_handler): add mrm state publisher
mkuri Aug 3, 2022
be50694
feat(vehicle_cmd_gate): add subscription for mrm_state
mkuri Aug 3, 2022
9d4ac84
fix(mrm_sudden_stop_operator): fix control command topic name
mkuri Aug 3, 2022
4c0d8df
feat(vehicle_cmd_gate): pub emergency control_cmd according to mrm state
mkuri Aug 3, 2022
47320cc
feat(emergency_handler): remove emergency control_cmd publisher
mkuri Aug 3, 2022
4cf27f9
chore(tier4_control_launch): remap mrm state topic
mkuri Aug 3, 2022
d913095
feat(tier4_system_launch): launch mrm operators
mkuri Aug 3, 2022
195d2a5
fix(emergency_handler): fix autoware_ad_api_msgs to autoware_adapi_v1…
mkuri Sep 29, 2022
088fe1b
fix(vehicle_cmd_gate): remove subscribers for emergency_state and mrm…
mkuri Sep 29, 2022
8886656
fix(vehicle_cmd_gate): fix system emergency condition
mkuri Sep 29, 2022
baa01c6
fix(emergency_handler): add stamp for mrm_state
mkuri Sep 29, 2022
157869f
fix(mrm_emergency_stop_operator): rename sudden stop to emergency stop
mkuri Sep 29, 2022
7195a5b
fix(vehicle_cmd_gate): remove emergency stop status publisher
mkuri Sep 29, 2022
43f790a
fix(emergency_handler): replace emergency state to mrm state
mkuri Oct 11, 2022
4134309
feat(mrm_emergency_stop_operator): add is_available logic
mkuri Oct 12, 2022
ac17e78
feat(emergency_handler): add use_comfortable_stop param
mkuri Oct 12, 2022
51f8f5d
refactor(emergency_handler): rename getCurrentMRMBehavior
mkuri Oct 12, 2022
fd9e82d
feat(emergency_handler): add mrm available status for ready conditions
mkuri Oct 12, 2022
b683cf0
feat(emergency_handler): add readme
mkuri Oct 12, 2022
73441fe
fix(mrm_comfortable_stop_operator): fix update rate
mkuri Oct 12, 2022
b829647
refactor(emergency_handler): move MRMBehaviorStatus msg to tier4_syst…
mkuri Oct 12, 2022
2fc101c
feat(emergency_handler): describe new io for emergency_handler
mkuri Oct 12, 2022
d848e1d
fix(emergency_handler): remove extra settings
mkuri Oct 12, 2022
18bba96
fix(mrm_emergency_stop_operator): fix is_available condition
mkuri Oct 12, 2022
c62b951
fix(mrm_emergency_stop_operator): fix typo
mkuri Oct 14, 2022
20ecde1
ci(pre-commit): autofix
pre-commit-ci[bot] Oct 14, 2022
362fcb1
fix(mrm_emergency_stop_operator): remove extra descriptions on config…
mkuri Oct 14, 2022
8375674
fix(mrm_comfortable_stop_operator): fix typo
mkuri Oct 14, 2022
faeb8e9
Merge branch 'main' into feature/add-multiple-mrm
mkuri Oct 14, 2022
544d06d
chore(mrm_comfortable_stop_operator): change words
mkuri Oct 14, 2022
4320283
chore(mrm_comfortable_stop_operator): change maintainer infomation
mkuri Oct 18, 2022
fd37af2
Merge branch 'main' into feature/add-multiple-mrm
mkuri Nov 8, 2022
a0fa96f
fix(emergency_handler): fix acronyms case
mkuri Nov 8, 2022
7b3dcb8
chore(emergency_handler): add a maintainer
mkuri Nov 8, 2022
f5cead0
fix(emergency_handler): fix to match msg changes
mkuri Nov 9, 2022
a491369
fix(vehicle_cmd_gate): remove an extra include
mkuri Nov 9, 2022
98830ce
ci(pre-commit): autofix
pre-commit-ci[bot] Nov 9, 2022
82963a2
fix(emergency_handler): fix topic name spaces
mkuri Nov 9, 2022
566f8e1
fix(emergency_handler): fix acronyms case
mkuri Nov 9, 2022
d7736ae
chore(tier4_system_launch): add a mrm comfortable stop parameter
mkuri Nov 9, 2022
25936c4
Merge branch 'main' into feature/add-multiple-mrm
mkuri Nov 10, 2022
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
<remap from="input/emergency/control_cmd" to="/system/emergency/control_cmd"/>
<remap from="input/emergency/hazard_lights_cmd" to="/system/emergency/hazard_lights_cmd"/>
<remap from="input/emergency/gear_cmd" to="/system/emergency/gear_cmd"/>
<remap from="input/mrm_state" to="/system/fail_safe/mrm_state"/>

<remap from="output/vehicle_cmd_emergency" to="/control/command/emergency_cmd"/>
<remap from="output/control_cmd" to="/control/command/control_cmd"/>
Expand Down
1 change: 1 addition & 0 deletions control/vehicle_cmd_gate/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@

<build_depend>autoware_cmake</build_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>
Expand Down
21 changes: 11 additions & 10 deletions control/vehicle_cmd_gate/src/vehicle_cmd_gate.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,8 +69,6 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options)
operation_mode_pub_ = this->create_publisher<OperationMode>("output/operation_mode", durable_qos);

// Subscriber
emergency_state_sub_ = this->create_subscription<EmergencyState>(
"input/emergency_state", 1, std::bind(&VehicleCmdGate::onEmergencyState, this, _1));
external_emergency_stop_heartbeat_sub_ = this->create_subscription<Heartbeat>(
"input/external_emergency_stop_heartbeat", 1,
std::bind(&VehicleCmdGate::onExternalEmergencyStopHeartbeat, this, _1));
Expand All @@ -84,6 +82,8 @@ VehicleCmdGate::VehicleCmdGate(const rclcpp::NodeOptions & node_options)
"input/operation_mode", 1, [this](const tier4_system_msgs::msg::OperationMode::SharedPtr msg) {
current_operation_mode_ = *msg;
});
mrm_state_sub_ = this->create_subscription<MrmState>(
"input/mrm_state", 1, std::bind(&VehicleCmdGate::onMrmState, this, _1));

// Subscriber for auto
auto_control_cmd_sub_ = this->create_subscription<AckermannControlCommand>(
Expand Down Expand Up @@ -546,14 +546,6 @@ AckermannControlCommand VehicleCmdGate::createEmergencyStopControlCmd() const
return cmd;
}

void VehicleCmdGate::onEmergencyState(EmergencyState::ConstSharedPtr msg)
{
is_system_emergency_ = (msg->state == EmergencyState::MRM_OPERATING) ||
(msg->state == EmergencyState::MRM_SUCCEEDED) ||
(msg->state == EmergencyState::MRM_FAILED);
emergency_state_heartbeat_received_time_ = std::make_shared<rclcpp::Time>(this->now());
}

void VehicleCmdGate::onExternalEmergencyStopHeartbeat(
[[maybe_unused]] Heartbeat::ConstSharedPtr msg)
{
Expand Down Expand Up @@ -587,6 +579,15 @@ void VehicleCmdGate::onSteering(SteeringReport::ConstSharedPtr msg)
current_steer_ = msg->steering_tire_angle;
}

void VehicleCmdGate::onMrmState(MrmState::ConstSharedPtr msg)
{
is_system_emergency_ =
(msg->state == MrmState::MRM_OPERATING || msg->state == MrmState::MRM_SUCCEEDED ||
msg->state == MrmState::MRM_FAILED) &&
(msg->behavior == MrmState::EMERGENCY_STOP);
emergency_state_heartbeat_received_time_ = std::make_shared<rclcpp::Time>(this->now());
}

double VehicleCmdGate::getDt()
{
if (!prev_time_) {
Expand Down
10 changes: 7 additions & 3 deletions control/vehicle_cmd_gate/src/vehicle_cmd_gate.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@
#include <std_srvs/srv/trigger.hpp>
#include <vehicle_info_util/vehicle_info_util.hpp>

#include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>
#include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
#include <autoware_auto_system_msgs/msg/emergency_state.hpp>
#include <autoware_auto_vehicle_msgs/msg/engage.hpp>
Expand All @@ -37,6 +38,7 @@
#include <tier4_external_api_msgs/msg/heartbeat.hpp>
#include <tier4_external_api_msgs/srv/engage.hpp>
#include <tier4_external_api_msgs/srv/set_emergency.hpp>
#include <tier4_system_msgs/msg/mrm_behavior_status.hpp>
#include <tier4_system_msgs/msg/operation_mode.hpp>
#include <tier4_vehicle_msgs/msg/vehicle_emergency_stamped.hpp>

Expand All @@ -45,8 +47,8 @@
namespace vehicle_cmd_gate
{

using autoware_adapi_v1_msgs::msg::MrmState;
using autoware_auto_control_msgs::msg::AckermannControlCommand;
using autoware_auto_system_msgs::msg::EmergencyState;
using autoware_auto_vehicle_msgs::msg::GearCommand;
using autoware_auto_vehicle_msgs::msg::HazardLightsCommand;
using autoware_auto_vehicle_msgs::msg::SteeringReport;
Expand All @@ -55,6 +57,7 @@ using tier4_control_msgs::msg::GateMode;
using tier4_external_api_msgs::msg::Emergency;
using tier4_external_api_msgs::msg::Heartbeat;
using tier4_external_api_msgs::srv::SetEmergency;
using tier4_system_msgs::msg::MrmBehaviorStatus;
using tier4_system_msgs::msg::OperationMode;
using tier4_vehicle_msgs::msg::VehicleEmergencyStamped;

Expand Down Expand Up @@ -93,22 +96,23 @@ class VehicleCmdGate : public rclcpp::Node
rclcpp::Publisher<OperationMode>::SharedPtr operation_mode_pub_;

// Subscription
rclcpp::Subscription<EmergencyState>::SharedPtr emergency_state_sub_;
rclcpp::Subscription<Heartbeat>::SharedPtr external_emergency_stop_heartbeat_sub_;
rclcpp::Subscription<GateMode>::SharedPtr gate_mode_sub_;
rclcpp::Subscription<SteeringReport>::SharedPtr steer_sub_;
rclcpp::Subscription<OperationMode>::SharedPtr operation_mode_sub_;
rclcpp::Subscription<MrmState>::SharedPtr mrm_state_sub_;

void onGateMode(GateMode::ConstSharedPtr msg);
void onEmergencyState(EmergencyState::ConstSharedPtr msg);
void onExternalEmergencyStopHeartbeat(Heartbeat::ConstSharedPtr msg);
void onSteering(SteeringReport::ConstSharedPtr msg);
void onMrmState(MrmState::ConstSharedPtr msg);

bool is_engaged_;
bool is_system_emergency_ = false;
bool is_external_emergency_stop_ = false;
double current_steer_ = 0;
GateMode current_gate_mode_;
MrmState current_mrm_state_;

// Heartbeat
std::shared_ptr<rclcpp::Time> emergency_state_heartbeat_received_time_;
Expand Down
1 change: 1 addition & 0 deletions launch/tier4_control_launch/launch/control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -177,6 +177,7 @@ def launch_setup(context, *args, **kwargs):
("input/emergency/control_cmd", "/system/emergency/control_cmd"),
("input/emergency/hazard_lights_cmd", "/system/emergency/hazard_lights_cmd"),
("input/emergency/gear_cmd", "/system/emergency/gear_cmd"),
("input/mrm_state", "/system/fail_safe/mrm_state"),
("output/vehicle_cmd_emergency", "/control/command/emergency_cmd"),
("output/control_cmd", "/control/command/control_cmd"),
("output/gear_cmd", "/control/command/gear_cmd"),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
timeout_takeover_request: 10.0
use_takeover_request: false
use_parking_after_stopped: false
use_comfortable_stop: false

# setting whether to turn hazard lamp on for each situation
turning_hazard_on:
Expand Down
8 changes: 8 additions & 0 deletions launch/tier4_system_launch/launch/system.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -66,5 +66,13 @@
<arg name="config_file" value="$(var tier4_system_launch_param_path)/emergency_handler/emergency_handler.param.yaml"/>
</include>
</group>

<!-- MRM Operator -->
<include file="$(find-pkg-share mrm_comfortable_stop_operator)/launch/mrm_comfortable_stop_operator.launch.py">
<arg name="config_file" value="$(find-pkg-share mrm_comfortable_stop_operator)/config/mrm_comfortable_stop_operator.param.yaml"/>
</include>
<include file="$(find-pkg-share mrm_emergency_stop_operator)/launch/mrm_emergency_stop_operator.launch.py">
<arg name="config_file" value="$(find-pkg-share mrm_emergency_stop_operator)/config/mrm_emergency_stop_operator.param.yaml"/>
</include>
</group>
</launch>
28 changes: 16 additions & 12 deletions system/emergency_handler/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -14,21 +14,24 @@ Emergency Handler is a node to select proper MRM from from system failure state

### Input

| Name | Type | Description |
| --------------------------------- | ---------------------------------------------------------- | ----------------------------------------------------------------------------- |
| `/system/emergency/hazard_status` | `autoware_auto_system_msgs::msg::HazardStatusStamped` | Used to select proper MRM from system failure state contained in HazardStatus |
| `/control/vehicle_cmd` | `autoware_auto_control_msgs::msg::AckermannControlCommand` | Used as reference when generate Emergency Control Command |
| `/localization/kinematic_state` | `nav_msgs::msg::Odometry` | Used to decide whether vehicle is stopped or not |
| `/vehicle/status/control_mode` | `autoware_auto_vehicle_msgs::msg::ControlModeReport` | Used to check vehicle mode: autonomous or manual. |
| Name | Type | Description |
| ----------------------------------------- | ---------------------------------------------------------- | ----------------------------------------------------------------------------- |
| `/system/emergency/hazard_status` | `autoware_auto_system_msgs::msg::HazardStatusStamped` | Used to select proper MRM from system failure state contained in HazardStatus |
| `/control/vehicle_cmd` | `autoware_auto_control_msgs::msg::AckermannControlCommand` | Used as reference when generate Emergency Control Command |
| `/localization/kinematic_state` | `nav_msgs::msg::Odometry` | Used to decide whether vehicle is stopped or not |
| `/vehicle/status/control_mode` | `autoware_auto_vehicle_msgs::msg::ControlModeReport` | Used to check vehicle mode: autonomous or manual |
| `/system/api/mrm/comfortable_stop/status` | `tier4_system_msgs::msg::MrmBehaviorStatus` | Used to check if MRM comfortable stop operation is available |
| `/system/api/mrm/emergency_stop/status` | `tier4_system_msgs::msg::MrmBehaviorStatus` | Used to check if MRM emergency stop operation is available |

### Output

| Name | Type | Description |
| ----------------------------------- | ---------------------------------------------------------- | ----------------------------------------------------- |
| `/system/emergency/control_cmd` | `autoware_auto_control_msgs::msg::AckermannControlCommand` | Required to execute proper MRM |
| `/system/emergency/shift_cmd` | `autoware_auto_vehicle_msgs::msg::GearCommand` | Required to execute proper MRM (send gear cmd) |
| `/system/emergency/hazard_cmd` | `autoware_auto_vehicle_msgs::msg::HazardLightsCommand` | Required to execute proper MRM (send turn signal cmd) |
| `/system/emergency/emergency_state` | `autoware_auto_system_msgs::msg::EmergencyStateStamped` | Used to inform the emergency situation of the vehicle |
| Name | Type | Description |
| ------------------------------------------ | ------------------------------------------------------ | ----------------------------------------------------- |
| `/system/emergency/shift_cmd` | `autoware_auto_vehicle_msgs::msg::GearCommand` | Required to execute proper MRM (send gear cmd) |
| `/system/emergency/hazard_cmd` | `autoware_auto_vehicle_msgs::msg::HazardLightsCommand` | Required to execute proper MRM (send turn signal cmd) |
| `/api/fail_safe/mrm_state` | `autoware_adapi_v1_msgs::msg::MrmState` | Inform MRM execution state and selected MRM behavior |
| `/system/api/mrm/comfortable_stop/operate` | `tier4_system_msgs::srv::OperateMrm` | Execution order for MRM comfortable stop |
| `/system/api/mrm/emergency_stop/operate` | `tier4_system_msgs::srv::OperateMrm` | Execution order for MRM emergency stop |

## Parameters

Expand All @@ -45,6 +48,7 @@ Emergency Handler is a node to select proper MRM from from system failure state
| 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. |

## Assumptions / Known limits

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
timeout_takeover_request: 10.0
use_takeover_request: false
use_parking_after_stopped: false
use_comfortable_stop: false

# setting whether to turn hazard lamp on for each situation
turning_hazard_on:
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -20,12 +20,14 @@
#include <string>

// Autoware
#include <autoware_adapi_v1_msgs/msg/mrm_state.hpp>
#include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp>
#include <autoware_auto_system_msgs/msg/emergency_state.hpp>
#include <autoware_auto_system_msgs/msg/hazard_status_stamped.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/srv/operate_mrm.hpp>

// ROS2 core
#include <rclcpp/create_timer.hpp>
Expand All @@ -46,6 +48,7 @@ struct Param
double timeout_takeover_request;
bool use_takeover_request;
bool use_parking_after_stopped;
bool use_comfortable_stop;
HazardLampPolicy turning_hazard_on{};
};

Expand All @@ -63,18 +66,28 @@ class EmergencyHandler : public rclcpp::Node
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::MrmBehaviorStatus>::SharedPtr
sub_mrm_comfortable_stop_status_;
rclcpp::Subscription<tier4_system_msgs::msg::MrmBehaviorStatus>::SharedPtr
sub_mrm_emergency_stop_status_;

autoware_auto_system_msgs::msg::HazardStatusStamped::ConstSharedPtr hazard_status_stamped_;
autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr prev_control_command_;
nav_msgs::msg::Odometry::ConstSharedPtr odom_;
autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr control_mode_;
tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr mrm_comfortable_stop_status_;
tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr mrm_emergency_stop_status_;

void onHazardStatusStamped(
const autoware_auto_system_msgs::msg::HazardStatusStamped::ConstSharedPtr msg);
void onPrevControlCommand(
const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg);
void onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg);
void onControlMode(const autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg);
void onMrmComfortableStopStatus(
const tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr msg);
void onMrmEmergencyStopStatus(
const tier4_system_msgs::msg::MrmBehaviorStatus::ConstSharedPtr msg);

// Publisher
rclcpp::Publisher<autoware_auto_control_msgs::msg::AckermannControlCommand>::SharedPtr
Expand All @@ -85,12 +98,30 @@ class EmergencyHandler : public rclcpp::Node
rclcpp::Publisher<autoware_auto_vehicle_msgs::msg::HazardLightsCommand>::SharedPtr
pub_hazard_cmd_;
rclcpp::Publisher<autoware_auto_vehicle_msgs::msg::GearCommand>::SharedPtr pub_gear_cmd_;
rclcpp::Publisher<autoware_auto_system_msgs::msg::EmergencyState>::SharedPtr pub_emergency_state_;

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_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_;

Expand All @@ -104,15 +135,14 @@ class EmergencyHandler : public rclcpp::Node
rclcpp::Time stamp_hazard_status_;

// Algorithm
autoware_auto_system_msgs::msg::EmergencyState::_state_type emergency_state_{
autoware_auto_system_msgs::msg::EmergencyState::NORMAL};
rclcpp::Time takeover_requested_time_;

bool is_takeover_request_ = false;
void transitionTo(const int new_state);
void updateEmergencyState();
void updateMrmState();
void operateMrm();
autoware_adapi_v1_msgs::msg::MrmState::_behavior_type getCurrentMrmBehavior();
bool isStopped();
bool isEmergency(const autoware_auto_system_msgs::msg::HazardStatus & hazard_status);
autoware_auto_control_msgs::msg::AckermannControlCommand selectAlternativeControlCommand();
};

#endif // EMERGENCY_HANDLER__EMERGENCY_HANDLER_CORE_HPP_
14 changes: 10 additions & 4 deletions system/emergency_handler/launch/emergency_handler.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,14 @@
<arg name="input_prev_control_command" default="/control/command/control_cmd"/>
<arg name="input_odometry" default="/localization/kinematic_state"/>
<arg name="input_control_mode" default="/vehicle/status/control_mode"/>
<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="output_control_command" default="/system/emergency/control_cmd"/>
<arg name="output_gear" default="/system/emergency/gear_cmd"/>
<arg name="output_hazard" default="/system/emergency/hazard_lights_cmd"/>
<arg name="output_emergency_state" default="/system/emergency/emergency_state"/>
<arg name="output_mrm_state" default="/system/fail_safe/mrm_state"/>
<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 emergency_handler)/config/emergency_handler.param.yaml"/>

Expand All @@ -18,11 +21,14 @@
<remap from="~/input/prev_control_command" to="$(var input_prev_control_command)"/>
<remap from="~/input/odometry" to="$(var input_odometry)"/>
<remap from="~/input/control_mode" to="$(var input_control_mode)"/>
<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="~/output/control_command" to="$(var output_control_command)"/>
<remap from="~/output/gear" to="$(var output_gear)"/>
<remap from="~/output/hazard" to="$(var output_hazard)"/>
<remap from="~/output/emergency_state" to="$(var output_emergency_state)"/>
<remap from="~/output/mrm/state" to="$(var output_mrm_state)"/>
<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>
Expand Down
Loading