15 #ifndef OPENSCENARIO_INTERPRETER__SIMULATOR_CORE_HPP_
16 #define OPENSCENARIO_INTERPRETER__SIMULATOR_CORE_HPP_
41 static inline std::unique_ptr<traffic_simulator::API> core =
nullptr;
44 template <
typename Node,
typename... Ts>
49 core = std::make_unique<traffic_simulator::API>(
50 node, configuration, std::forward<decltype(
xs)>(
xs)...);
52 throw Error(
"The simulator core has already been instantiated.");
56 static auto active() {
return static_cast<bool>(core); }
61 core->despawnEntities();
62 core->closeZMQConnection();
67 static auto update() ->
void { core->updateFrame(); }
78 template <
typename T,
typename std::enable_if_t<std::is_same_v<T, NativeLanePosition>,
int> = 0>
81 constexpr
bool include_crosswalk{
false};
84 pose, include_crosswalk, core->getHdmapUtils())) {
85 return result.value();
88 "The specified WorldPosition = [", pose.position.x,
", ", pose.position.y,
", ",
90 "] could not be approximated to the proper Lane. Perhaps the "
91 "WorldPosition points to a location where multiple lanes overlap, and "
92 "there are at least two or more candidates for a LanePosition that "
93 "can be approximated to that WorldPosition. This issue can be "
94 "resolved by strictly specifying the location using LanePosition "
95 "instead of WorldPosition");
100 typename T,
typename std::enable_if_t<std::is_same_v<T, NativeWorldPosition>,
int> = 0>
109 if (
const auto from_entity = core->getEntity(from_entity_name)) {
110 if (
const auto to_entity = core->getEntity(to_entity_name)) {
113 from_entity->getMapPose(), to_entity->getMapPose()))
114 return relative_pose.value();
123 if (
const auto from_entity = core->getEntity(from_entity_name)) {
125 const auto relative_pose =
127 return relative_pose.value();
136 if (
const auto to_entity = core->getEntity(to_entity_name)) {
138 const auto relative_pose =
140 return relative_pose.value();
148 const RoutingAlgorithm::value_type routing_algorithm = RoutingAlgorithm::undefined)
151 if (
const auto to_entity = core->getEntity(to_entity_name)) {
152 if (
const auto to_lanelet_pose = to_entity->getCanonicalizedLaneletPose()) {
154 from_entity_name, to_lanelet_pose.value(), routing_algorithm);
162 const RoutingAlgorithm::value_type routing_algorithm = RoutingAlgorithm::undefined)
165 if (
const auto from_entity = core->getEntity(from_entity_name)) {
166 if (
const auto from_lanelet_pose = from_entity->getCanonicalizedLaneletPose()) {
168 from_lanelet_pose.value(), to_lanelet_pose, routing_algorithm);
176 const RoutingAlgorithm::value_type routing_algorithm = RoutingAlgorithm::undefined)
179 const bool allow_lane_change = (routing_algorithm == RoutingAlgorithm::value_type::shortest);
181 from_lanelet_pose, to_lanelet_pose, allow_lane_change, core->getHdmapUtils());
186 const RoutingAlgorithm::value_type routing_algorithm = RoutingAlgorithm::undefined)
188 if (
const auto from_entity = core->getEntity(from_entity_name)) {
189 if (
const auto to_entity = core->getEntity(to_entity_name)) {
190 if (
const auto from_lanelet_pose = from_entity->getCanonicalizedLaneletPose()) {
191 if (
const auto to_lanelet_pose = to_entity->getCanonicalizedLaneletPose()) {
193 from_lanelet_pose.value(), from_entity->getBoundingBox(), to_lanelet_pose.value(),
194 to_entity->getBoundingBox(), routing_algorithm);
204 const RoutingAlgorithm::value_type routing_algorithm = RoutingAlgorithm::undefined)
206 if (
const auto from_entity = core->getEntity(from_entity_name)) {
207 if (
const auto from_lanelet_pose = from_entity->getCanonicalizedLaneletPose()) {
209 from_lanelet_pose.value(), from_entity->getBoundingBox(), to_lanelet_pose,
210 traffic_simulator_msgs::msg::BoundingBox(), routing_algorithm);
218 const traffic_simulator_msgs::msg::BoundingBox & from_bounding_box,
220 const traffic_simulator_msgs::msg::BoundingBox & to_bounding_box,
221 const RoutingAlgorithm::value_type routing_algorithm = RoutingAlgorithm::undefined)
224 const bool allow_lane_change = (routing_algorithm == RoutingAlgorithm::value_type::shortest);
226 from_lanelet_pose, from_bounding_box, to_lanelet_pose, to_bounding_box, allow_lane_change,
227 core->getHdmapUtils());
233 if (
const auto from_entity = core->getEntity(from_entity_name)) {
234 if (
const auto to_entity = core->getEntity(to_entity_name)) {
237 from_entity->getMapPose(), from_entity->getBoundingBox(), to_entity->getMapPose(),
238 to_entity->getBoundingBox())) {
239 return relative_pose.value();
249 if (
const auto from_entity = core->getEntity(from_entity_name)) {
252 from_entity->getMapPose(), from_entity->getBoundingBox(), to_map_pose,
253 traffic_simulator_msgs::msg::BoundingBox())) {
254 return relative_pose.value();
262 const RoutingAlgorithm::value_type routing_algorithm = RoutingAlgorithm::undefined) ->
int
264 if (
const auto from_entity = core->getEntity(from_entity_name)) {
265 if (
const auto to_entity = core->getEntity(to_entity_name)) {
266 const bool allow_lane_change =
267 (routing_algorithm == RoutingAlgorithm::value_type::shortest);
270 from_entity->getCanonicalizedLaneletPose().value(),
271 to_entity->getCanonicalizedLaneletPose().value(), allow_lane_change,
272 core->getHdmapUtils())) {
273 return lane_changes.value().first - lane_changes.value().second;
278 "Failed to evaluate lateral relative lanes between ", from_entity_name,
" and ",
286 template <
typename... Ts>
289 core->requestClearRoute(entity_ref);
290 return core->requestAcquirePosition(entity_ref, std::forward<decltype(
xs)>(
xs)...);
293 template <
typename... Ts>
296 return core->spawn(std::forward<decltype(
xs)>(
xs)...);
299 template <
typename EntityRef,
typename DynamicConstra
ints>
303 return core->setBehaviorParameter(entity_ref, [&]() {
304 auto behavior_parameter = core->getBehaviorParameter(entity_ref);
306 if (not std::isinf(dynamic_constraints.max_speed)) {
307 behavior_parameter.dynamic_constraints.max_speed = dynamic_constraints.max_speed;
310 if (not std::isinf(dynamic_constraints.max_acceleration)) {
311 behavior_parameter.dynamic_constraints.max_acceleration =
312 dynamic_constraints.max_acceleration;
315 if (not std::isinf(dynamic_constraints.max_acceleration_rate)) {
316 behavior_parameter.dynamic_constraints.max_acceleration_rate =
317 dynamic_constraints.max_acceleration_rate;
320 if (not std::isinf(dynamic_constraints.max_deceleration)) {
321 behavior_parameter.dynamic_constraints.max_deceleration =
322 dynamic_constraints.max_deceleration;
325 if (not std::isinf(dynamic_constraints.max_deceleration_rate)) {
326 behavior_parameter.dynamic_constraints.max_deceleration_rate =
327 dynamic_constraints.max_deceleration_rate;
330 return behavior_parameter;
334 template <
typename Controller>
338 core->setVelocityLimit(
339 entity_ref, controller.properties.template get<Double>(
340 "maxSpeed", std::numeric_limits<Double::value_type>::max()));
342 core->setBehaviorParameter(entity_ref, [&]() {
343 auto message = core->getBehaviorParameter(entity_ref);
344 message.see_around = not controller.properties.template get<Boolean>(
"isBlind");
346 message.dynamic_constraints.max_acceleration =
347 controller.properties.template get<Double>(
"maxAcceleration", 10.0);
348 message.dynamic_constraints.max_acceleration_rate =
349 controller.properties.template get<Double>(
"maxAccelerationRate", 3.0);
350 message.dynamic_constraints.max_deceleration =
351 controller.properties.template get<Double>(
"maxDeceleration", 10.0);
352 message.dynamic_constraints.max_deceleration_rate =
353 controller.properties.template get<Double>(
"maxDecelerationRate", 3.0);
354 message.dynamic_constraints.max_speed =
355 controller.properties.template get<Double>(
"maxSpeed", 50.0);
359 if (controller.isAutoware()) {
360 core->attachImuSensor(entity_ref, [&]() {
361 simulation_api_schema::ImuSensorConfiguration configuration;
362 configuration.set_entity(entity_ref);
363 configuration.set_frame_id(
"base_link");
364 configuration.set_add_gravity(
true);
365 configuration.set_use_seed(
true);
366 configuration.set_seed(0);
367 configuration.set_noise_standard_deviation_orientation(0.01);
368 configuration.set_noise_standard_deviation_twist(0.01);
369 configuration.set_noise_standard_deviation_acceleration(0.01);
370 return configuration;
373 core->attachLidarSensor([&]() {
374 simulation_api_schema::LidarConfiguration configuration;
376 auto degree_to_radian = [](
auto degree) {
377 return degree / 180.0 * boost::math::constants::pi<double>();
381 configuration.set_architecture_type(core->getROS2Parameter<
std::string>(
"architecture_type",
"awf/universe"));
382 configuration.set_entity(entity_ref);
383 configuration.set_horizontal_resolution(degree_to_radian(controller.properties.template get<Double>(
"pointcloudHorizontalResolution", 1.0)));
384 configuration.set_lidar_sensor_delay(controller.properties.template get<Double>(
"pointcloudPublishingDelay"));
385 configuration.set_scan_duration(0.1);
388 const auto vertical_field_of_view = degree_to_radian(
389 controller.properties.template get<Double>(
"pointcloudVerticalFieldOfView", 30.0));
391 const auto channels =
392 controller.properties.template get<UnsignedInteger>(
"pointcloudChannels", 16);
394 for (std::size_t i = 0; i < channels; ++i) {
395 configuration.add_vertical_angles(
396 vertical_field_of_view / 2 - vertical_field_of_view / channels * i);
399 return configuration;
402 core->attachDetectionSensor([&]() {
403 simulation_api_schema::DetectionSensorConfiguration configuration;
405 configuration.set_architecture_type(core->getROS2Parameter<
std::string>(
"architecture_type",
"awf/universe"));
406 configuration.set_entity(entity_ref);
407 configuration.set_detect_all_objects_in_range(controller.properties.template get<Boolean>(
"isClairvoyant"));
408 configuration.set_object_recognition_delay(controller.properties.template get<Double>(
"detectedObjectPublishingDelay"));
409 configuration.set_pos_noise_stddev(controller.properties.template get<Double>(
"detectedObjectPositionStandardDeviation"));
410 configuration.set_probability_of_lost(controller.properties.template get<Double>(
"detectedObjectMissingProbability"));
411 configuration.set_random_seed(controller.properties.template get<UnsignedInteger>(
"randomSeed"));
412 configuration.set_range(controller.properties.template get<Double>(
"detectionSensorRange",300.0));
413 configuration.set_object_recognition_ground_truth_delay(controller.properties.template get<Double>(
"detectedObjectGroundTruthPublishingDelay"));
414 configuration.set_update_duration(0.1);
416 return configuration;
419 core->attachOccupancyGridSensor([&]() {
420 simulation_api_schema::OccupancyGridSensorConfiguration configuration;
422 configuration.set_architecture_type(core->getROS2Parameter<
std::string>(
"architecture_type",
"awf/universe"));
423 configuration.set_entity(entity_ref);
424 configuration.set_filter_by_range(controller.properties.template get<Boolean>(
"isClairvoyant"));
425 configuration.set_height(200);
426 configuration.set_range(300);
427 configuration.set_resolution(0.5);
428 configuration.set_update_duration(0.1);
429 configuration.set_width(200);
431 return configuration;
434 core->attachPseudoTrafficLightDetector([&]() {
435 simulation_api_schema::PseudoTrafficLightDetectorConfiguration configuration;
436 configuration.set_architecture_type(
437 core->getROS2Parameter<
std::string>(
"architecture_type",
"awf/universe"));
438 return configuration;
441 core->asFieldOperatorApplication(entity_ref)
442 .declare_parameter<
bool>(
443 "allow_goal_modification",
444 controller.properties.template get<Boolean>(
"allowGoalModification"));
446 for (
const auto & module :
448 manual_modules_string.erase(
450 manual_modules_string.begin(), manual_modules_string.end(),
451 [](
const auto & c) { return std::isspace(c); }),
452 manual_modules_string.end());
454 std::vector<std::string> modules;
456 std::istringstream modules_stream(manual_modules_string);
457 while (std::getline(modules_stream, buffer,
',')) {
458 modules.push_back(buffer);
461 }(controller.properties.template get<String>(
462 "featureIdentifiersRequiringExternalPermissionForAutonomousDecisions"))) {
464 core->asFieldOperatorApplication(entity_ref)
465 .requestAutoModeForCooperation(module,
false);
466 }
catch (
const Error & error) {
468 "featureIdentifiersRequiringExternalPermissionForAutonomousDecisions is not "
469 "supported in this environment: ",
476 template <
typename... Ts>
479 return core->requestAssignRoute(std::forward<decltype(
xs)>(
xs)...);
482 template <
typename... Ts>
485 return core->despawn(std::forward<decltype(
xs)>(
xs)...);
488 template <
typename... Ts>
491 return core->requestFollowTrajectory(std::forward<decltype(
xs)>(
xs)...);
494 template <
typename... Ts>
497 return core->requestLaneChange(std::forward<decltype(
xs)>(
xs)...);
500 template <
typename... Ts>
503 return core->requestSpeedChange(std::forward<decltype(
xs)>(
xs)...);
506 template <
typename... Ts>
509 return core->setEntityStatus(std::forward<decltype(
xs)>(
xs)...);
512 template <
typename... Ts>
515 return core->requestWalkStraight(std::forward<decltype(
xs)>(
xs)...);
523 template <
typename... Ts>
526 return core->getCurrentAccel(std::forward<decltype(
xs)>(
xs)...).linear.x;
529 template <
typename... Ts>
532 return core->checkCollision(std::forward<decltype(
xs)>(
xs)...);
535 template <
typename... Ts>
540 if (
const auto from_entity = core->getEntity(from_entity_name)) {
541 if (
const auto to_entity = core->getEntity(to_entity_name)) {
544 from_entity->getMapPose(), from_entity->getBoundingBox(), to_entity->getMapPose(),
545 to_entity->getBoundingBox())) {
550 return std::numeric_limits<double>::quiet_NaN();
553 template <
typename... Ts>
557 return core->getCurrentTime(std::forward<decltype(
xs)>(
xs)...);
559 return std::numeric_limits<double>::quiet_NaN();
563 template <
typename... Ts>
566 return core->getCurrentTwist(std::forward<decltype(
xs)>(
xs)...).linear.x;
569 template <
typename... Ts>
572 return core->getStandStillDuration(std::forward<decltype(
xs)>(
xs)...);
575 template <
typename... Ts>
578 if (
const auto result = core->getTimeHeadway(std::forward<decltype(
xs)>(
xs)...); result) {
579 return result.value();
581 using value_type =
typename std::decay<decltype(result)>::type::value_type;
582 return std::numeric_limits<value_type>::quiet_NaN();
590 template <
typename Performance,
typename Properties>
595 core->activateOutOfRangeJob(
597 +performance.
max_acceleration, properties.template get<Double>(
"minJerk", Double::lowest()),
598 properties.template get<Double>(
"maxJerk", Double::max()));
601 template <
typename... Ts>
604 return core->asFieldOperatorApplication(std::forward<decltype(
xs)>(
xs)...);
609 return core->startNpcLogic();
612 template <
typename... Ts>
615 return core->getCurrentAction(std::forward<decltype(
xs)>(
xs)...);
618 template <
typename EntityRef,
typename OSCLanePosition>
620 const EntityRef & entity_ref,
const OSCLanePosition & osc_lane_position)
622 if (
const auto entity = core->getEntity(entity_ref)) {
623 const auto from_map_pose = entity->getMapPose();
626 const auto relative_pose =
628 return static_cast<Double>(std::abs(
632 return Double::nan();
635 template <
typename EntityRef>
638 if (
const auto entity = core->getEntity(entity_ref)) {
639 if (
const auto canonicalized_lanelet_pose = entity->getCanonicalizedLaneletPose()) {
640 return static_cast<Double>(std::abs(
644 return Double::nan();
647 template <
typename... Ts>
651 .sendCooperateCommand(std::forward<decltype(
xs)>(
xs)...);
655 template <
typename... Ts>
658 return core->getConventionalTrafficLights()->setTrafficLightsState(
659 std::forward<decltype(
xs)>(
xs)...);
662 template <
typename... Ts>
665 return core->getConventionalTrafficLights()->setTrafficLightsConfidence(
666 std::forward<decltype(
xs)>(
xs)...);
669 template <
typename... Ts>
672 return core->getConventionalTrafficLights()->getTrafficLightsComposedState(
673 std::forward<decltype(
xs)>(
xs)...);
676 template <
typename... Ts>
679 return core->getConventionalTrafficLights()->compareTrafficLightsState(
680 std::forward<decltype(
xs)>(
xs)...);
683 template <
typename... Ts>
686 return core->getConventionalTrafficLights()->resetUpdate(std::forward<decltype(
xs)>(
xs)...);
689 template <
typename... Ts>
692 return core->getV2ITrafficLights()->setTrafficLightsState(std::forward<decltype(
xs)>(
xs)...);
695 template <
typename... Ts>
698 return core->getV2ITrafficLights()->resetUpdate(std::forward<decltype(
xs)>(
xs)...);
Definition: simulator_core.hpp:284
static auto applyWalkStraightAction(Ts &&... xs)
Definition: simulator_core.hpp:513
static auto applyFollowTrajectoryAction(Ts &&... xs)
Definition: simulator_core.hpp:489
static auto applyAssignRouteAction(Ts &&... xs)
Definition: simulator_core.hpp:477
static auto applySpeedAction(Ts &&... xs)
Definition: simulator_core.hpp:501
static auto applyAcquirePositionAction(const std::string &entity_ref, Ts &&... xs)
Definition: simulator_core.hpp:287
static auto applyAssignControllerAction(const std::string &entity_ref, Controller &&controller) -> void
Definition: simulator_core.hpp:335
static auto applyProfileAction(const EntityRef &entity_ref, const DynamicConstraints &dynamic_constraints) -> void
Definition: simulator_core.hpp:300
static auto applyTeleportAction(Ts &&... xs)
Definition: simulator_core.hpp:507
static auto applyDeleteEntityAction(Ts &&... xs)
Definition: simulator_core.hpp:483
static auto applyLaneChangeAction(Ts &&... xs)
Definition: simulator_core.hpp:495
static auto applyAddEntityAction(Ts &&... xs)
Definition: simulator_core.hpp:294
Definition: simulator_core.hpp:521
static auto evaluateBoundingBoxEuclideanDistance(const std::string &from_entity_name, const std::string &to_entity_name)
Definition: simulator_core.hpp:536
static auto evaluateTimeHeadway(Ts &&... xs)
Definition: simulator_core.hpp:576
static auto evaluateCollisionCondition(Ts &&... xs) -> bool
Definition: simulator_core.hpp:530
static auto evaluateSimulationTime(Ts &&... xs) -> double
Definition: simulator_core.hpp:554
static auto evaluateStandStill(Ts &&... xs)
Definition: simulator_core.hpp:570
static auto evaluateSpeed(Ts &&... xs)
Definition: simulator_core.hpp:564
static auto evaluateAcceleration(Ts &&... xs)
Definition: simulator_core.hpp:524
Definition: simulator_core.hpp:70
static auto makeNativeRelativeWorldPosition(const std::string &from_entity_name, const std::string &to_entity_name)
Definition: simulator_core.hpp:106
static auto makeNativeBoundingBoxRelativeWorldPosition(const std::string &from_entity_name, const std::string &to_entity_name)
Definition: simulator_core.hpp:230
static auto makeNativeRelativeLanePosition(const std::string &from_entity_name, const NativeLanePosition &to_lanelet_pose, const RoutingAlgorithm::value_type routing_algorithm=RoutingAlgorithm::undefined) -> traffic_simulator::LaneletPose
Definition: simulator_core.hpp:160
static auto makeNativeBoundingBoxRelativeLanePosition(const std::string &from_entity_name, const std::string &to_entity_name, const RoutingAlgorithm::value_type routing_algorithm=RoutingAlgorithm::undefined)
Definition: simulator_core.hpp:184
static auto makeNativeBoundingBoxRelativeLanePosition(const NativeLanePosition &from_lanelet_pose, const traffic_simulator_msgs::msg::BoundingBox &from_bounding_box, const NativeLanePosition &to_lanelet_pose, const traffic_simulator_msgs::msg::BoundingBox &to_bounding_box, const RoutingAlgorithm::value_type routing_algorithm=RoutingAlgorithm::undefined) -> traffic_simulator::LaneletPose
Definition: simulator_core.hpp:216
static auto convert(const NativeLanePosition &native_lane_position) -> NativeWorldPosition
Definition: simulator_core.hpp:101
static auto convert(const NativeWorldPosition &pose) -> NativeLanePosition
Definition: simulator_core.hpp:79
static auto evaluateLateralRelativeLanes(const std::string &from_entity_name, const std::string &to_entity_name, const RoutingAlgorithm::value_type routing_algorithm=RoutingAlgorithm::undefined) -> int
Definition: simulator_core.hpp:260
static auto makeNativeRelativeLanePosition(const NativeLanePosition &from_lanelet_pose, const NativeLanePosition &to_lanelet_pose, const RoutingAlgorithm::value_type routing_algorithm=RoutingAlgorithm::undefined) -> traffic_simulator::LaneletPose
Definition: simulator_core.hpp:174
static auto makeNativeBoundingBoxRelativeWorldPosition(const std::string &from_entity_name, const NativeWorldPosition &to_map_pose)
Definition: simulator_core.hpp:246
static auto makeNativeRelativeLanePosition(const std::string &from_entity_name, const std::string &to_entity_name, const RoutingAlgorithm::value_type routing_algorithm=RoutingAlgorithm::undefined) -> traffic_simulator::LaneletPose
Definition: simulator_core.hpp:146
static auto canonicalize(const traffic_simulator::LaneletPose &non_canonicalized) -> NativeLanePosition
Definition: simulator_core.hpp:72
static auto makeNativeRelativeWorldPosition(const std::string &from_entity_name, const NativeWorldPosition &to_map_pose)
Definition: simulator_core.hpp:120
static auto makeNativeRelativeWorldPosition(const NativeWorldPosition &from_map_pose, const std::string &to_entity_name)
Definition: simulator_core.hpp:133
static auto makeNativeBoundingBoxRelativeLanePosition(const std::string &from_entity_name, const NativeLanePosition &to_lanelet_pose, const RoutingAlgorithm::value_type routing_algorithm=RoutingAlgorithm::undefined)
Definition: simulator_core.hpp:202
Definition: simulator_core.hpp:588
static auto evaluateCurrentState(Ts &&... xs) -> decltype(auto)
Definition: simulator_core.hpp:613
static auto evaluateRelativeHeading(const EntityRef &entity_ref)
Definition: simulator_core.hpp:636
static auto setV2ITrafficLightsState(Ts &&... xs) -> decltype(auto)
Definition: simulator_core.hpp:690
static auto resetV2ITrafficLightPublishRate(Ts &&... xs) -> decltype(auto)
Definition: simulator_core.hpp:696
static auto setConventionalTrafficLightsState(Ts &&... xs) -> decltype(auto)
Definition: simulator_core.hpp:656
static auto compareConventionalTrafficLightsState(Ts &&... xs) -> decltype(auto)
Definition: simulator_core.hpp:677
static auto resetConventionalTrafficLightPublishRate(Ts &&... xs) -> decltype(auto)
Definition: simulator_core.hpp:684
static auto evaluateRelativeHeading(const EntityRef &entity_ref, const OSCLanePosition &osc_lane_position)
Definition: simulator_core.hpp:619
static auto getConventionalTrafficLightsComposedState(Ts &&... xs) -> decltype(auto)
Definition: simulator_core.hpp:670
static auto sendCooperateCommand(Ts &&... xs) -> decltype(auto)
Definition: simulator_core.hpp:648
static auto activatePerformanceAssertion(const std::string &entity_ref, const Performance &performance, const Properties &properties)
Definition: simulator_core.hpp:591
static auto asFieldOperatorApplication(Ts &&... xs) -> decltype(auto)
Definition: simulator_core.hpp:602
static auto setConventionalTrafficLightConfidence(Ts &&... xs) -> decltype(auto)
Definition: simulator_core.hpp:663
static auto activateNonUserDefinedControllers() -> decltype(auto)
Definition: simulator_core.hpp:607
Definition: simulator_core.hpp:40
static auto deactivate() -> void
Definition: simulator_core.hpp:58
static auto active()
Definition: simulator_core.hpp:56
static auto activate(const Node &node, const traffic_simulator::Configuration &configuration, Ts &&... xs) -> void
Definition: simulator_core.hpp:45
static auto update() -> void
Definition: simulator_core.hpp:67
Definition: lanelet_pose.hpp:27
auto convertQuaternionToEulerAngle(const T &q)
Definition: quaternion_to_euler.hpp:30
Definition: escape_sequence.hpp:22
traffic_simulator::CanonicalizedLaneletPose NativeLanePosition
Definition: simulator_core.hpp:35
geometry_msgs::msg::Pose NativeWorldPosition
Definition: simulator_core.hpp:31
traffic_simulator::LaneletPose NativeRelativeLanePosition
Definition: simulator_core.hpp:37
NativeWorldPosition NativeRelativeWorldPosition
Definition: simulator_core.hpp:33
auto distance(const geometry_msgs::Pose &pose1, const geometry_msgs::Pose &pose2)
Definition: detection_sensor.cpp:34
auto countLaneChanges(const CanonicalizedLaneletPose &from, const CanonicalizedLaneletPose &to, bool allow_lane_change, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> std::optional< std::pair< int, int >>
Definition: distance.cpp:48
auto boundingBoxDistance(const geometry_msgs::msg::Pose &from, const traffic_simulator_msgs::msg::BoundingBox &from_bounding_box, const geometry_msgs::msg::Pose &to, const traffic_simulator_msgs::msg::BoundingBox &to_bounding_box) -> std::optional< double >
Definition: distance.cpp:131
auto boundingBoxRelativeLaneletPose(const CanonicalizedLaneletPose &from, const traffic_simulator_msgs::msg::BoundingBox &from_bounding_box, const CanonicalizedLaneletPose &to, const traffic_simulator_msgs::msg::BoundingBox &to_bounding_box, const bool allow_lane_change, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> LaneletPose
Definition: pose.cpp:201
auto quietNaNPose() -> geometry_msgs::msg::Pose
Definition: pose.cpp:25
auto quietNaNLaneletPose() -> LaneletPose
Definition: pose.cpp:35
auto relativeLaneletPose(const CanonicalizedLaneletPose &from, const CanonicalizedLaneletPose &to, const bool allow_lane_change, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> LaneletPose
Definition: pose.cpp:178
auto boundingBoxRelativePose(const geometry_msgs::msg::Pose &from, const traffic_simulator_msgs::msg::BoundingBox &from_bounding_box, const geometry_msgs::msg::Pose &to, const traffic_simulator_msgs::msg::BoundingBox &to_bounding_box) -> std::optional< geometry_msgs::msg::Pose >
Definition: pose.cpp:158
auto relativePose(const geometry_msgs::msg::Pose &from, const geometry_msgs::msg::Pose &to) -> std::optional< geometry_msgs::msg::Pose >
Definition: pose.cpp:136
auto toCanonicalizedLaneletPose(const geometry_msgs::msg::Pose &map_pose, const bool include_crosswalk, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> std::optional< CanonicalizedLaneletPose >
Definition: pose.cpp:73
auto toMapPose(const CanonicalizedLaneletPose &lanelet_pose) -> geometry_msgs::msg::Pose
Definition: pose.cpp:59
traffic_simulator_msgs::msg::LaneletPose LaneletPose
Definition: lanelet_pose.hpp:22
Definition: junit5.hpp:25
std::string string
Definition: junit5.hpp:26
Definition: exception.hpp:27
Definition: controller.hpp:46
Definition: double.hpp:25
Definition: dynamic_constraints.hpp:44
Definition: entity_ref.hpp:35
Definition: properties.hpp:42
Definition: configuration.hpp:29
traffic_simulator::lanelet_pose::CanonicalizedLaneletPose CanonicalizedLaneletPose
Definition: test_lanelet_pose.cpp:21