scenario_simulator_v2 C++ API
distance_condition.hpp
Go to the documentation of this file.
1 // Copyright 2015 TIER IV, Inc. 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 #ifndef OPENSCENARIO_INTERPRETER__SYNTAX__DISTANCE_CONDITION_HPP_
16 #define OPENSCENARIO_INTERPRETER__SYNTAX__DISTANCE_CONDITION_HPP_
17 
28 #include <pugixml.hpp>
29 
31 {
32 inline namespace syntax
33 {
34 /*
35  DistanceCondition (OpenSCENARIO XML 1.3)
36 
37  The current distance between an entity and a position is compared to a given
38  distance (less, greater, equal). Several additional parameters like free
39  space etc. can be defined. The property "alongRoute" is deprecated. If
40  "coordinateSystem" or "relativeDistanceType" are set, "alongRoute" is
41  ignored.
42 
43  <xsd:complexType name="DistanceCondition">
44  <xsd:all>
45  <xsd:element name="Position" type="Position"/>
46  </xsd:all>
47  <xsd:attribute name="alongRoute" type="Boolean">
48  <xsd:annotation>
49  <xsd:appinfo>
50  deprecated
51  </xsd:appinfo>
52  </xsd:annotation>
53  </xsd:attribute>
54  <xsd:attribute name="freespace" type="Boolean" use="required"/>
55  <xsd:attribute name="rule" type="Rule" use="required"/>
56  <xsd:attribute name="value" type="Double" use="required"/>
57  <xsd:attribute name="coordinateSystem" type="CoordinateSystem"/>
58  <xsd:attribute name="relativeDistanceType" type="RelativeDistanceType"/>
59  <xsd:attribute name="routingAlgorithm" type="RoutingAlgorithm"/>
60  </xsd:complexType>
61 */
63 {
64  /*
65  Definition of the coordinate system to be used for calculations. If not
66  provided the value is interpreted as "entity". If set, "alongRoute" is
67  ignored.
68  */
70 
71  /*
72  True: distance is measured between closest bounding box points.
73  False: reference point distance is used.
74  */
76 
77  /*
78  Definition of the coordinate system dimension(s) to be used for calculating
79  distances. If set, "alongRoute" is ignored. If not provided, value is
80  interpreted as "euclideanDistance".
81  */
83 
84  /*
85  Algorithm for path selection/calculation between two positions across
86  roads. Only relevant, if CoordinateSystem is "road"/"lane". Default value
87  if omitted: "undefined".
88  */
90 
91  /*
92  The operator (less, greater, equal).
93  */
94  const Rule rule;
95 
96  /*
97  The distance value. Unit: m; Range: [0..inf[.
98  */
99  const Double value;
100 
101  /*
102  The given position the distance is related to.
103  */
105 
107 
108  std::vector<Double> results; // for description
109 
110  const bool consider_z;
111 
112  explicit DistanceCondition(const pugi::xml_node &, Scope &, const TriggeringEntities &);
113 
114  auto description() const -> std::string;
115 
116  auto distance(const EntityRef &) const -> double;
117 
118  template <
119  CoordinateSystem::value_type, RelativeDistanceType::value_type, RoutingAlgorithm::value_type,
120  Boolean::value_type>
121  auto distance(const EntityRef &) const -> double
122  {
123  throw SyntaxError(__FILE__, ":", __LINE__);
124  }
125 
126  auto evaluate() -> Object;
127 };
128 
129 // Ignore spell miss due to OpenSCENARIO standard.
130 // cspell: ignore euclidian
131 
132 // clang-format off
133 template <> auto DistanceCondition::distance<CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined, false>(const EntityRef &) const -> double;
134 template <> auto DistanceCondition::distance<CoordinateSystem::entity, RelativeDistanceType::euclidianDistance, RoutingAlgorithm::undefined, true >(const EntityRef &) const -> double;
135 template <> auto DistanceCondition::distance<CoordinateSystem::entity, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, false>(const EntityRef &) const -> double;
136 template <> auto DistanceCondition::distance<CoordinateSystem::entity, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, true >(const EntityRef &) const -> double;
137 template <> auto DistanceCondition::distance<CoordinateSystem::entity, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, false>(const EntityRef &) const -> double;
138 template <> auto DistanceCondition::distance<CoordinateSystem::entity, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, true >(const EntityRef &) const -> double;
139 template <> auto DistanceCondition::distance<CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, false>(const EntityRef &) const -> double;
140 template <> auto DistanceCondition::distance<CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::undefined, true >(const EntityRef &) const -> double;
141 template <> auto DistanceCondition::distance<CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, false>(const EntityRef &) const -> double;
142 template <> auto DistanceCondition::distance<CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::undefined, true >(const EntityRef &) const -> double;
143 template <> auto DistanceCondition::distance<CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::shortest, false>(const EntityRef &) const -> double;
144 template <> auto DistanceCondition::distance<CoordinateSystem::lane, RelativeDistanceType::lateral, RoutingAlgorithm::shortest, true >(const EntityRef &) const -> double;
145 template <> auto DistanceCondition::distance<CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::shortest, false>(const EntityRef &) const -> double;
146 template <> auto DistanceCondition::distance<CoordinateSystem::lane, RelativeDistanceType::longitudinal, RoutingAlgorithm::shortest, true >(const EntityRef &) const -> double;
147 // clang-format on
148 } // namespace syntax
149 } // namespace openscenario_interpreter
150 
151 #endif // OPENSCENARIO_INTERPRETER__SYNTAX__DISTANCE_CONDITION_HPP_
Definition: scope.hpp:154
Definition: escape_sequence.hpp:22
Pointer< Expression > Object
Definition: object.hpp:26
Definition: cache.hpp:27
Definition: coordinate_system.hpp:50
Definition: distance_condition.hpp:63
std::vector< Double > results
Definition: distance_condition.hpp:108
const RelativeDistanceType relative_distance_type
Definition: distance_condition.hpp:82
const CoordinateSystem coordinate_system
Definition: distance_condition.hpp:69
const TriggeringEntities triggering_entities
Definition: distance_condition.hpp:106
auto description() const -> std::string
Definition: distance_condition.cpp:64
DistanceCondition(const pugi::xml_node &, Scope &, const TriggeringEntities &)
Definition: distance_condition.cpp:35
auto evaluate() -> Object
Definition: distance_condition.cpp:747
const Position position
Definition: distance_condition.hpp:104
const RoutingAlgorithm routing_algorithm
Definition: distance_condition.hpp:89
const Double value
Definition: distance_condition.hpp:99
const Rule rule
Definition: distance_condition.hpp:94
auto distance(const EntityRef &) const -> double
Definition: distance_condition.cpp:130
const bool consider_z
Definition: distance_condition.hpp:110
const Boolean freespace
Definition: distance_condition.hpp:75
Definition: entity_ref.hpp:35
Definition: relative_distance_type.hpp:55
Definition: routing_algorithm.hpp:48
Definition: triggering_entities.hpp:39