Branch data Line data Source code
1 : : // ----------------- BEGIN LICENSE BLOCK ---------------------------------
2 : : //
3 : : // Copyright (C) 2019-2021 Intel Corporation
4 : : //
5 : : // SPDX-License-Identifier: LGPL-2.1-only
6 : : //
7 : : // ----------------- END LICENSE BLOCK -----------------------------------
8 : :
9 : : #include <ad/map/access/Logging.hpp>
10 : : #include <ad/map/access/Operation.hpp>
11 : : #include <ad/map/match/AdMapMatching.hpp>
12 : : #include <ad/map/route/Planning.hpp>
13 : : #include <ad/rss/core/RssCheck.hpp>
14 : : #include <ad/rss/map/Logging.hpp>
15 : : #include <ad/rss/map/RssSceneCreation.hpp>
16 : : #include <ad/rss/situation/SituationSnapshot.hpp>
17 : : #include <ad/rss/state/ProperResponse.hpp>
18 : : #include <ad/rss/state/RssStateSnapshot.hpp>
19 : : #include <ad/rss/world/WorldModelValidInputRange.hpp>
20 : : #include <gtest/gtest.h>
21 : :
22 : : #include <algorithm>
23 : : #include <fstream>
24 : : #include <streambuf>
25 : :
26 : : struct RssSceneCreationTest : ::testing::Test
27 : : {
28 : : const ::ad::physics::Duration cResponseTimeEgoVehicle{1};
29 : : const ::ad::physics::Duration cResponseTimeOtherVehicles{2};
30 : :
31 : : const ::ad::physics::Acceleration cMaximumLongitudinalAcceleration{3.5};
32 : : const ::ad::physics::Acceleration cMinimumLongitudinalBrakingDeceleleration{-4};
33 : : const ::ad::physics::Acceleration cMaximumLongitudinalBrakingDeceleleration{-8};
34 : : const ::ad::physics::Acceleration cMinimumLongitudinalBrakingDecelelerationCorrect{-3};
35 : :
36 : : const ::ad::physics::Acceleration cMaximumLateralAcceleration{0.2};
37 : : const ::ad::physics::Acceleration cMinimumLateralBrakingDeceleleration{-0.8};
38 : :
39 : : typedef std::tuple<::ad::rss::situation::SituationType, size_t, size_t, ::ad::physics::Speed> ExpectedResultTuple;
40 : : typedef std::tuple<::ad::map::point::Longitude, ::ad::map::point::Latitude, double> ObjectGeoLocationTuple;
41 : :
42 : : enum class TestMode
43 : : {
44 : : withRouteWithSpeedLimit,
45 : : withoutRouteWithoutSpeedLimit
46 : : };
47 : :
48 : 916 : ::ad::rss::world::UnstructuredSettings getUnstructuredSettings()
49 : : {
50 : 916 : ::ad::rss::world::UnstructuredSettings unstructuredSettings;
51 : 916 : unstructuredSettings.pedestrianTurningRadius = ad::physics::Distance(2.0);
52 : 916 : unstructuredSettings.driveAwayMaxAngle = ad::physics::Angle(2.4);
53 : 916 : unstructuredSettings.vehicleYawRateChange = ad::physics::AngularAcceleration(0.3);
54 : 916 : unstructuredSettings.vehicleMinRadius = ad::physics::Distance(3.5);
55 : 916 : unstructuredSettings.vehicleTrajectoryCalculationStep = ad::physics::Duration(0.2);
56 : 916 : return unstructuredSettings;
57 : : }
58 : :
59 : 428 : ::ad::rss::world::RssDynamics getEgoVehicleDynamics(::ad::physics::Speed const maxSpeedOnAcceleration
60 : : = ::ad::physics::Speed(100.))
61 : : {
62 : 428 : ::ad::rss::world::RssDynamics result;
63 : 428 : result.alphaLat.accelMax = cMaximumLateralAcceleration;
64 : 428 : result.alphaLat.brakeMin = cMinimumLateralBrakingDeceleleration;
65 : :
66 : 428 : result.alphaLon.accelMax = cMaximumLongitudinalAcceleration;
67 : 428 : result.alphaLon.brakeMinCorrect = cMinimumLongitudinalBrakingDecelelerationCorrect;
68 : 428 : result.alphaLon.brakeMin = cMinimumLongitudinalBrakingDeceleleration;
69 : 428 : result.alphaLon.brakeMax = cMaximumLongitudinalBrakingDeceleleration;
70 : :
71 : 428 : result.lateralFluctuationMargin = ::ad::physics::Distance(0.);
72 : :
73 : 428 : result.responseTime = cResponseTimeEgoVehicle;
74 : 428 : result.maxSpeedOnAcceleration = maxSpeedOnAcceleration;
75 : :
76 : 428 : result.unstructuredSettings = getUnstructuredSettings();
77 : :
78 : 428 : return result;
79 : : }
80 : :
81 : 488 : ::ad::rss::world::RssDynamics getObjectVehicleDynamics(::ad::physics::Speed const maxSpeedOnAcceleration
82 : : = ::ad::physics::Speed(100.))
83 : : {
84 : 488 : ::ad::rss::world::RssDynamics result;
85 : 488 : result.alphaLat.accelMax = cMaximumLateralAcceleration;
86 : 488 : result.alphaLat.brakeMin = cMinimumLateralBrakingDeceleleration;
87 : :
88 : 488 : result.alphaLon.accelMax = cMaximumLongitudinalAcceleration;
89 : 488 : result.alphaLon.brakeMinCorrect = cMinimumLongitudinalBrakingDecelelerationCorrect;
90 : 488 : result.alphaLon.brakeMin = cMinimumLongitudinalBrakingDeceleleration;
91 : 488 : result.alphaLon.brakeMax = cMaximumLongitudinalBrakingDeceleleration;
92 : :
93 : 488 : result.lateralFluctuationMargin = ::ad::physics::Distance(0.);
94 : :
95 : 488 : result.responseTime = cResponseTimeOtherVehicles;
96 : 488 : result.maxSpeedOnAcceleration = maxSpeedOnAcceleration;
97 : :
98 : 488 : result.unstructuredSettings = getUnstructuredSettings();
99 : :
100 : 488 : return result;
101 : : }
102 : :
103 : : enum class MapToLoad
104 : : {
105 : : Town01,
106 : : Town04,
107 : : None
108 : : };
109 : :
110 : : virtual MapToLoad getMapToLoad() = 0;
111 : :
112 : 214 : void initMap()
113 : : {
114 : : static MapToLoad loadedMap = MapToLoad::None;
115 : :
116 : 214 : MapToLoad mapToLoad = getMapToLoad();
117 [ + + ]: 214 : if (mapToLoad != loadedMap)
118 : : {
119 : 2 : ::ad::map::access::cleanup();
120 [ + + - ]: 2 : switch (mapToLoad)
121 : : {
122 : 1 : case MapToLoad::Town01:
123 : : // using priority to the right intersections
124 [ + - + - : 1 : ASSERT_TRUE(::ad::map::access::init("resources/Town01.txt"));
- + - - -
- - - -
- ]
125 : 1 : break;
126 : 1 : case MapToLoad::Town04:
127 : : {
128 [ + - ]: 1 : std::ifstream fileStream("resources/Town04.xodr");
129 : : std::string town04OpenDriveContent((std::istreambuf_iterator<char>(fileStream)),
130 [ + - ]: 1 : std::istreambuf_iterator<char>());
131 [ + - - + : 1 : ASSERT_TRUE(::ad::map::access::initFromOpenDriveContent(
- - - - -
- - - ]
132 : : town04OpenDriveContent, 0.2, ::ad::map::intersection::IntersectionType::TrafficLight));
133 : 1 : break;
134 : : }
135 : 0 : case MapToLoad::None:
136 : : default:
137 [ # # # # : 0 : ASSERT_TRUE(false);
# # # # #
# ]
138 : 0 : break;
139 : : }
140 : 2 : loadedMap = mapToLoad;
141 : : }
142 : : }
143 : :
144 : : virtual void initializeEgoVehicle() = 0;
145 : :
146 : 214 : void SetUp() override
147 : : {
148 : : //::ad::rss::map::getLogger()->set_level(spdlog::level::debug);
149 : : //::ad::map::access::getLogger()->set_level(spdlog::level::trace);
150 : 214 : initMap();
151 : 214 : initializeEgoVehicle();
152 : 214 : }
153 : :
154 : 214 : void TearDown() override
155 : : {
156 : 214 : }
157 : :
158 : 849 : void initializeObjectGeo(ObjectGeoLocationTuple const &objectLocation, ::ad::map::match::Object &object)
159 : : {
160 : 849 : auto const lon = std::get<0>(objectLocation);
161 : 849 : auto const lat = std::get<1>(objectLocation);
162 [ + - ]: 849 : auto const yawAngle = ::ad::map::point::createENUHeading(std::get<2>(objectLocation));
163 : 849 : auto positionGeo = ::ad::map::point::createGeoPoint(lon, lat, ::ad::map::point::Altitude(0.));
164 [ + - + - ]: 849 : initializeObjectENU(::ad::map::point::toENU(positionGeo), yawAngle, object);
165 : 849 : }
166 : :
167 : 851 : void initializeObjectENU(::ad::map::point::ENUPoint const &position,
168 : : ::ad::map::point::ENUHeading const &heading,
169 : : ::ad::map::match::Object &object)
170 : : {
171 : 851 : object.enuPosition.centerPoint = position;
172 : 851 : object.enuPosition.heading = heading;
173 : 851 : object.enuPosition.dimension.length = ::ad::physics::Distance(4.5);
174 : 851 : object.enuPosition.dimension.width = ::ad::physics::Distance(2.);
175 : 851 : object.enuPosition.dimension.height = ::ad::physics::Distance(1.5);
176 [ + - ]: 851 : object.enuPosition.enuReferencePoint = ::ad::map::access::getENUReferencePoint();
177 : :
178 [ + - ]: 851 : ::ad::map::match::AdMapMatching mapMatching;
179 : : object.mapMatchedBoundingBox
180 [ + - ]: 851 : = mapMatching.getMapMatchedBoundingBox(object.enuPosition, ::ad::physics::Distance(2.0));
181 : :
182 [ + - - + : 851 : ASSERT_GE(object.mapMatchedBoundingBox.referencePointPositions.size(),
- - - - -
- ]
183 : : static_cast<uint64_t>(::ad::map::match::ObjectReferencePoints::Center));
184 [ + - - + : 851 : ASSERT_GE(object.mapMatchedBoundingBox
- - - - -
- ]
185 : : .referencePointPositions[static_cast<uint64_t>(::ad::map::match::ObjectReferencePoints::Center)]
186 : : .size(),
187 : : 0u);
188 : : }
189 : :
190 : 212 : void checkSceneResults(::ad::rss::world::WorldModel const &worldModel,
191 : : ::ad::rss::world::ObjectId const &otherVehicleId,
192 : : std::vector<ExpectedResultTuple> const &expectedResults)
193 : : {
194 [ + - - + : 212 : EXPECT_TRUE(withinValidInputRange(worldModel));
- - - - -
- - - ]
195 [ + - - + : 212 : ASSERT_EQ(expectedResults.size(), worldModel.scenes.size());
- - - - -
- ]
196 : :
197 [ + - ]: 424 : std::vector<ExpectedResultTuple> notMatchedResults = expectedResults;
198 [ + + ]: 487 : for (auto i = 0u; i < worldModel.scenes.size(); ++i)
199 : : {
200 : 275 : auto &scene = worldModel.scenes[i];
201 [ + - - + : 275 : EXPECT_TRUE(withinValidInputRange(scene)) << i;
- - - - -
- - - -
- ]
202 [ + - - + : 275 : EXPECT_EQ(::ad::rss::world::ObjectType::OtherVehicle, scene.object.objectType) << i;
- - - - -
- - - ]
203 [ + - - + : 275 : EXPECT_EQ(otherVehicleId, scene.object.objectId) << i;
- - - - -
- - - ]
204 : : auto findResult
205 : : = std::find_if(notMatchedResults.begin(),
206 : : notMatchedResults.end(),
207 : 556 : [this, scene](ExpectedResultTuple const &expectedResultTuple) {
208 : 281 : return (std::get<0>(expectedResultTuple) == scene.situationType)
209 [ + - ]: 275 : && (std::get<1>(expectedResultTuple) == scene.egoVehicleRoad.size())
210 [ + - ]: 275 : && (std::get<2>(expectedResultTuple) == scene.intersectingRoad.size())
211 [ + + + - : 556 : && (getObjectVehicleDynamics(std::get<3>(expectedResultTuple)) == scene.objectRssDynamics);
+ - ]
212 [ + - + - ]: 275 : });
213 [ + - ]: 275 : if (findResult != notMatchedResults.end())
214 : : {
215 [ + - ]: 275 : notMatchedResults.erase(findResult);
216 : : }
217 : : else
218 : : {
219 [ # # # # : 0 : EXPECT_TRUE(false) << " scene index: " << i << " not found" << scene;
# # # # #
# # # # #
# # # # ]
220 : : }
221 : : }
222 [ - + - - : 212 : EXPECT_TRUE(notMatchedResults.empty())
- - - - ]
223 [ # # # # : 0 : << " not all expected results observed: " << std::get<0>(notMatchedResults[0]) << ", "
# # ]
224 [ # # # # : 0 : << std::get<1>(notMatchedResults[0]) << ", " << std::get<2>(notMatchedResults[0]) << ", "
# # # # ]
225 [ # # # # ]: 0 : << getObjectVehicleDynamics(std::get<3>(notMatchedResults[0]));
226 : : }
227 : :
228 : 212 : void shortenEgoRoute(ObjectGeoLocationTuple const &egoGeoLocation)
229 : : {
230 : 212 : initializeObjectGeo(egoGeoLocation, egoMatchObject);
231 : :
232 : 212 : ::ad::map::route::shortenRoute(
233 : : egoMatchObject.mapMatchedBoundingBox
234 : 212 : .referencePointPositions[int32_t(::ad::map::match::ObjectReferencePoints::Center)],
235 : 212 : egoRoute,
236 : : ::ad::map::route::ShortenRouteMode::DontCutIntersectionAndPrependIfSucceededBeforeRoute);
237 : 212 : }
238 : :
239 : : virtual TestMode getTestMode() = 0;
240 : :
241 : 212 : void performSceneTest(ObjectGeoLocationTuple const &egoLocation,
242 : : ObjectGeoLocationTuple const &otherLocation,
243 : : std::vector<ExpectedResultTuple> const &expectedResults)
244 : : {
245 [ + - ]: 424 : ::ad::rss::map::RssSceneCreation sceneCreation(1u, getEgoVehicleDynamics());
246 : :
247 [ + - ]: 212 : initializeEgoVehicle();
248 [ + - ]: 212 : shortenEgoRoute(egoLocation);
249 : :
250 : 212 : ::ad::rss::world::ObjectId otherVehicleId{10};
251 : 212 : ::ad::physics::Speed otherVehicleSpeed{10.};
252 : 212 : ::ad::physics::AngularVelocity otherVehicleYawRate{0.};
253 : 212 : ::ad::physics::Angle otherVehicleSteeringAngle{0.};
254 : :
255 : 424 : ::ad::map::match::Object otherMatchObject;
256 : :
257 [ + - ]: 212 : initializeObjectGeo(otherLocation, otherMatchObject);
258 : :
259 : 424 : ::ad::map::route::FullRoute testRoute;
260 : 212 : auto speedLimitMode{::ad::rss::map::RssSceneCreation::RestrictSpeedLimitMode::None};
261 [ + - + + ]: 212 : if (getTestMode() == TestMode::withRouteWithSpeedLimit)
262 : : {
263 [ + - ]: 150 : testRoute = egoRoute;
264 : 150 : speedLimitMode = ::ad::rss::map::RssSceneCreation::RestrictSpeedLimitMode::IncreasedSpeedLimit10;
265 : : }
266 : :
267 : 424 : ::ad::rss::map::RssObjectData egoObjectData;
268 : 212 : egoObjectData.id = egoVehicleId;
269 : 212 : egoObjectData.type = ::ad::rss::world::ObjectType::EgoVehicle;
270 [ + - ]: 212 : egoObjectData.matchObject = egoMatchObject;
271 : 212 : egoObjectData.speed = egoSpeed;
272 : 212 : egoObjectData.yawRate = egoYawRate;
273 : 212 : egoObjectData.steeringAngle = egoSteeringAngle;
274 : 212 : egoObjectData.rssDynamics = getEgoVehicleDynamics();
275 : :
276 : 424 : ::ad::rss::map::RssObjectData otherObjectData;
277 : 212 : otherObjectData.id = otherVehicleId;
278 : 212 : otherObjectData.type = ::ad::rss::world::ObjectType::OtherVehicle;
279 [ + - ]: 212 : otherObjectData.matchObject = otherMatchObject;
280 : 212 : otherObjectData.speed = otherVehicleSpeed;
281 : 212 : otherObjectData.yawRate = otherVehicleYawRate;
282 : 212 : otherObjectData.steeringAngle = otherVehicleSteeringAngle;
283 : 212 : otherObjectData.rssDynamics = getObjectVehicleDynamics();
284 : :
285 [ + - - + : 212 : EXPECT_TRUE(sceneCreation.appendScenes(egoObjectData,
- - - - -
- - - ]
286 : : testRoute,
287 : : otherObjectData,
288 : : speedLimitMode,
289 : : ::ad::map::landmark::LandmarkIdSet(),
290 : : ::ad::rss::map::RssMode::Structured));
291 : :
292 [ + - ]: 424 : auto const worldModel = sceneCreation.getWorldModel();
293 [ + - ]: 212 : checkSceneResults(worldModel, otherVehicleId, expectedResults);
294 : 212 : }
295 : :
296 : : ::ad::rss::world::ObjectId egoVehicleId{123u};
297 : : ::ad::physics::Speed egoSpeed;
298 : : ::ad::physics::AngularVelocity egoYawRate;
299 : : ::ad::physics::Angle egoSteeringAngle;
300 : : ::ad::map::match::Object egoMatchObject;
301 : : ::ad::map::route::FullRoute egoRoute;
302 : : };
303 : :
304 : : struct RssSceneCreationTestTown01 : RssSceneCreationTest
305 : : {
306 : 213 : MapToLoad getMapToLoad() override
307 : : {
308 : 213 : return MapToLoad::Town01;
309 : : }
310 : :
311 : 425 : void initializeEgoVehicle() override
312 : : {
313 : : // laneId: offset 240151:0.55
314 : : auto egoGeoLocation = std::make_tuple(
315 [ + - ]: 425 : ::ad::map::point::Longitude(8.00125444865324766), ::ad::map::point::Latitude(48.99758627528235877), M_PI_2);
316 : :
317 [ + - ]: 425 : initializeObjectGeo(egoGeoLocation, egoMatchObject);
318 : :
319 : 425 : egoSpeed = ::ad::physics::Speed(5.);
320 : 425 : egoYawRate = ::ad::physics::AngularVelocity(0.);
321 : 425 : egoSteeringAngle = ::ad::physics::Angle(0.);
322 : :
323 : : // laneId: offset 120149:0.52 (ego turn right)
324 : : auto positionEndGeo = ::ad::map::point::createGeoPoint(::ad::map::point::Longitude(8.003),
325 : : ::ad::map::point::Latitude(48.99821051747871792),
326 : 425 : ::ad::map::point::Altitude(0.));
327 : :
328 : 425 : egoRoute = ::ad::map::route::planning::planRoute(
329 : : egoMatchObject.mapMatchedBoundingBox
330 : 425 : .referencePointPositions[static_cast<uint64_t>(::ad::map::match::ObjectReferencePoints::Center)][0]
331 [ + - ]: 425 : .lanePoint.paraPoint,
332 : 425 : positionEndGeo);
333 : 425 : }
334 : :
335 : : /*
336 : : * | NorthIncoming NorthOutgoing |
337 : : * | |
338 : : * | |
339 : : * | NorthEntering NorthExiting |______________________
340 : : * |
341 : : * | EastEntering EastIncoming
342 : : * |
343 : : * | EastExiting EastOutgoing
344 : : * | _______________________
345 : : * | SouthExiting SouthEntering |
346 : : * | |
347 : : * | |
348 : : * | SouthOutgoing SouthIncoming |
349 : : *
350 : : */
351 : :
352 : 68 : ObjectGeoLocationTuple locationSouthIncoming()
353 : : {
354 : : // laneId: 240151 directly in front of intersection
355 : : return std::make_tuple(
356 [ + - ]: 136 : ::ad::map::point::Longitude(8.00125444865324766), ::ad::map::point::Latitude(48.9980), M_PI_2);
357 : : }
358 : :
359 : 60 : ObjectGeoLocationTuple locationSouthEntering()
360 : : {
361 : : // laneId: 240151:0. & 1290149:0. (right turn lane) & 1360149:0. (straight lane)
362 [ + - ]: 120 : return std::make_tuple(::ad::map::point::Longitude(8.0012619), ::ad::map::point::Latitude(48.9981266), M_PI_2);
363 : : }
364 : :
365 : 54 : ObjectGeoLocationTuple locationSouth2East()
366 : : {
367 : : // laneId: 1290149:0.3, starting right turn
368 [ + - ]: 108 : return std::make_tuple(::ad::map::point::Longitude(8.0012731), ::ad::map::point::Latitude(48.9981734), M_PI_2 / 2.);
369 : : }
370 : :
371 : 55 : ObjectGeoLocationTuple locationEastExiting()
372 : : {
373 : : // laneId: 120149:0 & 1290149:1. right turn around the intersection
374 [ + - ]: 110 : return std::make_tuple(::ad::map::point::Longitude(8.0013843), ::ad::map::point::Latitude(48.9982095), 0.);
375 : : }
376 : :
377 : 56 : ObjectGeoLocationTuple locationEastOutgoing()
378 : : {
379 : : // laneId: 120149:0.16 right turn around the intersection
380 : : return std::make_tuple(
381 [ + - ]: 112 : ::ad::map::point::Longitude(8.00188527300496979), ::ad::map::point::Latitude(48.99821051747871792), 0.);
382 : : }
383 : :
384 : 14 : ObjectGeoLocationTuple locationEastIncoming()
385 : : {
386 : : // laneId: 120151:0.16
387 : : return std::make_tuple(
388 [ + - ]: 28 : ::ad::map::point::Longitude(8.00188527300496979), ::ad::map::point::Latitude(48.99824), M_PI);
389 : : }
390 : :
391 : 10 : ObjectGeoLocationTuple locationEastEntering()
392 : : {
393 : : // laneId: 120151:0.16
394 [ + - ]: 20 : return std::make_tuple(::ad::map::point::Longitude(8.0013870), ::ad::map::point::Latitude(48.9982463), M_PI);
395 : : }
396 : :
397 : 5 : ObjectGeoLocationTuple locationEast2North()
398 : : {
399 : : // laneId: 1370149:0.5
400 : : return std::make_tuple(
401 [ + - ]: 10 : ::ad::map::point::Longitude(8.0012889), ::ad::map::point::Latitude(48.9982608), 3. * M_PI_2 / 2.);
402 : : }
403 : :
404 : 10 : ObjectGeoLocationTuple locationSouth2North()
405 : : {
406 : : // laneId: 13690249:0.5, second half of intersection when driving straight
407 [ + - ]: 20 : return std::make_tuple(::ad::map::point::Longitude(8.0012631), ::ad::map::point::Latitude(48.9982781), M_PI_2);
408 : : }
409 : :
410 : 15 : ObjectGeoLocationTuple locationNorthExiting()
411 : : {
412 : : // laneId: 13690249:1. & 230151:1., outgoing border of the intersection when driving straight
413 [ + - ]: 30 : return std::make_tuple(::ad::map::point::Longitude(8.0012623), ::ad::map::point::Latitude(48.9983242), M_PI_2);
414 : : }
415 : :
416 : 16 : ObjectGeoLocationTuple locationNorthOutgoing()
417 : : {
418 : : // laneId: 230151:0.94 after the intersection when driving straight
419 [ + - ]: 32 : return std::make_tuple(::ad::map::point::Longitude(8.0012635), ::ad::map::point::Latitude(48.9984330), M_PI_2);
420 : : }
421 : :
422 : 14 : ObjectGeoLocationTuple locationNorthIncoming()
423 : : {
424 : : // laneId: 230149, straight through the intersection in opposite direction
425 [ + - ]: 28 : return std::make_tuple(::ad::map::point::Longitude(8.00120), ::ad::map::point::Latitude(48.9985), -M_PI_2);
426 : : }
427 : :
428 : 10 : ObjectGeoLocationTuple locationNorthEntering()
429 : : {
430 : : // laneId: 230149:1.0 & 1350251:1.0 touching straight through the intersection in opposite direction
431 [ + - ]: 20 : return std::make_tuple(::ad::map::point::Longitude(8.0012081), ::ad::map::point::Latitude(48.9983242), -M_PI_2);
432 : : }
433 : :
434 : 5 : ObjectGeoLocationTuple locationNorth2East()
435 : : {
436 : : // laneId: 1380149:0.5
437 : : return std::make_tuple(
438 [ + - ]: 10 : ::ad::map::point::Longitude(8.0012391), ::ad::map::point::Latitude(48.9982440), -M_PI_2 / 2.);
439 : : }
440 : :
441 : 5 : ObjectGeoLocationTuple locationNorth2South()
442 : : {
443 : : // laneId: 1350151:0.5, mid straight through the intersection in opposite direction
444 [ + - ]: 10 : return std::make_tuple(::ad::map::point::Longitude(8.0012077), ::ad::map::point::Latitude(48.9981817), -M_PI_2);
445 : : }
446 : :
447 : 5 : ObjectGeoLocationTuple locationEast2South()
448 : : {
449 : : // laneId: 1300149:0.5
450 : : return std::make_tuple(
451 [ + - ]: 10 : ::ad::map::point::Longitude(8.0012368), ::ad::map::point::Latitude(48.9982053), 5. * M_PI_2 / 2.);
452 : : }
453 : :
454 : 10 : ObjectGeoLocationTuple locationSouthExiting()
455 : : {
456 : : // laneId: 240149:0. opposite direction in front across intersection
457 [ + - ]: 20 : return std::make_tuple(::ad::map::point::Longitude(8.0012069), ::ad::map::point::Latitude(48.9981252), -M_PI_2);
458 : : }
459 : :
460 : 12 : ObjectGeoLocationTuple locationSouthOutgoing()
461 : : {
462 : : // laneId: 240149, opposite direction no intersection in between
463 [ + - ]: 24 : return std::make_tuple(::ad::map::point::Longitude(8.00120), ::ad::map::point::Latitude(48.9980), -M_PI_2);
464 : : }
465 : : };
466 : :
467 : : struct RssSceneCreationTestWithRoute : public RssSceneCreationTestTown01
468 : : {
469 : 150 : TestMode getTestMode() override
470 : : {
471 : 150 : return TestMode::withRouteWithSpeedLimit;
472 : : }
473 : : };
474 : :
475 : : struct RssSceneCreationTestWithoutRoute : public RssSceneCreationTestTown01
476 : : {
477 : 62 : TestMode getTestMode() override
478 : : {
479 : 62 : return TestMode::withoutRouteWithoutSpeedLimit;
480 : : }
481 : : };
|