|
| 1 | +// Copyright 2024 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 DECISION_RESULT_HPP_ |
| 16 | +#define DECISION_RESULT_HPP_ |
| 17 | + |
| 18 | +#include <optional> |
| 19 | +#include <string> |
| 20 | +#include <variant> |
| 21 | + |
| 22 | +namespace behavior_velocity_planner::intersection |
| 23 | +{ |
| 24 | + |
| 25 | +/** |
| 26 | + * @struct |
| 27 | + * @brief Internal error or ego already passed pass_judge_line |
| 28 | + */ |
| 29 | +struct Indecisive |
| 30 | +{ |
| 31 | + std::string error; |
| 32 | +}; |
| 33 | + |
| 34 | +/** |
| 35 | + * @struct |
| 36 | + * @brief detected stuck vehicle |
| 37 | + */ |
| 38 | +struct StuckStop |
| 39 | +{ |
| 40 | + size_t closest_idx{0}; |
| 41 | + size_t stuck_stopline_idx{0}; |
| 42 | + std::optional<size_t> occlusion_stopline_idx{std::nullopt}; |
| 43 | +}; |
| 44 | + |
| 45 | +/** |
| 46 | + * @struct |
| 47 | + * @brief yielded by vehicle on the attention area |
| 48 | + */ |
| 49 | +struct YieldStuckStop |
| 50 | +{ |
| 51 | + size_t closest_idx{0}; |
| 52 | + size_t stuck_stopline_idx{0}; |
| 53 | +}; |
| 54 | + |
| 55 | +/** |
| 56 | + * @struct |
| 57 | + * @brief only collision is detected |
| 58 | + */ |
| 59 | +struct NonOccludedCollisionStop |
| 60 | +{ |
| 61 | + size_t closest_idx{0}; |
| 62 | + size_t collision_stopline_idx{0}; |
| 63 | + size_t occlusion_stopline_idx{0}; |
| 64 | +}; |
| 65 | + |
| 66 | +/** |
| 67 | + * @struct |
| 68 | + * @brief occlusion is detected so ego needs to stop at the default stop line position |
| 69 | + */ |
| 70 | +struct FirstWaitBeforeOcclusion |
| 71 | +{ |
| 72 | + bool is_actually_occlusion_cleared{false}; |
| 73 | + size_t closest_idx{0}; |
| 74 | + size_t first_stopline_idx{0}; |
| 75 | + size_t occlusion_stopline_idx{0}; |
| 76 | +}; |
| 77 | + |
| 78 | +/** |
| 79 | + * @struct |
| 80 | + * @brief ego is approaching the boundary of attention area in the presence of traffic light |
| 81 | + */ |
| 82 | +struct PeekingTowardOcclusion |
| 83 | +{ |
| 84 | + //! if intersection_occlusion is disapproved externally through RTC, it indicates |
| 85 | + //! "is_forcefully_occluded" |
| 86 | + bool is_actually_occlusion_cleared{false}; |
| 87 | + bool temporal_stop_before_attention_required{false}; |
| 88 | + size_t closest_idx{0}; |
| 89 | + size_t collision_stopline_idx{0}; |
| 90 | + size_t first_attention_stopline_idx{0}; |
| 91 | + size_t occlusion_stopline_idx{0}; |
| 92 | + //! if null, it is dynamic occlusion and shows up intersection_occlusion(dyn). if valid, it |
| 93 | + //! contains the remaining time to release the static occlusion stuck and shows up |
| 94 | + //! intersection_occlusion(x.y) |
| 95 | + std::optional<double> static_occlusion_timeout{std::nullopt}; |
| 96 | +}; |
| 97 | + |
| 98 | +/** |
| 99 | + * @struct |
| 100 | + * @brief both collision and occlusion are detected in the presence of traffic light |
| 101 | + */ |
| 102 | +struct OccludedCollisionStop |
| 103 | +{ |
| 104 | + bool is_actually_occlusion_cleared{false}; |
| 105 | + bool temporal_stop_before_attention_required{false}; |
| 106 | + size_t closest_idx{0}; |
| 107 | + size_t collision_stopline_idx{0}; |
| 108 | + size_t first_attention_stopline_idx{0}; |
| 109 | + size_t occlusion_stopline_idx{0}; |
| 110 | + //! if null, it is dynamic occlusion and shows up intersection_occlusion(dyn). if valid, it |
| 111 | + //! contains the remaining time to release the static occlusion stuck |
| 112 | + std::optional<double> static_occlusion_timeout{std::nullopt}; |
| 113 | +}; |
| 114 | + |
| 115 | +/** |
| 116 | + * @struct |
| 117 | + * @brief at least occlusion is detected in the absence of traffic light |
| 118 | + */ |
| 119 | +struct OccludedAbsenceTrafficLight |
| 120 | +{ |
| 121 | + bool is_actually_occlusion_cleared{false}; |
| 122 | + bool collision_detected{false}; |
| 123 | + bool temporal_stop_before_attention_required{false}; |
| 124 | + size_t closest_idx{0}; |
| 125 | + size_t first_attention_area_stopline_idx{0}; |
| 126 | + size_t peeking_limit_line_idx{0}; |
| 127 | +}; |
| 128 | + |
| 129 | +/** |
| 130 | + * @struct |
| 131 | + * @brief both collision and occlusion are not detected |
| 132 | + */ |
| 133 | +struct Safe |
| 134 | +{ |
| 135 | + size_t closest_idx{0}; |
| 136 | + size_t collision_stopline_idx{0}; |
| 137 | + size_t occlusion_stopline_idx{0}; |
| 138 | +}; |
| 139 | + |
| 140 | +/** |
| 141 | + * @struct |
| 142 | + * @brief traffic light is red or arrow signal |
| 143 | + */ |
| 144 | +struct FullyPrioritized |
| 145 | +{ |
| 146 | + bool collision_detected{false}; |
| 147 | + size_t closest_idx{0}; |
| 148 | + size_t collision_stopline_idx{0}; |
| 149 | + size_t occlusion_stopline_idx{0}; |
| 150 | +}; |
| 151 | + |
| 152 | +using DecisionResult = std::variant< |
| 153 | + Indecisive, //! internal process error, or over the pass judge line |
| 154 | + StuckStop, //! detected stuck vehicle |
| 155 | + YieldStuckStop, //! detected yield stuck vehicle |
| 156 | + NonOccludedCollisionStop, //! detected collision while FOV is clear |
| 157 | + FirstWaitBeforeOcclusion, //! stop for a while before peeking to occlusion |
| 158 | + PeekingTowardOcclusion, //! peeking into occlusion while collision is not detected |
| 159 | + OccludedCollisionStop, //! occlusion and collision are both detected |
| 160 | + OccludedAbsenceTrafficLight, //! occlusion is detected in the absence of traffic light |
| 161 | + Safe, //! judge as safe |
| 162 | + FullyPrioritized //! only detect vehicles violating traffic rules |
| 163 | + >; |
| 164 | + |
| 165 | +inline std::string formatDecisionResult(const DecisionResult & decision_result) |
| 166 | +{ |
| 167 | + if (std::holds_alternative<Indecisive>(decision_result)) { |
| 168 | + const auto indecisive = std::get<Indecisive>(decision_result); |
| 169 | + return "Indecisive because " + indecisive.error; |
| 170 | + } |
| 171 | + if (std::holds_alternative<StuckStop>(decision_result)) { |
| 172 | + return "StuckStop"; |
| 173 | + } |
| 174 | + if (std::holds_alternative<YieldStuckStop>(decision_result)) { |
| 175 | + return "YieldStuckStop"; |
| 176 | + } |
| 177 | + if (std::holds_alternative<NonOccludedCollisionStop>(decision_result)) { |
| 178 | + return "NonOccludedCollisionStop"; |
| 179 | + } |
| 180 | + if (std::holds_alternative<FirstWaitBeforeOcclusion>(decision_result)) { |
| 181 | + return "FirstWaitBeforeOcclusion"; |
| 182 | + } |
| 183 | + if (std::holds_alternative<PeekingTowardOcclusion>(decision_result)) { |
| 184 | + return "PeekingTowardOcclusion"; |
| 185 | + } |
| 186 | + if (std::holds_alternative<OccludedCollisionStop>(decision_result)) { |
| 187 | + return "OccludedCollisionStop"; |
| 188 | + } |
| 189 | + if (std::holds_alternative<OccludedAbsenceTrafficLight>(decision_result)) { |
| 190 | + return "OccludedAbsenceTrafficLight"; |
| 191 | + } |
| 192 | + if (std::holds_alternative<Safe>(decision_result)) { |
| 193 | + return "Safe"; |
| 194 | + } |
| 195 | + if (std::holds_alternative<FullyPrioritized>(decision_result)) { |
| 196 | + return "FullyPrioritized"; |
| 197 | + } |
| 198 | + return ""; |
| 199 | +} |
| 200 | + |
| 201 | +} // namespace behavior_velocity_planner::intersection |
| 202 | + |
| 203 | +#endif // DECISION_RESULT_HPP_ |
0 commit comments