|
| 1 | +// Copyright 2020 Tier IV, Inc. |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | + |
| 15 | +#ifndef EMERGENCY_HANDLER__EMERGENCY_HANDLER_CORE_HPP_ |
| 16 | +#define EMERGENCY_HANDLER__EMERGENCY_HANDLER_CORE_HPP_ |
| 17 | + |
| 18 | +// Core |
| 19 | +#include <memory> |
| 20 | +#include <string> |
| 21 | + |
| 22 | +// Autoware |
| 23 | +#include <autoware_auto_control_msgs/msg/ackermann_control_command.hpp> |
| 24 | +#include <autoware_auto_system_msgs/msg/emergency_state.hpp> |
| 25 | +#include <autoware_auto_system_msgs/msg/hazard_status_stamped.hpp> |
| 26 | +#include <autoware_auto_vehicle_msgs/msg/control_mode_report.hpp> |
| 27 | +#include <autoware_auto_vehicle_msgs/msg/gear_command.hpp> |
| 28 | +#include <autoware_auto_vehicle_msgs/msg/hazard_lights_command.hpp> |
| 29 | + |
| 30 | +// ROS2 core |
| 31 | +#include <autoware_utils/system/heartbeat_checker.hpp> |
| 32 | +#include <rclcpp/create_timer.hpp> |
| 33 | +#include <rclcpp/rclcpp.hpp> |
| 34 | + |
| 35 | +#include <diagnostic_msgs/msg/diagnostic_array.hpp> |
| 36 | +#include <nav_msgs/msg/odometry.hpp> |
| 37 | + |
| 38 | +struct HazardLampPolicy |
| 39 | +{ |
| 40 | + bool emergency; |
| 41 | +}; |
| 42 | + |
| 43 | +struct Param |
| 44 | +{ |
| 45 | + int update_rate; |
| 46 | + double timeout_hazard_status; |
| 47 | + double timeout_takeover_request; |
| 48 | + bool use_takeover_request; |
| 49 | + bool use_parking_after_stopped; |
| 50 | + HazardLampPolicy turning_hazard_on{}; |
| 51 | +}; |
| 52 | + |
| 53 | +class EmergencyHandler : public rclcpp::Node |
| 54 | +{ |
| 55 | +public: |
| 56 | + EmergencyHandler(); |
| 57 | + |
| 58 | +private: |
| 59 | + // Subscribers |
| 60 | + rclcpp::Subscription<autoware_auto_system_msgs::msg::HazardStatusStamped>::SharedPtr |
| 61 | + sub_hazard_status_stamped_; |
| 62 | + rclcpp::Subscription<autoware_auto_control_msgs::msg::AckermannControlCommand>::SharedPtr |
| 63 | + sub_prev_control_command_; |
| 64 | + rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr sub_odom_; |
| 65 | + rclcpp::Subscription<autoware_auto_vehicle_msgs::msg::ControlModeReport>::SharedPtr |
| 66 | + sub_control_mode_; |
| 67 | + |
| 68 | + autoware_auto_system_msgs::msg::HazardStatusStamped::ConstSharedPtr hazard_status_stamped_; |
| 69 | + autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr prev_control_command_; |
| 70 | + nav_msgs::msg::Odometry::ConstSharedPtr odom_; |
| 71 | + autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr control_mode_; |
| 72 | + |
| 73 | + void onHazardStatusStamped( |
| 74 | + const autoware_auto_system_msgs::msg::HazardStatusStamped::ConstSharedPtr msg); |
| 75 | + void onPrevControlCommand( |
| 76 | + const autoware_auto_control_msgs::msg::AckermannControlCommand::ConstSharedPtr msg); |
| 77 | + void onOdometry(const nav_msgs::msg::Odometry::ConstSharedPtr msg); |
| 78 | + void onControlMode(const autoware_auto_vehicle_msgs::msg::ControlModeReport::ConstSharedPtr msg); |
| 79 | + |
| 80 | + // Publisher |
| 81 | + rclcpp::Publisher<autoware_auto_control_msgs::msg::AckermannControlCommand>::SharedPtr |
| 82 | + pub_control_command_; |
| 83 | + |
| 84 | + // rclcpp::Publisher<autoware_vehicle_msgs::msg::ShiftStamped>::SharedPtr pub_shift_; |
| 85 | + // rclcpp::Publisher<autoware_vehicle_msgs::msg::TurnSignal>::SharedPtr pub_turn_signal_; |
| 86 | + rclcpp::Publisher<autoware_auto_vehicle_msgs::msg::HazardLightsCommand>::SharedPtr |
| 87 | + pub_hazard_cmd_; |
| 88 | + rclcpp::Publisher<autoware_auto_vehicle_msgs::msg::GearCommand>::SharedPtr pub_gear_cmd_; |
| 89 | + rclcpp::Publisher<autoware_auto_system_msgs::msg::EmergencyState>::SharedPtr pub_emergency_state_; |
| 90 | + |
| 91 | + autoware_auto_vehicle_msgs::msg::HazardLightsCommand createHazardCmdMsg(); |
| 92 | + autoware_auto_vehicle_msgs::msg::GearCommand createGearCmdMsg(); |
| 93 | + void publishControlCommands(); |
| 94 | + |
| 95 | + // Timer |
| 96 | + rclcpp::TimerBase::SharedPtr timer_; |
| 97 | + |
| 98 | + // Parameters |
| 99 | + Param param_; |
| 100 | + |
| 101 | + bool isDataReady(); |
| 102 | + void onTimer(); |
| 103 | + |
| 104 | + // Heartbeat |
| 105 | + std::shared_ptr<HeaderlessHeartbeatChecker<autoware_auto_system_msgs::msg::HazardStatusStamped>> |
| 106 | + heartbeat_hazard_status_; |
| 107 | + |
| 108 | + // Algorithm |
| 109 | + autoware_auto_system_msgs::msg::EmergencyState::_state_type emergency_state_{ |
| 110 | + autoware_auto_system_msgs::msg::EmergencyState::NORMAL}; |
| 111 | + rclcpp::Time takeover_requested_time_; |
| 112 | + |
| 113 | + void transitionTo(const int new_state); |
| 114 | + void updateEmergencyState(); |
| 115 | + bool isStopped(); |
| 116 | + bool isEmergency(const autoware_auto_system_msgs::msg::HazardStatus & hazard_status); |
| 117 | + autoware_auto_control_msgs::msg::AckermannControlCommand selectAlternativeControlCommand(); |
| 118 | +}; |
| 119 | + |
| 120 | +#endif // EMERGENCY_HANDLER__EMERGENCY_HANDLER_CORE_HPP_ |
0 commit comments