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