|
| 1 | +// Copyright 2024 Autoware Foundation. All rights reserved. |
| 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 | +// NOLINTBEGIN(readability-identifier-naming) |
| 16 | + |
| 17 | +#include "autoware_lanelet2_extension/regulatory_elements/bus_stop_area.hpp" |
| 18 | + |
| 19 | +#include <boost/variant.hpp> |
| 20 | + |
| 21 | +#include <lanelet2_core/primitives/RegulatoryElement.h> |
| 22 | + |
| 23 | +#include <algorithm> |
| 24 | +#include <memory> |
| 25 | +#include <utility> |
| 26 | +#include <vector> |
| 27 | + |
| 28 | +namespace lanelet::autoware |
| 29 | +{ |
| 30 | +namespace |
| 31 | +{ |
| 32 | +template <typename T> |
| 33 | +bool findAndErase(const T & primitive, RuleParameters * member) |
| 34 | +{ |
| 35 | + if (member == nullptr) { |
| 36 | + return false; |
| 37 | + } |
| 38 | + auto it = std::find(member->begin(), member->end(), RuleParameter(primitive)); |
| 39 | + if (it == member->end()) { |
| 40 | + return false; |
| 41 | + } |
| 42 | + member->erase(it); |
| 43 | + return true; |
| 44 | +} |
| 45 | + |
| 46 | +template <typename T> |
| 47 | +Optional<T> tryGetFront(const std::vector<T> & vec) |
| 48 | +{ |
| 49 | + if (vec.empty()) { |
| 50 | + return {}; |
| 51 | + } |
| 52 | + return vec.front(); |
| 53 | +} |
| 54 | + |
| 55 | +template <typename T> |
| 56 | +RuleParameters toRuleParameters(const std::vector<T> & primitives) |
| 57 | +{ |
| 58 | + auto cast_func = [](const auto & elem) { return static_cast<RuleParameter>(elem); }; |
| 59 | + return utils::transform(primitives, cast_func); |
| 60 | +} |
| 61 | + |
| 62 | +Polygons3d getPoly(const RuleParameterMap & paramsMap, RoleName role) |
| 63 | +{ |
| 64 | + auto params = paramsMap.find(role); |
| 65 | + if (params == paramsMap.end()) { |
| 66 | + return {}; |
| 67 | + } |
| 68 | + |
| 69 | + Polygons3d result; |
| 70 | + for (auto & param : params->second) { |
| 71 | + auto p = boost::get<Polygon3d>(¶m); |
| 72 | + if (p != nullptr) { |
| 73 | + result.push_back(*p); |
| 74 | + } |
| 75 | + } |
| 76 | + return result; |
| 77 | +} |
| 78 | + |
| 79 | +ConstPolygons3d getConstPoly(const RuleParameterMap & params, RoleName role) |
| 80 | +{ |
| 81 | + auto cast_func = [](auto & poly) { return static_cast<ConstPolygon3d>(poly); }; |
| 82 | + return utils::transform(getPoly(params, role), cast_func); |
| 83 | +} |
| 84 | + |
| 85 | +RegulatoryElementDataPtr constructBusStopAreaData( |
| 86 | + Id id, const AttributeMap & attributes, const Polygons3d & bus_stop_areas) |
| 87 | +{ |
| 88 | + RuleParameterMap rpm = {{RoleNameString::Refers, toRuleParameters(bus_stop_areas)}}; |
| 89 | + |
| 90 | + auto data = std::make_shared<RegulatoryElementData>(id, std::move(rpm), attributes); |
| 91 | + data->attributes[AttributeName::Type] = AttributeValueString::RegulatoryElement; |
| 92 | + data->attributes[AttributeName::Subtype] = "bus_stop_area"; |
| 93 | + return data; |
| 94 | +} |
| 95 | +} // namespace |
| 96 | + |
| 97 | +// TODO(soblin): remove this when format_v2 has been released |
| 98 | +namespace format_v2 |
| 99 | +{ |
| 100 | +BusStopArea::BusStopArea(const RegulatoryElementDataPtr & data) : RegulatoryElement(data) |
| 101 | +{ |
| 102 | + if (getConstPoly(data->parameters, RoleName::Refers).empty()) { |
| 103 | + throw InvalidInputError("no bus stop area defined!"); |
| 104 | + } |
| 105 | +} |
| 106 | + |
| 107 | +BusStopArea::BusStopArea(Id id, const AttributeMap & attributes, const Polygons3d & bus_stop_areas) |
| 108 | +: BusStopArea(constructBusStopAreaData(id, attributes, bus_stop_areas)) |
| 109 | +{ |
| 110 | +} |
| 111 | + |
| 112 | +ConstPolygons3d BusStopArea::busStopAreas() const |
| 113 | +{ |
| 114 | + return getConstPoly(parameters(), RoleName::Refers); |
| 115 | +} |
| 116 | +Polygons3d BusStopArea::busStopAreas() |
| 117 | +{ |
| 118 | + return getPoly(parameters(), RoleName::Refers); |
| 119 | +} |
| 120 | + |
| 121 | +void BusStopArea::addBusStopArea(const Polygon3d & primitive) |
| 122 | +{ |
| 123 | + parameters()["bus_stop_area"].emplace_back(primitive); |
| 124 | +} |
| 125 | + |
| 126 | +bool BusStopArea::removeBusStopArea(const Polygon3d & primitive) |
| 127 | +{ |
| 128 | + return findAndErase(primitive, ¶meters().find("bus_stop_area")->second); |
| 129 | +} |
| 130 | + |
| 131 | +RegisterRegulatoryElement<BusStopArea> regBusStopArea; |
| 132 | +} // namespace format_v2 |
| 133 | + |
| 134 | +} // namespace lanelet::autoware |
| 135 | + |
| 136 | +// NOLINTEND(readability-identifier-naming) |
0 commit comments