diff --git a/README.md b/README.md
index 80dfe3cec357998a30373b7c3fe742e4334ad15f..10e0b17dab4a4129338dd7c34c39ae18359df831 100644
--- a/README.md
+++ b/README.md
@@ -247,14 +247,14 @@ Converts `NET_ASAM_OPENSCENARIO::v1_3::ITrajectoryRef` object type to [mantle_ap
 | CatalogReference       | ✔️      |
 
 ### Transition Dynamics
-Converts `NET_ASAM_OPENSCENARIO::v1_3::ITransitionDynamics` object type to [mantle_api::TransitionDynamics](https://gitlab.eclipse.org/eclipse/openpass/mantle-api/-/blob/master/include/MantleAPI/Traffic/control_strategy.h)  
+Converts `NET_ASAM_OPENSCENARIO::v1_3::ITransitionDynamics` object type to [mantle_api::TransitionDynamics](https://gitlab.eclipse.org/eclipse/openpass/mantle-api/-/blob/master/include/MantleAPI/Traffic/control_strategy.h)
 **Note**: Right now the property `followingMode` is not considered.
 
 # Dependencies
 
 | Dependency | Commit | Version | License |
 | ---------- | ------ | ------- | ------- |
-| [MantleAPI](https://gitlab.eclipse.org/eclipse/openpass/mantle-api) | a5530013 | 6.0.0 | EPL 2.0 |
+| [MantleAPI](https://gitlab.eclipse.org/eclipse/openpass/mantle-api) | 18eadd8a | 8.0.0 | EPL 2.0 |
 | [OpenSCENARIO API](https://github.com/RA-Consulting-GmbH/openscenario.api.test/) | 5980e88 | 1.4.0 | Apache 2.0 |
 | [YASE](https://gitlab.eclipse.org/eclipse/openpass/yase) | d0c0e58d | | EPL 2.0 |
 | [Units](https://github.com/nholthaus/units) | b04d436 | 2.3.3 | MIT License |
diff --git a/engine/BUILD.bazel b/engine/BUILD.bazel
index 6d6f78d835fe98f0b0fcb961e697eca84a832778..1143206ab9845afaf5d2154ccfc29060b36571d5 100644
--- a/engine/BUILD.bazel
+++ b/engine/BUILD.bazel
@@ -37,19 +37,22 @@ cc_library(
 
 filegroup(
     name = "scenario_environment_test_data",
-    srcs = ["tests/data/Scenarios/OSC_1_2_test_EnvironmentCatalog.xosc",
-            "tests/data/Scenarios/Catalogs/Environment/EnvironmentCatalog.xosc"],
+    srcs = [
+        "tests/data/Scenarios/Catalogs/Environment/EnvironmentCatalog.xosc",
+        "tests/data/Scenarios/OSC_1_2_test_EnvironmentCatalog.xosc",
+    ],
 )
 
 cc_test(
     name = "convert_osc_to_mantle_tests",
     timeout = "short",
     srcs = glob(["tests/Conversion/**/*.cpp"]),
+    data = [":scenario_environment_test_data"],
     tags = ["test"],
-    data = [":scenario_environment_test_data",],
     deps = [
         ":open_scenario_engine",
         ":open_scenario_engine_test_utils",
+        ":test_utils",
         "@googletest//:gtest_main",
         "@mantle_api//:test_utils",
     ],
@@ -201,6 +204,7 @@ cc_test(
 
 cc_library(
     name = "test_utils",
+    srcs = glob(["tests/TestUtils/**/*.cpp"]),
     hdrs = glob(["tests/TestUtils/**/*.h"]),
     includes = ["tests"],
     deps = [
diff --git a/engine/CMakeLists.txt b/engine/CMakeLists.txt
index b59bfa842bd2b993fe26d3aa0607ba9a3ce3b30b..316f366f19bfdf7b45d0b460b2f8278a401f7b1f 100644
--- a/engine/CMakeLists.txt
+++ b/engine/CMakeLists.txt
@@ -1,5 +1,5 @@
 # *****************************************************************************
-# Copyright (c) 2021-2023 Bayerische Motoren Werke Aktiengesellschaft (BMW AG)
+# Copyright (c) 2021-2025 Bayerische Motoren Werke Aktiengesellschaft (BMW AG)
 #
 # This program and the accompanying materials are made available under the terms
 # of the Eclipse Public License 2.0 which is available at
@@ -54,7 +54,7 @@ find_package(Antlr4Runtime REQUIRED MODULE)
 include(cmake/generated_files.cmake)
 
 target_sources(
-  ${PROJECT_NAME} PRIVATE ${${PROJECT_NAME}_SOURCES} 
+  ${PROJECT_NAME} PRIVATE ${${PROJECT_NAME}_SOURCES}
                           ${${PROJECT_NAME}_HEADERS}
                           ${CMAKE_CURRENT_LIST_DIR}/include/OpenScenarioEngine/OpenScenarioEngine.h
 )
@@ -62,14 +62,14 @@ target_sources(
 target_include_directories(
   ${PROJECT_NAME}
   PUBLIC $<INSTALL_INTERFACE:include>
-  PRIVATE gen src 
+  PRIVATE gen src
             $<BUILD_INTERFACE:${CMAKE_CURRENT_LIST_DIR}/include>
 )
 
-target_link_libraries(${PROJECT_NAME} PUBLIC openscenario_api::shared 
-                                             antlr4_runtime::shared 
-                                             Yase::agnostic_behavior_tree 
-                                             units::units 
+target_link_libraries(${PROJECT_NAME} PUBLIC openscenario_api::shared
+                                             antlr4_runtime::shared
+                                             Yase::agnostic_behavior_tree
+                                             units::units
                                              MantleAPI::MantleAPI)
 
 if(USE_CCACHE)
@@ -151,12 +151,13 @@ add_executable(${PROJECT_NAME}Test "")
 
 target_sources(
   ${PROJECT_NAME}Test
-  PRIVATE 
+  PRIVATE
           ${CMAKE_CURRENT_LIST_DIR}/tests/builders/ActionBuilder.cpp
           ${CMAKE_CURRENT_LIST_DIR}/tests/builders/condition_builder.cpp
           ${CMAKE_CURRENT_LIST_DIR}/tests/builders/PositionBuilder.cpp
           ${CMAKE_CURRENT_LIST_DIR}/tests/Conversion/OscToMantle/ConvertScenarioAbsoluteTargetLaneTest.cpp
           ${CMAKE_CURRENT_LIST_DIR}/tests/Conversion/OscToMantle/ConvertScenarioCentralSwarmObjectTest.cpp
+          ${CMAKE_CURRENT_LIST_DIR}/tests/Conversion/OscToMantle/ConvertScenarioClothoidSplineTest.cpp
           ${CMAKE_CURRENT_LIST_DIR}/tests/Conversion/OscToMantle/ConvertScenarioCoordinateSystemTest.cpp
           ${CMAKE_CURRENT_LIST_DIR}/tests/Conversion/OscToMantle/ConvertScenarioEnvironmentTest.cpp
           ${CMAKE_CURRENT_LIST_DIR}/tests/Conversion/OscToMantle/ConvertScenarioLateralDisplacementTest.cpp
@@ -207,6 +208,7 @@ target_sources(
           ${CMAKE_CURRENT_LIST_DIR}/tests/Storyboard/MotionControlAction/LongitudinalDistanceActionTest.cpp
           ${CMAKE_CURRENT_LIST_DIR}/tests/Storyboard/MotionControlAction/MotionControlActionTest.cpp
           ${CMAKE_CURRENT_LIST_DIR}/tests/Storyboard/MotionControlAction/SpeedActionTest.cpp
+          ${CMAKE_CURRENT_LIST_DIR}/tests/TestUtils/ClothoidSplineUtils.cpp
           ${CMAKE_CURRENT_LIST_DIR}/tests/TrafficSignalParsing/TrafficPhaseNodeTest.cpp
           ${CMAKE_CURRENT_LIST_DIR}/tests/TrafficSignalParsing/TreeGenerationTest.cpp
           ${CMAKE_CURRENT_LIST_DIR}/tests/Utils/ConstantsTest.cpp
diff --git a/engine/bazel/deps.bzl b/engine/bazel/deps.bzl
index d5bc97eafd5a48d25038d2168b746bf1e3ee2c7a..efc8bf15c5f896262bb7a987943f953de9b60844 100644
--- a/engine/bazel/deps.bzl
+++ b/engine/bazel/deps.bzl
@@ -3,7 +3,7 @@ load("@bazel_tools//tools/build_defs/repo:utils.bzl", "maybe")
 
 ECLIPSE_GITLAB = "https://gitlab.eclipse.org/eclipse"
 
-MANTLE_API_TAG = "v6.0.0"
+MANTLE_API_TAG = "v8.0.0"
 UNITS_TAG = "2.3.3"
 YASE_TAG = "v0.0.1"
 
@@ -13,7 +13,7 @@ def osc_engine_deps():
         http_archive,
         name = "mantle_api",
         url = ECLIPSE_GITLAB + "/openpass/mantle-api/-/archive/{tag}/mantle-api-{tag}.tar.gz".format(tag = MANTLE_API_TAG),
-        sha256 = "d6365096eceefd6848f7429382279b337e9cb8292a984ef54137dbdebd4ce599",
+        sha256 = "abb18f7180da012c02bda874752a7efd9ceab1da31e616174790f07a17c4fa3f",
         strip_prefix = "mantle-api-{tag}".format(tag = MANTLE_API_TAG),
     )
 
diff --git a/engine/cmake/generated_files.cmake b/engine/cmake/generated_files.cmake
index e6d2a3319d069ddca2a9713a1c33c7feeac49437..a0e7d28d4ca0f1fbdae041ffcfc0d5fc7bbf5c46 100644
--- a/engine/cmake/generated_files.cmake
+++ b/engine/cmake/generated_files.cmake
@@ -1,5 +1,5 @@
 ################################################################################
-# Copyright (c) 2022-2024 Bayerische Motoren Werke Aktiengesellschaft (BMW AG)
+# Copyright (c) 2022-2025 Bayerische Motoren Werke Aktiengesellschaft (BMW AG)
 #
 # This program and the accompanying materials are made available under the
 # terms of the Eclipse Public License 2.0 which is available at
@@ -142,6 +142,7 @@ list(APPEND ${PROJECT_NAME}_SOURCES
     gen/Storyboard/MotionControlAction/SynchronizeAction_impl.cpp
     src/Conversion/OscToMantle/ConvertScenarioAbsoluteTargetLane.cpp
     src/Conversion/OscToMantle/ConvertScenarioCentralSwarmObject.cpp
+    src/Conversion/OscToMantle/ConvertScenarioClothoidSpline.cpp
     src/Conversion/OscToMantle/ConvertScenarioConditionEdge.cpp
     src/Conversion/OscToMantle/ConvertScenarioController.cpp
     src/Conversion/OscToMantle/ConvertScenarioCoordinateSystem.cpp
@@ -496,6 +497,7 @@ list(APPEND ${PROJECT_NAME}_HEADERS
     src/Conversion/OscToMantle/ConvertScenarioAngleType.h
     src/Conversion/OscToMantle/ConvertScenarioByObjectType.h
     src/Conversion/OscToMantle/ConvertScenarioCentralSwarmObject.h
+    src/Conversion/OscToMantle/ConvertScenarioClothoidSpline.h
     src/Conversion/OscToMantle/ConvertScenarioConditionEdge.h
     src/Conversion/OscToMantle/ConvertScenarioController.h
     src/Conversion/OscToMantle/ConvertScenarioCoordinateSystem.h
diff --git a/engine/src/Conversion/OscToMantle/ConvertScenarioClothoidSpline.cpp b/engine/src/Conversion/OscToMantle/ConvertScenarioClothoidSpline.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..2738666c9315e39c2f01832cc022484fde787851
--- /dev/null
+++ b/engine/src/Conversion/OscToMantle/ConvertScenarioClothoidSpline.cpp
@@ -0,0 +1,100 @@
+/********************************************************************************
+ * Copyright (c) 2025 Bayerische Motoren Werke Aktiengesellschaft (BMW AG)
+ *
+ * This program and the accompanying materials are made available under the
+ * terms of the Eclipse Public License 2.0 which is available at
+ * http://www.eclipse.org/legal/epl-2.0.
+ *
+ * SPDX-License-Identifier: EPL-2.0
+ ********************************************************************************/
+
+#include "Conversion/OscToMantle/ConvertScenarioClothoidSpline.h"
+
+#include <MantleAPI/Common/pose.h>
+#include <MantleAPI/Common/unit_definitions.h>
+#include <openScenarioLib/generated/v1_3/api/ApiClassInterfacesV1_3.h>
+
+#include <memory>
+#include <optional>
+#include <stdexcept>
+
+namespace OpenScenarioEngine::v1_3::detail
+{
+
+using units::literals::operator""_rad;
+using units::literals::operator""_m;
+
+std::optional<mantle_api::Pose> ConvertWorldPosition(const std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::IClothoidSplineSegment>& clothoid_spline_segment)
+{
+  if (clothoid_spline_segment->IsSetPositionStart())
+  {
+    const auto position_start = clothoid_spline_segment->GetPositionStart();
+
+    if (!position_start->IsSetWorldPosition())
+    {
+      throw std::runtime_error("ConvertWorldPosition: World position is not set");
+    }
+
+    const auto world_position = position_start->GetWorldPosition();
+
+    return std::make_optional<mantle_api::Pose>(
+        {{units::length::meter_t(world_position->GetX()),
+          units::length::meter_t(world_position->GetY()),
+          world_position->IsSetZ() ? units::length::meter_t(world_position->GetZ()) : 0_m},
+         {world_position->IsSetH() ? units::angle::radian_t(world_position->GetH()) : 0_rad,
+          world_position->IsSetP() ? units::angle::radian_t(world_position->GetP()) : 0_rad,
+          world_position->IsSetR() ? units::angle::radian_t(world_position->GetR()) : 0_rad}});
+  }
+  else
+  {
+    return std::nullopt;
+  }
+}
+
+mantle_api::ClothoidSplineSegment ConvertClothoidSplineSegment(const std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::IClothoidSplineSegment>& clothoid_spline_segment)
+{
+  if (!clothoid_spline_segment)
+  {
+    throw std::invalid_argument("ConvertClothoidSplineSegment: clothoid_spline_segment is not initialized");
+  }
+
+  mantle_api::ClothoidSplineSegment converted_clothoid_spline_segment;
+
+  converted_clothoid_spline_segment.curvature_end = units::curve::curvature_t(clothoid_spline_segment->GetCurvatureEnd());
+  converted_clothoid_spline_segment.curvature_start = units::curve::curvature_t(clothoid_spline_segment->GetCurvatureStart());
+
+  if (clothoid_spline_segment->IsSetHOffset())
+  {
+    converted_clothoid_spline_segment.h_offset = units::angle::radian_t(clothoid_spline_segment->GetHOffset());
+  }
+  else
+  {
+    converted_clothoid_spline_segment.h_offset = 0.0_rad;
+  }
+
+  converted_clothoid_spline_segment.length = units::length::meter_t(clothoid_spline_segment->GetLength());
+
+  converted_clothoid_spline_segment.position_start = ConvertWorldPosition(clothoid_spline_segment);
+
+  return converted_clothoid_spline_segment;
+}
+}  // namespace OpenScenarioEngine::v1_3::detail
+
+namespace OpenScenarioEngine::v1_3
+{
+mantle_api::ClothoidSpline ConvertClothoidSpline(const std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::IClothoidSpline>& clothoid_spline)
+{
+  if (!clothoid_spline)
+  {
+    throw std::invalid_argument("ConvertClothoidSpline: clothoid_spline is not initialized");
+  }
+
+  mantle_api::ClothoidSpline converted_clothoid_spline;
+  for (const auto& segment : clothoid_spline->GetSegments())
+  {
+    converted_clothoid_spline.segments.push_back(detail::ConvertClothoidSplineSegment(segment));
+  }
+  return converted_clothoid_spline;
+}
+
+}  // namespace OpenScenarioEngine::v1_3
diff --git a/engine/src/Conversion/OscToMantle/ConvertScenarioClothoidSpline.h b/engine/src/Conversion/OscToMantle/ConvertScenarioClothoidSpline.h
new file mode 100644
index 0000000000000000000000000000000000000000..a07d2af4ec323c08ce1ece8df25fcde6ee3cc0da
--- /dev/null
+++ b/engine/src/Conversion/OscToMantle/ConvertScenarioClothoidSpline.h
@@ -0,0 +1,23 @@
+/********************************************************************************
+ * Copyright (c) 2025 Bayerische Motoren Werke Aktiengesellschaft (BMW AG)
+ *
+ * This program and the accompanying materials are made available under the
+ * terms of the Eclipse Public License 2.0 which is available at
+ * http://www.eclipse.org/legal/epl-2.0.
+ *
+ * SPDX-License-Identifier: EPL-2.0
+ ********************************************************************************/
+
+#pragma once
+
+#include <MantleAPI/Common/clothoid_spline.h>
+#include <openScenarioLib/generated/v1_3/api/ApiClassInterfacesV1_3.h>
+
+#include <memory>
+
+namespace OpenScenarioEngine::v1_3
+{
+
+mantle_api::ClothoidSpline ConvertClothoidSpline(const std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::IClothoidSpline>& clothoid_spline);
+
+}  // namespace OpenScenarioEngine::v1_3
diff --git a/engine/src/Conversion/OscToMantle/ConvertScenarioTrajectoryRef.cpp b/engine/src/Conversion/OscToMantle/ConvertScenarioTrajectoryRef.cpp
index 961f9aecec5bf1d70cc0450b1efa641aafabcbf0..25ec2da833e8a7d309146902391bd27d3653ea44 100644
--- a/engine/src/Conversion/OscToMantle/ConvertScenarioTrajectoryRef.cpp
+++ b/engine/src/Conversion/OscToMantle/ConvertScenarioTrajectoryRef.cpp
@@ -1,6 +1,6 @@
 
 /********************************************************************************
- * Copyright (c) 2021-2024 Bayerische Motoren Werke Aktiengesellschaft (BMW AG)
+ * Copyright (c) 2021-2025 Bayerische Motoren Werke Aktiengesellschaft (BMW AG)
  *
  * This program and the accompanying materials are made available under the
  * terms of the Eclipse Public License 2.0 which is available at
@@ -11,8 +11,13 @@
 
 #include "Conversion/OscToMantle/ConvertScenarioTrajectoryRef.h"
 
+#include <MantleAPI/Common/clothoid_spline.h>
+
+#include <memory>
+#include <unordered_map>
 #include <utility>
 
+#include "Conversion/OscToMantle/ConvertScenarioClothoidSpline.h"
 #include "Conversion/OscToMantle/ConvertScenarioPosition.h"
 
 namespace OpenScenarioEngine::v1_3
@@ -43,63 +48,112 @@ std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::ITrajectory> OpenScenarioToMantle(c
   }
   throw std::runtime_error("convertScenarioRoute: Either trajectorReference or catalogReference must be set");
 }
+
+mantle_api::TrajectoryReferencePoint ParseTrajectoryReferencePoint(const std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::ITrajectory>& follow_trajectory_action_trajectory)
+{
+  mantle_api::TrajectoryReferencePoint reference_point{mantle_api::TrajectoryReferencePoint::kUndefined};
+
+  for (const auto& parameter : follow_trajectory_action_trajectory->GetParameterDeclarations())
+  {
+    if (parameter->GetName() == "reference")
+    {
+      const std::unordered_map<std::string, mantle_api::TrajectoryReferencePoint> string_to_reference_point{
+          {"rear_axle", mantle_api::TrajectoryReferencePoint::kRearAxle},
+          {"front_axle", mantle_api::TrajectoryReferencePoint::kFrontAxle},
+          {"center_of_mass", mantle_api::TrajectoryReferencePoint::kCenterOfMass},
+          {"bounding_box_center", mantle_api::TrajectoryReferencePoint::kBoundingBoxCenter}};
+      const auto value_it = string_to_reference_point.find(parameter->GetValue());
+      if (value_it == string_to_reference_point.end())
+      {
+        throw std::runtime_error("ConvertScenarioTrajectoryRef: Invalid value of Trajectory Parameter \"reference\"");
+      }
+      else
+      {
+        reference_point = value_it->second;
+      }
+    }
+  }
+  return reference_point;
+}
+
+mantle_api::Trajectory ConvertClothoidShape(const std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::ITrajectory>& follow_trajectory_action_trajectory)
+{
+  mantle_api::Trajectory trajectory{follow_trajectory_action_trajectory->GetName()};
+
+  std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::IShape> follow_trajectory_action_trajectory_shape = follow_trajectory_action_trajectory->GetShape();
+  const auto clothoid_spline = follow_trajectory_action_trajectory_shape->GetClothoidSpline();
+  const auto converted_clothoid_spline = ConvertClothoidSpline(clothoid_spline);
+
+  trajectory.type = converted_clothoid_spline;
+  trajectory.reference = ParseTrajectoryReferencePoint(follow_trajectory_action_trajectory);
+
+  return trajectory;
+}
+
+mantle_api::Trajectory ConvertPolyline(const std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::ITrajectory>& follow_trajectory_action_trajectory, const std::shared_ptr<mantle_api::IEnvironment>& environment)
+{
+  mantle_api::Trajectory trajectory{follow_trajectory_action_trajectory->GetName()};
+  std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::IShape> follow_trajectory_action_trajectory_shape = follow_trajectory_action_trajectory->GetShape();
+  mantle_api::PolyLine poly_line;
+
+  for (const auto& poly_line_vertex : follow_trajectory_action_trajectory_shape->GetPolyline()->GetVertices())
+  {
+    mantle_api::PolyLinePoint poly_line_point;
+
+    // TODO CK Separate method to parse position, which can be used anywhere in the openScenarioEngine
+    auto poly_line_vertex_position = poly_line_vertex->GetPosition();
+    auto pose = ConvertScenarioPosition(environment, poly_line_vertex_position);
+    poly_line_point.pose = pose.value();
+    // if (poly_line_vertex_position->GetWorldPosition())
+    // {
+    //     auto world_position = poly_line_vertex_position->GetWorldPosition();
+
+    //     mantle_api::Vec3<units::length::meter_t> position;
+    //     position.x = units::length::meter_t(world_position->GetX());
+    //     position.y = units::length::meter_t(world_position->GetY());
+    //     position.z = units::length::meter_t(world_position->GetZ());
+
+    //     mantle_api::Orientation3<units::angle::radian_t> orientation;
+    //     orientation.yaw = units::angle::radian_t(world_position->GetH());
+    //     orientation.pitch = units::angle::radian_t(world_position->GetP());
+    //     orientation.roll = units::angle::radian_t(world_position->GetR());
+
+    //     poly_line_point.pose = {position, orientation};
+    // }
+    // else
+    // {
+    //     Logger::Warning("FollowTrajectoryAction currently does not support other Position types than "
+    //                     "WorldPosition in Polyline shape");
+    // }
+
+    poly_line_point.time = poly_line_vertex->IsSetTime() ? std::make_optional<units::time::second_t>(poly_line_vertex->GetTime()) : std::nullopt;
+
+    poly_line.push_back(poly_line_point);
+  }
+
+  trajectory.type = poly_line;
+  return trajectory;
+}
+
 }  // namespace detail
 
 TrajectoryRef ConvertScenarioTrajectoryRef(const std::shared_ptr<mantle_api::IEnvironment>& environment,
                                            const std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::ITrajectoryRef>& trajectoryRef,
                                            const std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::ICatalogReference>& catalogReference)
 {
-  mantle_api::Trajectory trajectory{};
-
   auto follow_trajectory_action_trajectory = detail::OpenScenarioToMantle(trajectoryRef, catalogReference);
 
-  trajectory.name = follow_trajectory_action_trajectory->GetName();
-
   auto follow_trajectory_action_trajectory_shape = follow_trajectory_action_trajectory->GetShape();
 
   if (follow_trajectory_action_trajectory_shape->GetPolyline())
   {
-    mantle_api::PolyLine poly_line;
-
-    for (const auto& poly_line_vertex : follow_trajectory_action_trajectory_shape->GetPolyline()->GetVertices())
-    {
-      mantle_api::PolyLinePoint poly_line_point;
-
-      // TODO CK Separate method to parse position, which can be used anywhere in the openScenarioEngine
-      auto poly_line_vertex_position = poly_line_vertex->GetPosition();
-      auto pose = ConvertScenarioPosition(environment, poly_line_vertex_position);
-      poly_line_point.pose = pose.value();
-      // if (poly_line_vertex_position->GetWorldPosition())
-      // {
-      //     auto world_position = poly_line_vertex_position->GetWorldPosition();
-
-      //     mantle_api::Vec3<units::length::meter_t> position;
-      //     position.x = units::length::meter_t(world_position->GetX());
-      //     position.y = units::length::meter_t(world_position->GetY());
-      //     position.z = units::length::meter_t(world_position->GetZ());
-
-      //     mantle_api::Orientation3<units::angle::radian_t> orientation;
-      //     orientation.yaw = units::angle::radian_t(world_position->GetH());
-      //     orientation.pitch = units::angle::radian_t(world_position->GetP());
-      //     orientation.roll = units::angle::radian_t(world_position->GetR());
-
-      //     poly_line_point.pose = {position, orientation};
-      // }
-      // else
-      // {
-      //     Logger::Warning("FollowTrajectoryAction currently does not support other Position types than "
-      //                     "WorldPosition in Polyline shape");
-      // }
-
-      poly_line_point.time = poly_line_vertex->IsSetTime() ? std::make_optional<units::time::second_t>(poly_line_vertex->GetTime()): std::nullopt;
-
-      poly_line.push_back(poly_line_point);
-    }
-
-    trajectory.type = poly_line;
-    return trajectory;
+    return detail::ConvertPolyline(follow_trajectory_action_trajectory, environment);
+  }
+  else if (follow_trajectory_action_trajectory_shape->GetClothoidSpline())
+  {
+    return detail::ConvertClothoidShape(follow_trajectory_action_trajectory);
   }
   return std::nullopt;
 }
 
-}  // namespace OpenScenarioEngine::v1_3
\ No newline at end of file
+}  // namespace OpenScenarioEngine::v1_3
diff --git a/engine/tests/Conversion/OscToMantle/ConvertScenarioClothoidSplineTest.cpp b/engine/tests/Conversion/OscToMantle/ConvertScenarioClothoidSplineTest.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..a230b266bd3f65f845f2ea3de84eaf7847c9e486
--- /dev/null
+++ b/engine/tests/Conversion/OscToMantle/ConvertScenarioClothoidSplineTest.cpp
@@ -0,0 +1,161 @@
+/********************************************************************************
+ * Copyright (c) 2025 Bayerische Motoren Werke Aktiengesellschaft (BMW AG)
+ *
+ * This program and the accompanying materials are made available under the
+ * terms of the Eclipse Public License 2.0 which is available at
+ * http://www.eclipse.org/legal/epl-2.0.
+ *
+ * SPDX-License-Identifier: EPL-2.0
+ ********************************************************************************/
+
+#include <MantleAPI/Common/clothoid_spline.h>
+#include <MantleAPI/Common/pose.h>
+#include <gtest/gtest.h>
+#include <openScenarioLib/generated/v1_3/api/writer/ApiClassWriterInterfacesV1_3.h>
+#include <openScenarioLib/generated/v1_3/impl/ApiClassImplV1_3.h>
+
+#include <functional>
+#include <memory>
+#include <optional>
+
+#include "Conversion/OscToMantle/ConvertScenarioClothoidSpline.h"
+#include "TestUtils/ClothoidSplineUtils.h"
+
+namespace
+{
+
+using units::literals::operator""_m;
+using units::literals::operator""_rad;
+using units::literals::operator""_curv;
+
+using ClothoidSplineSegmentWriter = NET_ASAM_OPENSCENARIO::v1_3::IClothoidSplineSegmentWriter;
+using ClothoidSplineSegmentWriterSharedPtr = std::shared_ptr<ClothoidSplineSegmentWriter>;
+class ConvertClothoidSplineTestFixture : public ::testing::Test
+{
+protected:
+  ConvertClothoidSplineTestFixture()
+  {
+    expected_converted_clothoid_spline_.segments.push_back({-6.8_curv,
+                                                            9.4_curv,
+                                                            2.3_rad,
+                                                            1.5_m,
+                                                            mantle_api::Pose{{6.1_m, -1.5_m, 3.9_m}, {1.4_rad, 2.0_rad, -1.4_rad}}});
+
+    clothoid_spline_ = std::make_shared<NET_ASAM_OPENSCENARIO::v1_3::ClothoidSplineImpl>();
+  }
+  void SetUpClothoid()
+  {
+    std::vector<ClothoidSplineSegmentWriterSharedPtr> segments;
+
+    for (auto& segment : expected_converted_clothoid_spline_.segments)
+    {
+      segments.push_back(testing::OpenScenarioEngine::v1_3::CreateClothoidSegment(segment));
+    }
+
+    clothoid_spline_->SetSegments(segments);
+  }
+
+  std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::IClothoidSplineWriter> clothoid_spline_;
+  mantle_api::ClothoidSpline expected_converted_clothoid_spline_;
+};
+
+TEST_F(ConvertClothoidSplineTestFixture, GivenNotInitializedClothoidSpline_ThenException)
+{
+  clothoid_spline_.reset();
+  EXPECT_THROW(OpenScenarioEngine::v1_3::ConvertClothoidSpline(clothoid_spline_), std::invalid_argument);
+}
+
+TEST_F(ConvertClothoidSplineTestFixture, GivenNotInitializedClothoidSplineSegment_ThenException)
+{
+  ClothoidSplineSegmentWriterSharedPtr segment;
+  std::vector<ClothoidSplineSegmentWriterSharedPtr> segments;
+
+  segments.push_back(segment);
+  clothoid_spline_->SetSegments(segments);
+
+  EXPECT_THROW(OpenScenarioEngine::v1_3::ConvertClothoidSpline(clothoid_spline_), std::invalid_argument);
+}
+
+TEST_F(ConvertClothoidSplineTestFixture, GivenClothoidSplineSegment_WhenWorldPositionNotSet_ThenException)
+{
+  auto osc_position_start = std::make_shared<NET_ASAM_OPENSCENARIO::v1_3::PositionImpl>();
+  auto geo_position = std::make_shared<NET_ASAM_OPENSCENARIO::v1_3::GeoPositionImpl>();
+  osc_position_start->SetGeoPosition(geo_position);
+
+  SetUpClothoid();
+
+  ClothoidSplineSegmentWriterSharedPtr segment = std::dynamic_pointer_cast<ClothoidSplineSegmentWriter>(clothoid_spline_->GetSegmentsAtIndex(0));
+  segment->SetPositionStart(osc_position_start);
+
+  EXPECT_THROW(OpenScenarioEngine::v1_3::ConvertClothoidSpline(clothoid_spline_), std::runtime_error);
+}
+
+using ResetParam = std::function<void(ClothoidSplineSegmentWriterSharedPtr&, mantle_api::ClothoidSplineSegment&)>;
+
+void ResetHOffset(ClothoidSplineSegmentWriterSharedPtr& segment, mantle_api::ClothoidSplineSegment& expected_converted_clothoid_spline_segment)
+{
+  expected_converted_clothoid_spline_segment.h_offset = 0.0_rad;
+  segment->ResetHOffset();
+}
+
+void ResetPoseZ(ClothoidSplineSegmentWriterSharedPtr& segment, mantle_api::ClothoidSplineSegment& expected_converted_clothoid_spline_segment)
+{
+  expected_converted_clothoid_spline_segment.position_start->position.z = 0.0_m;
+  std::dynamic_pointer_cast<NET_ASAM_OPENSCENARIO::v1_3::IWorldPositionWriter>(segment->GetPositionStart()->GetWorldPosition())
+      ->ResetZ();
+}
+
+void ResetPoseH(ClothoidSplineSegmentWriterSharedPtr& segment, mantle_api::ClothoidSplineSegment& expected_converted_clothoid_spline_segment)
+{
+  expected_converted_clothoid_spline_segment.position_start->orientation.yaw = 0.0_rad;
+  std::dynamic_pointer_cast<NET_ASAM_OPENSCENARIO::v1_3::IWorldPositionWriter>(segment->GetPositionStart()->GetWorldPosition())
+      ->ResetH();
+}
+
+void ResetPoseP(ClothoidSplineSegmentWriterSharedPtr& segment, mantle_api::ClothoidSplineSegment& expected_converted_clothoid_spline_segment)
+{
+  expected_converted_clothoid_spline_segment.position_start->orientation.pitch = 0.0_rad;
+  std::dynamic_pointer_cast<NET_ASAM_OPENSCENARIO::v1_3::IWorldPositionWriter>(segment->GetPositionStart()->GetWorldPosition())
+      ->ResetP();
+}
+
+void ResetPoseR(ClothoidSplineSegmentWriterSharedPtr& segment, mantle_api::ClothoidSplineSegment& expected_converted_clothoid_spline_segment)
+{
+  expected_converted_clothoid_spline_segment.position_start->orientation.roll = 0.0_rad;
+  std::dynamic_pointer_cast<NET_ASAM_OPENSCENARIO::v1_3::IWorldPositionWriter>(segment->GetPositionStart()->GetWorldPosition())
+      ->ResetR();
+}
+class ConvertClothoidSplineTestParamFixture : public ::testing::WithParamInterface<ResetParam>, public ConvertClothoidSplineTestFixture
+{
+};
+
+INSTANTIATE_TEST_SUITE_P(ConvertClothoidSplineTestInstParamFixture, ConvertClothoidSplineTestParamFixture, ::testing::Values(ResetHOffset, ResetPoseZ, ResetPoseH, ResetPoseP, ResetPoseR));
+
+TEST_P(ConvertClothoidSplineTestParamFixture, GivenClothoidSplineSegment_WhenNotRequiredParametersNotSet_ThenConvertedClothoidSplineSegmentHasNotRequiredParametersEqualToZero)
+{
+  SetUpClothoid();
+
+  ClothoidSplineSegmentWriterSharedPtr segment = std::dynamic_pointer_cast<ClothoidSplineSegmentWriter>(clothoid_spline_->GetSegmentsAtIndex(0));
+
+  GetParam()(segment, expected_converted_clothoid_spline_.segments.front());
+
+  mantle_api::ClothoidSpline actual_converted_clothoid_spline = OpenScenarioEngine::v1_3::ConvertClothoidSpline(clothoid_spline_);
+
+  EXPECT_EQ(expected_converted_clothoid_spline_.segments, actual_converted_clothoid_spline.segments);
+}
+
+TEST_F(ConvertClothoidSplineTestFixture, GivenClothoidSpline_ThenConvertedClotoidSplineHasEqualParameters)
+{
+  expected_converted_clothoid_spline_.segments.push_back({2.0_curv,
+                                                          1.5_curv,
+                                                          1.5_rad,
+                                                          1.8_m,
+                                                          std::nullopt});
+  SetUpClothoid();
+
+  mantle_api::ClothoidSpline actual_converted_clothoid_spline = OpenScenarioEngine::v1_3::ConvertClothoidSpline(clothoid_spline_);
+
+  EXPECT_EQ(expected_converted_clothoid_spline_, actual_converted_clothoid_spline);
+}
+
+}  // namespace
diff --git a/engine/tests/Conversion/OscToMantle/ConvertScenarioTrajectoryRefTest.cpp b/engine/tests/Conversion/OscToMantle/ConvertScenarioTrajectoryRefTest.cpp
index c280f57ef1f27a0c5e46529c31fc8260dab9a51a..7dbb6fe6884b5f61967bfdadd1aae138a6986f57 100644
--- a/engine/tests/Conversion/OscToMantle/ConvertScenarioTrajectoryRefTest.cpp
+++ b/engine/tests/Conversion/OscToMantle/ConvertScenarioTrajectoryRefTest.cpp
@@ -1,5 +1,5 @@
 /********************************************************************************
- * Copyright (c) 2021-2024 Bayerische Motoren Werke Aktiengesellschaft (BMW AG)
+ * Copyright (c) 2021-2025 Bayerische Motoren Werke Aktiengesellschaft (BMW AG)
  *
  * This program and the accompanying materials are made available under the
  * terms of the Eclipse Public License 2.0 which is available at
@@ -13,15 +13,53 @@
 #include <openScenarioLib/generated/v1_3/api/ApiClassInterfacesV1_3.h>
 #include <openScenarioLib/generated/v1_3/impl/ApiClassImplV1_3.h>
 
+#include <optional>
+#include <stdexcept>
+#include <tuple>
 #include <vector>
 
 #include "Conversion/OscToMantle/ConvertScenarioTrajectoryRef.h"
+#include "TestUtils/ClothoidSplineUtils.h"
+
+namespace
+{
 
 using namespace units::literals;
 
 class ConvertScenarioTrajectoryRefTest : public ::testing::Test
 {
 protected:
+  void SetTrajectoryWithClothoidSpline()
+  {
+    expected_clothoid_spline.segments.push_back({
+        2.0_curv,
+        1.5_curv,
+        1.5_rad,
+        1.8_m,
+        std::nullopt,
+    });
+
+    expected_clothoid_spline.segments.push_back({-6.8_curv,
+                                                 9.4_curv,
+                                                 2.3_rad,
+                                                 1.5_m,
+                                                 mantle_api::Pose{{6.1_m, -1.5_m, 3.9_m}, {1.4_rad, 2.0_rad, -1.4_rad}}});
+
+    for (const auto& segment : expected_clothoid_spline.segments)
+    {
+      clothoid_spline_segments.push_back(testing::OpenScenarioEngine::v1_3::CreateClothoidSegment(segment));
+    }
+
+    auto clothoid_spline = std::make_shared<NET_ASAM_OPENSCENARIO::v1_3::ClothoidSplineImpl>();
+    clothoid_spline->SetSegments(clothoid_spline_segments);
+    trajectory_shape->SetClothoidSpline(clothoid_spline);
+
+    trajectory->SetShape(trajectory_shape);
+    trajectory->SetName("Trajectory1");
+
+    trajectory_ref->SetTrajectory(trajectory);
+  }
+
   std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::PositionImpl> SetWorldPosition(double x, double y, double z, double h, double p, double r)
   {
     auto world_pos = std::make_shared<NET_ASAM_OPENSCENARIO::v1_3::WorldPositionImpl>();
@@ -53,12 +91,22 @@ protected:
   mantle_api::Vec3<units::length::meter_t> position3{1.2_m, 2.2_m, 0.0_m};
   mantle_api::Orientation3<units::angle::radian_t> orientation3{0.3_rad, 0.0_rad, 0.0_rad};
 
-  std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::PolylineImpl> polyLine{std::make_shared<NET_ASAM_OPENSCENARIO::v1_3::PolylineImpl>()};
-  std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::ShapeImpl> trajectoryShape{std::make_shared<NET_ASAM_OPENSCENARIO::v1_3::ShapeImpl>()};
+  std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::PolylineImpl>
+      polyline{std::make_shared<NET_ASAM_OPENSCENARIO::v1_3::PolylineImpl>()};
+
+  std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::ShapeImpl> trajectory_shape{std::make_shared<NET_ASAM_OPENSCENARIO::v1_3::ShapeImpl>()};
+
   std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::TrajectoryImpl> trajectory{std::make_shared<NET_ASAM_OPENSCENARIO::v1_3::TrajectoryImpl>()};
-  const std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::TrajectoryRefImpl> trajectoryRef{std::make_shared<NET_ASAM_OPENSCENARIO::v1_3::TrajectoryRefImpl>()};
+
+  const std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::TrajectoryRefImpl> trajectory_ref{std::make_shared<NET_ASAM_OPENSCENARIO::v1_3::TrajectoryRefImpl>()};
 
   const std::shared_ptr<mantle_api::MockEnvironment> mockEnvironment{std::make_shared<mantle_api::MockEnvironment>()};
+
+  std::vector<std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::IClothoidSplineSegmentWriter>> clothoid_spline_segments;
+
+  std::vector<std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::IParameterDeclarationWriter>> parameter_declarations;
+
+  mantle_api::ClothoidSpline expected_clothoid_spline;
 };
 
 TEST_F(ConvertScenarioTrajectoryRefTest, GivenPolyLine_ReturnMantleAPITrajectoryType)
@@ -68,19 +116,21 @@ TEST_F(ConvertScenarioTrajectoryRefTest, GivenPolyLine_ReturnMantleAPITrajectory
   vertices.push_back(SetVertex(position2.x.value(), position2.y.value(), position2.z.value(), orientation2.yaw.value(), orientation2.pitch.value(), orientation2.roll.value()));
   vertices.push_back(SetVertex(position3.x.value(), position3.y.value(), position3.z.value(), orientation3.yaw.value(), orientation3.pitch.value(), orientation3.roll.value()));
 
-  polyLine->SetVertices(vertices);
-  trajectoryShape->SetPolyline(polyLine);
-  trajectory->SetShape(trajectoryShape);
+  polyline->SetVertices(vertices);
+  trajectory_shape->SetPolyline(polyline);
+
+  trajectory->SetShape(trajectory_shape);
   trajectory->SetName("Trajectory1");
-  trajectoryRef->SetTrajectory(trajectory);
 
-  auto convertedTrajectoryRef = OpenScenarioEngine::v1_3::ConvertScenarioTrajectoryRef(mockEnvironment, trajectoryRef, nullptr);
+  trajectory_ref->SetTrajectory(trajectory);
+
+  auto converted_trajectory_ref = OpenScenarioEngine::v1_3::ConvertScenarioTrajectoryRef(mockEnvironment, trajectory_ref, nullptr);
 
   mantle_api::Pose expected_pose1{position1, orientation1};
   mantle_api::Pose expected_pose2{position2, orientation2};
   mantle_api::Pose expected_pose3{position3, orientation3};
 
-  auto& polyline = std::get<mantle_api::PolyLine>(convertedTrajectoryRef->type);
+  auto& polyline = std::get<mantle_api::PolyLine>(converted_trajectory_ref->type);
   EXPECT_THAT(polyline, testing::SizeIs(3));
   EXPECT_EQ(polyline.at(0).time, 5.0_s);
   EXPECT_EQ(polyline.at(0).pose, expected_pose1);
@@ -90,17 +140,67 @@ TEST_F(ConvertScenarioTrajectoryRefTest, GivenPolyLine_ReturnMantleAPITrajectory
   EXPECT_EQ(polyline.at(2).pose, expected_pose3);
 }
 
-TEST_F(ConvertScenarioTrajectoryRefTest, GivenNoPolyLine_ReturnNullPtr)
+class ConvertScenarioTrajectoryRefTestParam : public ConvertScenarioTrajectoryRefTest, public ::testing::WithParamInterface<std::tuple<std::optional<std::string>, mantle_api::TrajectoryReferencePoint>>
 {
-  trajectory->SetShape(trajectoryShape);
-  trajectory->SetName("Trajectory1");
-  trajectoryRef->SetTrajectory(trajectory);
+};
 
-  // TrajectoryRef ConvertScenarioTrajectoryRef(std::shared_ptr<mantle_api::IEnvironment> environment,
-  //                                            std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::ITrajectoryRef> trajectoryRef,
-  //                                            std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::ICatalogReference> catalogReference)
+INSTANTIATE_TEST_CASE_P(
+    ConvertScenarioTrajectoryRefTestInstParam,
+    ConvertScenarioTrajectoryRefTestParam,
+    ::testing::Values(
+        std::tuple<std::optional<std::string>, mantle_api::TrajectoryReferencePoint>{"rear_axle", mantle_api::TrajectoryReferencePoint::kRearAxle},
+        std::tuple<std::optional<std::string>, mantle_api::TrajectoryReferencePoint>{"front_axle", mantle_api::TrajectoryReferencePoint::kFrontAxle},
+        std::tuple<std::optional<std::string>, mantle_api::TrajectoryReferencePoint>{"center_of_mass", mantle_api::TrajectoryReferencePoint::kCenterOfMass},
+        std::tuple<std::optional<std::string>, mantle_api::TrajectoryReferencePoint>{"bounding_box_center", mantle_api::TrajectoryReferencePoint::kBoundingBoxCenter},
+        std::tuple<std::optional<std::string>, mantle_api::TrajectoryReferencePoint>{std::nullopt, mantle_api::TrajectoryReferencePoint::kUndefined}));
+
+TEST_P(ConvertScenarioTrajectoryRefTestParam, GivenTrajectoryWithClothoidSpline_ThenConvertedTrajectoryIsCorrect)
+{
+  SetTrajectoryWithClothoidSpline();
+
+  parameter_declarations.push_back(std::make_shared<NET_ASAM_OPENSCENARIO::v1_3::ParameterDeclarationImpl>());
+  if (std::get<0>(GetParam()))
+  {
+    parameter_declarations.back()->SetName("reference");
+    parameter_declarations.back()->SetValue(std::get<0>(GetParam()).value());
+  }
 
-  auto convertedTrajectoryRef = OpenScenarioEngine::v1_3::ConvertScenarioTrajectoryRef(mockEnvironment, trajectoryRef, nullptr);
+  trajectory->SetParameterDeclarations(parameter_declarations);
 
-  EXPECT_EQ(std::nullopt, convertedTrajectoryRef);
-}
\ No newline at end of file
+  auto converted_trajectory_ref = OpenScenarioEngine::v1_3::ConvertScenarioTrajectoryRef(mockEnvironment, trajectory_ref, nullptr);
+
+  mantle_api::ClothoidSpline converted_shape;
+
+  ASSERT_NO_THROW(converted_shape = std::get<mantle_api::ClothoidSpline>(converted_trajectory_ref->type);) << "Expect trajectory type ClothoidSpline, throw exception";
+
+  EXPECT_EQ(converted_trajectory_ref->name, trajectory->GetName());
+
+  EXPECT_EQ(converted_trajectory_ref->reference, std::get<1>(GetParam()));
+
+  EXPECT_EQ(converted_shape, expected_clothoid_spline);
+}
+
+TEST_F(ConvertScenarioTrajectoryRefTest, GivenTrajectoryWithClothoidSpline_WhenInvalidReferenceIsProvided_ThenException)
+{
+  SetTrajectoryWithClothoidSpline();
+
+  parameter_declarations.push_back(std::make_shared<NET_ASAM_OPENSCENARIO::v1_3::ParameterDeclarationImpl>());
+  parameter_declarations.back()->SetName("reference");
+  parameter_declarations.back()->SetValue("invalid_value");
+
+  trajectory->SetParameterDeclarations(parameter_declarations);
+
+  EXPECT_THROW(OpenScenarioEngine::v1_3::ConvertScenarioTrajectoryRef(mockEnvironment, trajectory_ref, nullptr), std::runtime_error);
+}
+
+TEST_F(ConvertScenarioTrajectoryRefTest, GivenNoPolyLineAndNoClothoidSpline_ReturnNullPtr)
+{
+  trajectory->SetShape(trajectory_shape);
+  trajectory->SetName("Trajectory1");
+  trajectory_ref->SetTrajectory(trajectory);
+
+  auto converted_trajectory_ref = OpenScenarioEngine::v1_3::ConvertScenarioTrajectoryRef(mockEnvironment, trajectory_ref, nullptr);
+
+  EXPECT_EQ(std::nullopt, converted_trajectory_ref);
+}
+}  // namespace
diff --git a/engine/tests/OpenScenarioEngineTest.cpp b/engine/tests/OpenScenarioEngineTest.cpp
index 529f8af9452df859f597324006f6c6fef239c85b..0735928cd878208366b8851806a58f48671b6b40 100644
--- a/engine/tests/OpenScenarioEngineTest.cpp
+++ b/engine/tests/OpenScenarioEngineTest.cpp
@@ -1,5 +1,5 @@
 /*******************************************************************************
- * Copyright (c) 2023-2024, Bayerische Motoren Werke Aktiengesellschaft (BMW AG)
+ * Copyright (c) 2023-2025, Bayerische Motoren Werke Aktiengesellschaft (BMW AG)
  * Copyright (c) 2023 Ansys, Inc.
  *
  * This program and the accompanying materials are made
@@ -21,14 +21,14 @@
 #include "TestUtils.h"
 #include "Utils/Constants.h"
 
-using testing::OpenScenarioEngine::v1_3::OpenScenarioEngineTestBase;
 using OpenScenarioEngine::v1_3::GetDefaultWeather;
 using testing::OpenScenarioEngine::v1_3::GetScenariosPath;
+using testing::OpenScenarioEngine::v1_3::OpenScenarioEngineTestBase;
 
 using testing::_;
+using testing::Pointee;
 using testing::Return;
 using testing::ReturnRef;
-using testing::Pointee;
 using testing::SaveArgPointee;
 
 using namespace units::literals;
@@ -36,282 +36,283 @@ using namespace std::string_literals;
 
 class OpenScenarioEngineTest : public OpenScenarioEngineTestBase
 {
-  protected:
-    void SetUp() override {
-        OpenScenarioEngineTestBase::SetUp();
-        ON_CALL(controller_, GetName()).WillByDefault(ReturnRef(controller_name));
-        ON_CALL(controller_, GetUniqueId()).WillByDefault(Return(1234));
-    }
-
-    std::string controller_name {"TestController"s};
+protected:
+  void SetUp() override
+  {
+    OpenScenarioEngineTestBase::SetUp();
+    ON_CALL(controller_, GetName()).WillByDefault(ReturnRef(controller_name));
+    ON_CALL(controller_, GetUniqueId()).WillByDefault(Return(1234));
+  }
+
+  std::string controller_name{"TestController"s};
 };
 
 TEST_F(OpenScenarioEngineTest, GivenValidScenarioFile_WhenInitialized_ThenDefaultRoutingBehaviourIsSetBeforeControllersAreCreated)
 {
-    std::string xosc_file_path{GetScenariosPath(test_info_->file()) + default_xosc_scenario_};
+  std::string xosc_file_path{GetScenariosPath(test_info_->file()) + default_xosc_scenario_};
 
-    {
-        testing::InSequence s;
-        EXPECT_CALL(*env_, SetDefaultRoutingBehavior(mantle_api::DefaultRoutingBehavior::kRandomRoute)).Times(1);
-        EXPECT_CALL(env_->GetControllerRepository(), Create(_)).Times(2);
-    }
+  {
+    testing::InSequence s;
+    EXPECT_CALL(*env_, SetDefaultRoutingBehavior(mantle_api::DefaultRoutingBehavior::kRandomRoute)).Times(1);
+    EXPECT_CALL(env_->GetControllerRepository(), Create(_)).Times(2);
+  }
 
-    OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
 
-    EXPECT_NO_THROW(engine.Init());
-    engine.SetupDynamicContent();
+  EXPECT_NO_THROW(engine.Init());
+  engine.SetupDynamicContent();
 }
 
 TEST_F(OpenScenarioEngineTest, GivenValidScenarioFile_WhenInitializedAndSteppedOnce_ThenNoThrow)
 {
-    std::string xosc_file_path{GetScenariosPath(test_info_->file()) + default_xosc_scenario_};
+  std::string xosc_file_path{GetScenariosPath(test_info_->file()) + default_xosc_scenario_};
 
-    OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
-    EXPECT_NO_THROW(engine.Init());
-    engine.SetupDynamicContent();
-    EXPECT_NO_THROW(engine.Step(1_ms));
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+  EXPECT_NO_THROW(engine.Init());
+  engine.SetupDynamicContent();
+  EXPECT_NO_THROW(engine.Step(1_ms));
 }
 
 MATCHER_P(EqualWeather, expected_weather, "The Weather does not match the default Weather")
 {
-    return arg.fog == expected_weather.fog && arg.precipitation == expected_weather.precipitation &&
-           arg.illumination == expected_weather.illumination && arg.humidity == expected_weather.humidity &&
-           arg.temperature == expected_weather.temperature &&
-           arg.atmospheric_pressure == expected_weather.atmospheric_pressure;
+  return arg.fog == expected_weather.fog && arg.precipitation == expected_weather.precipitation &&
+         arg.illumination == expected_weather.illumination && arg.humidity == expected_weather.humidity &&
+         arg.temperature == expected_weather.temperature &&
+         arg.atmospheric_pressure == expected_weather.atmospheric_pressure;
 }
 
 TEST_F(OpenScenarioEngineTest, GivenValidScenarioFile_WhenEnvironmentDefaultInitialized_ThenVerifyDefaultWeatherSet)
 {
-    std::string xosc_file_path{GetScenariosPath(test_info_->file()) + default_xosc_scenario_};
-    OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+  std::string xosc_file_path{GetScenariosPath(test_info_->file()) + default_xosc_scenario_};
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
 
-    EXPECT_CALL(*env_, SetWeather(EqualWeather(GetDefaultWeather()))).Times(1);
-    EXPECT_NO_THROW(engine.Init());
-    engine.SetupDynamicContent();
+  EXPECT_CALL(*env_, SetWeather(EqualWeather(GetDefaultWeather()))).Times(1);
+  EXPECT_NO_THROW(engine.Init());
+  engine.SetupDynamicContent();
 }
 
 TEST_F(OpenScenarioEngineTest, GivenOscVersion1_1ScenarioFile_WhenParsingScenario_ThenScenarioContainsNewFeature)
 {
-    std::string xosc_file_path{GetScenariosPath(test_info_->file()) + "OSC_1_1_test.xosc"};
+  std::string xosc_file_path{GetScenariosPath(test_info_->file()) + "OSC_1_1_test.xosc"};
 
-    OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
-    EXPECT_NO_THROW(engine.Init());
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+  EXPECT_NO_THROW(engine.Init());
 
-    OpenScenarioEngine::v1_3::OpenScenarioEngine::OpenScenarioPtr scenario_ptr = engine.GetScenario();
+  OpenScenarioEngine::v1_3::OpenScenarioEngine::OpenScenarioPtr scenario_ptr = engine.GetScenario();
 
-    ASSERT_TRUE(scenario_ptr != nullptr);
-    auto file_header = scenario_ptr->GetFileHeader();
-    ASSERT_TRUE(file_header != nullptr);
-    auto license = file_header->GetLicense();
-    ASSERT_TRUE(license != nullptr);
+  ASSERT_TRUE(scenario_ptr != nullptr);
+  auto file_header = scenario_ptr->GetFileHeader();
+  ASSERT_TRUE(file_header != nullptr);
+  auto license = file_header->GetLicense();
+  ASSERT_TRUE(license != nullptr);
 
-    EXPECT_EQ("GLWTPL", license->GetSpdxId());
+  EXPECT_EQ("GLWTPL", license->GetSpdxId());
 }
 
 TEST_F(OpenScenarioEngineTest, GivenOscVersion1_1ScenarioFile_WhenParsingScenario_ThenExpressionsAreResolved)
 {
-    std::string xosc_file_path{GetScenariosPath(test_info_->file()) + "OSC_1_1_test.xosc"};
-
-    OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
-    EXPECT_NO_THROW(engine.Init());
-
-    OpenScenarioEngine::v1_3::OpenScenarioEngine::OpenScenarioPtr scenario_ptr = engine.GetScenario();
-
-    ASSERT_TRUE(scenario_ptr != nullptr);
-    auto open_scenario_category = scenario_ptr->GetOpenScenarioCategory();
-    ASSERT_TRUE(open_scenario_category != nullptr);
-    auto scenario_definition = open_scenario_category->GetScenarioDefinition();
-    ASSERT_TRUE(scenario_definition != nullptr);
-
-    // Expression in parameter declaration
-    double value_parametrized = scenario_definition->GetStoryboard()
-                                    ->GetInit()
-                                    ->GetActions()
-                                    ->GetPrivates()[0]
-                                    ->GetPrivateActions()[1]
-                                    ->GetLongitudinalAction()
-                                    ->GetSpeedAction()
-                                    ->GetSpeedActionTarget()
-                                    ->GetAbsoluteTargetSpeed()
-                                    ->GetValue();
-    EXPECT_EQ(20.0, value_parametrized);
-
-    // Expression in storyboard element
-    auto value = scenario_definition->GetStoryboard()
-                     ->GetStopTrigger()
-                     ->GetConditionGroupsAtIndex(0)
-                     ->GetConditionsAtIndex(0)
-                     ->GetByValueCondition()
-                     ->GetSimulationTimeCondition()
-                     ->GetValue();
-    EXPECT_EQ(300.0, value);
+  std::string xosc_file_path{GetScenariosPath(test_info_->file()) + "OSC_1_1_test.xosc"};
+
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+  EXPECT_NO_THROW(engine.Init());
+
+  OpenScenarioEngine::v1_3::OpenScenarioEngine::OpenScenarioPtr scenario_ptr = engine.GetScenario();
+
+  ASSERT_TRUE(scenario_ptr != nullptr);
+  auto open_scenario_category = scenario_ptr->GetOpenScenarioCategory();
+  ASSERT_TRUE(open_scenario_category != nullptr);
+  auto scenario_definition = open_scenario_category->GetScenarioDefinition();
+  ASSERT_TRUE(scenario_definition != nullptr);
+
+  // Expression in parameter declaration
+  double value_parametrized = scenario_definition->GetStoryboard()
+                                  ->GetInit()
+                                  ->GetActions()
+                                  ->GetPrivates()[0]
+                                  ->GetPrivateActions()[1]
+                                  ->GetLongitudinalAction()
+                                  ->GetSpeedAction()
+                                  ->GetSpeedActionTarget()
+                                  ->GetAbsoluteTargetSpeed()
+                                  ->GetValue();
+  EXPECT_EQ(20.0, value_parametrized);
+
+  // Expression in storyboard element
+  auto value = scenario_definition->GetStoryboard()
+                   ->GetStopTrigger()
+                   ->GetConditionGroupsAtIndex(0)
+                   ->GetConditionsAtIndex(0)
+                   ->GetByValueCondition()
+                   ->GetSimulationTimeCondition()
+                   ->GetValue();
+  EXPECT_EQ(300.0, value);
 }
 
 TEST_F(OpenScenarioEngineTest, GivenInvalidOscVersion1_3ScenarioFile_WhenParsingScenario_ThenThrow)
 {
-    std::string xosc_file_path{GetScenariosPath(test_info_->file()) + "OSC_1_3_test_invalid.xosc"};
+  std::string xosc_file_path{GetScenariosPath(test_info_->file()) + "OSC_1_3_test_invalid.xosc"};
 
-    OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
-    EXPECT_ANY_THROW(engine.Init());
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+  EXPECT_ANY_THROW(engine.Init());
 }
 
 TEST_F(OpenScenarioEngineTest, GivenValidOscVersion1_3ScenarioFile_WhenParsingScenario_ThenScenarioContainsNewFeature)
 {
-    std::string xosc_file_path{GetScenariosPath(test_info_->file()) + "OSC_1_3_test.xosc"};
+  std::string xosc_file_path{GetScenariosPath(test_info_->file()) + "OSC_1_3_test.xosc"};
 
-    OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
-    EXPECT_NO_THROW(engine.Init());
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+  EXPECT_NO_THROW(engine.Init());
 
-    OpenScenarioEngine::v1_3::OpenScenarioEngine::OpenScenarioPtr scenario_ptr = engine.GetScenario();
+  OpenScenarioEngine::v1_3::OpenScenarioEngine::OpenScenarioPtr scenario_ptr = engine.GetScenario();
 
-    ASSERT_TRUE(scenario_ptr != nullptr);
-    auto scenario_objects = scenario_ptr->GetOpenScenarioCategory()->GetScenarioDefinition()->GetEntities()->GetScenarioObjects();
-    ASSERT_NE(scenario_objects.size(), 0);
-    auto trailer_coupler = scenario_objects[0]->GetEntityObject()->GetVehicle()->GetTrailerCoupler();
-    ASSERT_TRUE(trailer_coupler != nullptr);
+  ASSERT_TRUE(scenario_ptr != nullptr);
+  auto scenario_objects = scenario_ptr->GetOpenScenarioCategory()->GetScenarioDefinition()->GetEntities()->GetScenarioObjects();
+  ASSERT_NE(scenario_objects.size(), 0);
+  auto trailer_coupler = scenario_objects[0]->GetEntityObject()->GetVehicle()->GetTrailerCoupler();
+  ASSERT_TRUE(trailer_coupler != nullptr);
 
-    EXPECT_EQ(trailer_coupler->GetDx(), -1.1);
-    EXPECT_EQ(trailer_coupler->GetDz(), 0.3);
+  EXPECT_EQ(trailer_coupler->GetDx(), -1.1);
+  EXPECT_EQ(trailer_coupler->GetDz(), 0.3);
 }
 
 TEST_F(OpenScenarioEngineTest, GivenValidScenarioFile_WhenParsingScenario_ThenScenarioContainsHost)
 {
-    std::string xosc_file_path{GetScenariosPath(test_info_->file()) + default_xosc_scenario_};
+  std::string xosc_file_path{GetScenariosPath(test_info_->file()) + default_xosc_scenario_};
 
-    OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
-    EXPECT_NO_THROW(engine.Init());
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+  EXPECT_NO_THROW(engine.Init());
 
-    OpenScenarioEngine::v1_3::OpenScenarioEngine::OpenScenarioPtr scenario_ptr = engine.GetScenario();
+  OpenScenarioEngine::v1_3::OpenScenarioEngine::OpenScenarioPtr scenario_ptr = engine.GetScenario();
 
-    ASSERT_TRUE(scenario_ptr != nullptr);
-    const auto& scenario_objects =
-        scenario_ptr->GetOpenScenarioCategory()->GetScenarioDefinition()->GetEntities()->GetScenarioObjects();
+  ASSERT_TRUE(scenario_ptr != nullptr);
+  const auto& scenario_objects =
+      scenario_ptr->GetOpenScenarioCategory()->GetScenarioDefinition()->GetEntities()->GetScenarioObjects();
 
-    ASSERT_EQ(1, scenario_objects.size());
-    EXPECT_EQ("Ego", scenario_objects.front()->GetName());
+  ASSERT_EQ(1, scenario_objects.size());
+  EXPECT_EQ("Ego", scenario_objects.front()->GetName());
 
-    auto catalogue_ref = scenario_objects.front()->GetEntityObject()->GetCatalogReference();
-    ASSERT_TRUE(catalogue_ref != nullptr);
+  auto catalogue_ref = scenario_objects.front()->GetEntityObject()->GetCatalogReference();
+  ASSERT_TRUE(catalogue_ref != nullptr);
 
-    EXPECT_EQ("car_ego", catalogue_ref->GetEntryName());
+  EXPECT_EQ("car_ego", catalogue_ref->GetEntryName());
 
-    auto the_ref = catalogue_ref->GetRef();
+  auto the_ref = catalogue_ref->GetRef();
 
-    ASSERT_TRUE(the_ref != nullptr);
-    ASSERT_TRUE(NET_ASAM_OPENSCENARIO::v1_3::CatalogHelper::IsVehicle(the_ref));
+  ASSERT_TRUE(the_ref != nullptr);
+  ASSERT_TRUE(NET_ASAM_OPENSCENARIO::v1_3::CatalogHelper::IsVehicle(the_ref));
 }
 
 TEST_F(OpenScenarioEngineTest, GivenScenarioWithLogicFileReference_WhenInitScenario_ThenCreateMapIsCalled)
 {
-    const std::string relative_odr_file_path_{"../../Maps/xodr/ALKS_Road_Different_Curvatures.xodr"};
-    std::string xosc_file_path{GetScenariosPath(test_info_->file()) + default_xosc_scenario_};
-    OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+  const std::string relative_odr_file_path_{"../../Maps/xodr/ALKS_Road_Different_Curvatures.xodr"};
+  std::string xosc_file_path{GetScenariosPath(test_info_->file()) + default_xosc_scenario_};
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
 
-    EXPECT_NO_THROW(engine.Init());
-    auto scenario_info = engine.GetScenarioInfo();
-    EXPECT_NE("", scenario_info.full_map_path);
+  EXPECT_NO_THROW(engine.Init());
+  auto scenario_info = engine.GetScenarioInfo();
+  EXPECT_NE("", scenario_info.full_map_path);
 }
 
 bool IsMapDetailsWithLatLon(mantle_api::MapDetails& actual_map_details)
 {
-    const auto& map_region = actual_map_details.map_region;
-    if (map_region.size() != 2)
+  const auto& map_region = actual_map_details.map_region;
+  if (map_region.size() != 2)
+  {
+    return false;
+  }
+
+  if (const auto* lat_lon_position = std::get_if<mantle_api::LatLonPosition>(&map_region.front()))
+  {
+    if (*lat_lon_position != mantle_api::LatLonPosition{48.298065_deg, 11.583095_deg})
     {
-        return false;
+      return false;
     }
+  }
 
-    if (const auto* lat_lon_position = std::get_if<mantle_api::LatLonPosition>(&map_region.front()))
+  if (const auto* lat_lon_position = std::get_if<mantle_api::LatLonPosition>(&map_region.back()))
+  {
+    if (*lat_lon_position != mantle_api::LatLonPosition{48.346524_deg, 11.720233_deg})
     {
-        if (*lat_lon_position != mantle_api::LatLonPosition{48.298065_deg, 11.583095_deg})
-        {
-            return false;
-        }
+      return false;
     }
+  }
 
-    if (const auto* lat_lon_position = std::get_if<mantle_api::LatLonPosition>(&map_region.back()))
-    {
-        if (*lat_lon_position != mantle_api::LatLonPosition{48.346524_deg, 11.720233_deg})
-        {
-            return false;
-        }
-    }
-
-    return true;
+  return true;
 }
 
 TEST_F(OpenScenarioEngineTest, GivenScenarioWithUsedArea_WhenCallInit_ThenMapDetailsAreContainedInScenarioInfo)
 {
-    std::string xosc_file_path{GetScenariosPath(test_info_->file()) +
-                               "AutomatedLaneKeepingSystemScenarios/ALKS_Scenario_4.1_1_FreeDriving_UsedArea_TEMPLATE.xosc"};
-    OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+  std::string xosc_file_path{GetScenariosPath(test_info_->file()) +
+                             "AutomatedLaneKeepingSystemScenarios/ALKS_Scenario_4.1_1_FreeDriving_UsedArea_TEMPLATE.xosc"};
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
 
-    EXPECT_NO_THROW(engine.Init());
-    auto scenario_info = engine.GetScenarioInfo();
-    EXPECT_TRUE(IsMapDetailsWithLatLon(*scenario_info.map_details));
+  EXPECT_NO_THROW(engine.Init());
+  auto scenario_info = engine.GetScenarioInfo();
+  EXPECT_TRUE(IsMapDetailsWithLatLon(*scenario_info.map_details));
 }
 
 TEST_F(OpenScenarioEngineTest, GivenScenarioWithEntities_WhenInitScenario_ThenCreateIsCalledInEnvironmentForEveryEntity)
 {
-    std::string xosc_file_path{GetScenariosPath(test_info_->file()) + default_xosc_scenario_};
-    OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
-
-    mantle_api::MockVehicle mock_vehicle{};
-
-    mantle_api::VehicleProperties ego_properties{};
-    ego_properties.type = mantle_api::EntityType::kVehicle;
-    ego_properties.classification = mantle_api::VehicleClass::kMedium_car;
-    ego_properties.model = "medium_car";
-    ego_properties.bounding_box.dimension.length = 5.0_m;
-    ego_properties.bounding_box.dimension.width = 2.0_m;
-    ego_properties.bounding_box.dimension.height = 1.8_m;
-    ego_properties.bounding_box.geometric_center.x = 1.4_m;
-    ego_properties.bounding_box.geometric_center.y = 0.0_m;
-    ego_properties.bounding_box.geometric_center.z = 0.9_m;
-    ego_properties.performance.max_acceleration = 10_mps_sq;
-    ego_properties.performance.max_deceleration = 10_mps_sq;
-    ego_properties.performance.max_speed = 70_mps;
-    ego_properties.front_axle.bb_center_to_axle_center = {1.58_m, 0.0_m, -0.5_m};
-    ego_properties.front_axle.max_steering = 0.5_rad;
-    ego_properties.front_axle.track_width = 1.68_m;
-    ego_properties.front_axle.wheel_diameter = 0.8_m;
-    ego_properties.rear_axle.bb_center_to_axle_center = {-1.4_m, 0.0_m, -0.5_m};
-    ego_properties.rear_axle.max_steering = 0_rad;
-    ego_properties.rear_axle.track_width = 1.68_m;
-    ego_properties.rear_axle.wheel_diameter = 0.8_m;
-    ego_properties.is_host = true;
-
-    EXPECT_CALL(dynamic_cast<mantle_api::MockEntityRepository&>(env_->GetEntityRepository()),
-                Create(std::string("Ego"), ego_properties))
-        .Times(1)
-        .WillRepeatedly(ReturnRef(mock_vehicle));
-
-    EXPECT_NO_THROW(engine.Init());
-    engine.SetupDynamicContent();
+  std::string xosc_file_path{GetScenariosPath(test_info_->file()) + default_xosc_scenario_};
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+
+  mantle_api::MockVehicle mock_vehicle{};
+
+  mantle_api::VehicleProperties ego_properties{};
+  ego_properties.type = mantle_api::EntityType::kVehicle;
+  ego_properties.classification = mantle_api::VehicleClass::kMedium_car;
+  ego_properties.model = "medium_car";
+  ego_properties.bounding_box.dimension.length = 5.0_m;
+  ego_properties.bounding_box.dimension.width = 2.0_m;
+  ego_properties.bounding_box.dimension.height = 1.8_m;
+  ego_properties.bounding_box.geometric_center.x = 1.4_m;
+  ego_properties.bounding_box.geometric_center.y = 0.0_m;
+  ego_properties.bounding_box.geometric_center.z = 0.9_m;
+  ego_properties.performance.max_acceleration = 10_mps_sq;
+  ego_properties.performance.max_deceleration = 10_mps_sq;
+  ego_properties.performance.max_speed = 70_mps;
+  ego_properties.front_axle.bb_center_to_axle_center = {1.58_m, 0.0_m, -0.5_m};
+  ego_properties.front_axle.max_steering = 0.5_rad;
+  ego_properties.front_axle.track_width = 1.68_m;
+  ego_properties.front_axle.wheel_diameter = 0.8_m;
+  ego_properties.rear_axle.bb_center_to_axle_center = {-1.4_m, 0.0_m, -0.5_m};
+  ego_properties.rear_axle.max_steering = 0_rad;
+  ego_properties.rear_axle.track_width = 1.68_m;
+  ego_properties.rear_axle.wheel_diameter = 0.8_m;
+  ego_properties.is_host = true;
+
+  EXPECT_CALL(dynamic_cast<mantle_api::MockEntityRepository&>(env_->GetEntityRepository()),
+              Create(std::string("Ego"), ego_properties))
+      .Times(1)
+      .WillRepeatedly(ReturnRef(mock_vehicle));
+
+  EXPECT_NO_THROW(engine.Init());
+  engine.SetupDynamicContent();
 }
 
 TEST_F(OpenScenarioEngineTest,
        GivenScenarioWithExternallyControlledEntity_WhenInit_ThenControllerWithExternalConfigIsCreatedAndAssigned)
 {
-    std::string xosc_file_path{GetScenariosPath(test_info_->file()) + default_xosc_scenario_};
-    OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
-
-    mantle_api::MockController mock_default_controller;
-    const mantle_api::UniqueId DEFAULT_CONTROLLER_ID {1234};
-    const std::string DEFAULT_CONTROLLER_NAME {"TestDefaultController"};
-    ON_CALL(mock_default_controller, GetUniqueId()).WillByDefault(Return(DEFAULT_CONTROLLER_ID));
-    ON_CALL(mock_default_controller, GetName()).WillByDefault(ReturnRef(DEFAULT_CONTROLLER_NAME));
-
-    mantle_api::MockController mock_user_defined_controller;
-    const mantle_api::UniqueId USER_DEFINED_CONTROLLER_ID {5678};
-    const std::string USER_DEFINED_CONTROLLER_NAME {"TestUserDefinedController"};
-    ON_CALL(mock_user_defined_controller, GetUniqueId()).WillByDefault(Return(USER_DEFINED_CONTROLLER_ID));
-    ON_CALL(mock_user_defined_controller, GetName()).WillByDefault(ReturnRef(USER_DEFINED_CONTROLLER_NAME));
-
-    mantle_api::InternalControllerConfig internal_config_actual;
-    mantle_api::ExternalControllerConfig external_config_actual;
-    ON_CALL(env_->GetControllerRepository(), Create(_))
-    .WillByDefault(::testing::Invoke([&](std::unique_ptr<mantle_api::IControllerConfig> received_controller) -> mantle_api::IController&
-    {
+  std::string xosc_file_path{GetScenariosPath(test_info_->file()) + default_xosc_scenario_};
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+
+  mantle_api::MockController mock_default_controller;
+  const mantle_api::UniqueId DEFAULT_CONTROLLER_ID{1234};
+  const std::string DEFAULT_CONTROLLER_NAME{"TestDefaultController"};
+  ON_CALL(mock_default_controller, GetUniqueId()).WillByDefault(Return(DEFAULT_CONTROLLER_ID));
+  ON_CALL(mock_default_controller, GetName()).WillByDefault(ReturnRef(DEFAULT_CONTROLLER_NAME));
+
+  mantle_api::MockController mock_user_defined_controller;
+  const mantle_api::UniqueId USER_DEFINED_CONTROLLER_ID{5678};
+  const std::string USER_DEFINED_CONTROLLER_NAME{"TestUserDefinedController"};
+  ON_CALL(mock_user_defined_controller, GetUniqueId()).WillByDefault(Return(USER_DEFINED_CONTROLLER_ID));
+  ON_CALL(mock_user_defined_controller, GetName()).WillByDefault(ReturnRef(USER_DEFINED_CONTROLLER_NAME));
+
+  mantle_api::InternalControllerConfig internal_config_actual;
+  mantle_api::ExternalControllerConfig external_config_actual;
+  ON_CALL(env_->GetControllerRepository(), Create(_))
+      .WillByDefault(::testing::Invoke([&](std::unique_ptr<mantle_api::IControllerConfig> received_controller) -> mantle_api::IController&
+                                       {
         if (auto internal = dynamic_cast<mantle_api::InternalControllerConfig*>(received_controller.get()))
         {
             internal_config_actual = *internal; // copy assignment, as we drop the unique_ptr
@@ -324,103 +325,102 @@ TEST_F(OpenScenarioEngineTest,
             return mock_user_defined_controller;
         }
 
-        throw std::runtime_error("Untested ControllerConfigType");
-    }));
+        throw std::runtime_error("Untested ControllerConfigType"); }));
 
-    EXPECT_CALL(*env_, AddEntityToController(_, DEFAULT_CONTROLLER_ID));
-    EXPECT_CALL(*env_, AddEntityToController(_, USER_DEFINED_CONTROLLER_ID));
+  EXPECT_CALL(*env_, AddEntityToController(_, DEFAULT_CONTROLLER_ID));
+  EXPECT_CALL(*env_, AddEntityToController(_, USER_DEFINED_CONTROLLER_ID));
 
-    EXPECT_NO_THROW(engine.Init());
-    engine.SetupDynamicContent();
+  EXPECT_NO_THROW(engine.Init());
+  engine.SetupDynamicContent();
 
-    mantle_api::InternalControllerConfig internal_config_expected{};
-    internal_config_expected.name = OpenScenarioEngine::v1_3::CONTROLLER_NAME_DEFAULT;
-    internal_config_expected.control_strategies = {
-        std::make_shared<mantle_api::KeepVelocityControlStrategy>(),
-        std::make_shared<mantle_api::KeepLaneOffsetControlStrategy>()};
+  mantle_api::InternalControllerConfig internal_config_expected{};
+  internal_config_expected.name = OpenScenarioEngine::v1_3::CONTROLLER_NAME_DEFAULT;
+  internal_config_expected.control_strategies = {
+      std::make_shared<mantle_api::KeepVelocityControlStrategy>(),
+      std::make_shared<mantle_api::KeepLaneOffsetControlStrategy>()};
 
-    mantle_api::ExternalControllerConfig external_config_expected{};
-    external_config_expected.name = "ALKSController",
-    external_config_expected.parameters.emplace("controller_property", "3");
+  mantle_api::ExternalControllerConfig external_config_expected{};
+  external_config_expected.name = "ALKSController",
+  external_config_expected.parameters.emplace("controller_property", "3");
 
-    EXPECT_EQ(internal_config_expected, internal_config_actual);
-    EXPECT_EQ(external_config_expected, external_config_actual);
+  EXPECT_EQ(internal_config_expected, internal_config_actual);
+  EXPECT_EQ(external_config_expected, external_config_actual);
 }
 
 TEST_F(OpenScenarioEngineTest, GivenScenarioWithInitTeleportAction_WhenInitAndStepEngine_ThenSetPositionIsCalled)
 {
-    std::string xosc_file_path{GetScenariosPath(test_info_->file()) + default_xosc_scenario_};
-    OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+  std::string xosc_file_path{GetScenariosPath(test_info_->file()) + default_xosc_scenario_};
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
 
-    EXPECT_CALL(dynamic_cast<mantle_api::MockVehicle&>(env_->GetEntityRepository().Get("").value().get()),
-                SetPosition(_))
-        .Times(1);
+  EXPECT_CALL(dynamic_cast<mantle_api::MockVehicle&>(env_->GetEntityRepository().Get("").value().get()),
+              SetPosition(_))
+      .Times(1);
 
-    EXPECT_NO_THROW(engine.Init());
-    engine.SetupDynamicContent();
-    EXPECT_NO_THROW(engine.Step(1_ms));
+  EXPECT_NO_THROW(engine.Init());
+  engine.SetupDynamicContent();
+  EXPECT_NO_THROW(engine.Step(1_ms));
 }
 
 TEST_F(OpenScenarioEngineTest, GivenExistingScenarioFileWithWrongCatalog_WhenValidateScenario_ThenReturnsNumberofErrors)
 {
-    std::string xosc_file_path{GetScenariosPath(test_info_->file()) + "scenario_with_wrong_catalog_path.xosc"};
-    OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
-    EXPECT_EQ(3, engine.ValidateScenario());
+  std::string xosc_file_path{GetScenariosPath(test_info_->file()) + "scenario_with_wrong_catalog_path.xosc"};
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+  EXPECT_EQ(3, engine.ValidateScenario());
 }
 
 TEST_F(OpenScenarioEngineTest, GivenExistingScenarioFileWithWrongCatalog_WhenValidateScenario_ThenReturnsZero)
 {
-    std::string xosc_file_path{GetScenariosPath(test_info_->file()) + default_xosc_scenario_};
-    OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
-    EXPECT_EQ(0, engine.ValidateScenario());
+  std::string xosc_file_path{GetScenariosPath(test_info_->file()) + default_xosc_scenario_};
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+  EXPECT_EQ(0, engine.ValidateScenario());
 }
 
 TEST_F(OpenScenarioEngineTest, GivenScenarioWithOneSimulationTimeStopTrigger_WhenGetDuration_ThenReturnsDuration)
 {
-    std::string xosc_file_path{GetScenariosPath(test_info_->file()) + "OSC_1_1_test.xosc"};
+  std::string xosc_file_path{GetScenariosPath(test_info_->file()) + "OSC_1_1_test.xosc"};
 
-    OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
-    EXPECT_NO_THROW(engine.Init());
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+  EXPECT_NO_THROW(engine.Init());
 
-    EXPECT_EQ(engine.GetScenarioInfo().scenario_timeout_duration, units::time::second_t(300.0));
+  EXPECT_EQ(engine.GetScenarioInfo().scenario_timeout_duration, units::time::second_t(300.0));
 }
 
 TEST_F(OpenScenarioEngineTest, GivenScenarioWithTwoSimulationTimeStopTrigger_WhenGetDuration_ThenReturnsMaxDuration)
 {
-    std::string xosc_file_path{GetScenariosPath(test_info_->file()) + "OSC_1_1_test_TwoSimulationTimeConditions.xosc"};
+  std::string xosc_file_path{GetScenariosPath(test_info_->file()) + "OSC_1_1_test_TwoSimulationTimeConditions.xosc"};
 
-    OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
-    EXPECT_NO_THROW(engine.Init());
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+  EXPECT_NO_THROW(engine.Init());
 
-    EXPECT_EQ(engine.GetScenarioInfo().scenario_timeout_duration, units::time::second_t(300.0));
+  EXPECT_EQ(engine.GetScenarioInfo().scenario_timeout_duration, units::time::second_t(300.0));
 }
 
 TEST_F(OpenScenarioEngineTest, GivenScenarioWithNoSimulationTimeStopTrigger_WhenGetDuration_ThenReturnsMaxDouble)
 {
-    std::string xosc_file_path{GetScenariosPath(test_info_->file()) + "OSC_1_1_test_NoSimulationTimeCondition.xosc"};
+  std::string xosc_file_path{GetScenariosPath(test_info_->file()) + "OSC_1_1_test_NoSimulationTimeCondition.xosc"};
 
-    OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
-    EXPECT_NO_THROW(engine.Init());
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+  EXPECT_NO_THROW(engine.Init());
 
-    EXPECT_EQ(engine.GetScenarioInfo().scenario_timeout_duration, mantle_api::Time{std::numeric_limits<double>::max()});
+  EXPECT_EQ(engine.GetScenarioInfo().scenario_timeout_duration, mantle_api::Time{std::numeric_limits<double>::max()});
 }
 
 TEST_F(OpenScenarioEngineTest, GivenValidScenarioFile_WhenActivateExternalHostControlIsCalledWithoutInit_ThenNoThrow)
 {
-    std::string xosc_file_path{GetScenariosPath(test_info_->file()) + default_xosc_scenario_};
+  std::string xosc_file_path{GetScenariosPath(test_info_->file()) + default_xosc_scenario_};
 
-    OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
-    EXPECT_NO_THROW(engine.ActivateExternalHostControl());
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+  EXPECT_NO_THROW(engine.ActivateExternalHostControl());
 }
 
 TEST_F(OpenScenarioEngineTest, GivenScenarioWithSceneGraphFile_WhenParsingScenario_ThenSceneGraphFileRead)
 {
-    std::string xosc_file_path{GetScenariosPath(test_info_->file()) + "OSC_1_1_test.xosc"};
+  std::string xosc_file_path{GetScenariosPath(test_info_->file()) + "OSC_1_1_test.xosc"};
 
-    OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
-    EXPECT_NO_THROW(engine.Init());
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+  EXPECT_NO_THROW(engine.Init());
 
-    EXPECT_EQ(engine.GetScenarioInfo().map_model_reference, "/File/Path/To/Unexisted/3D/ModelFile");
+  EXPECT_EQ(engine.GetScenarioInfo().map_model_reference, "/File/Path/To/Unexisted/3D/ModelFile");
 }
 
 class MapRegionTypeParamFixture : public ::testing::WithParamInterface<std::tuple<std::string, mantle_api::MapRegionType>>,
@@ -430,13 +430,13 @@ class MapRegionTypeParamFixture : public ::testing::WithParamInterface<std::tupl
 
 TEST_P(MapRegionTypeParamFixture, GivenScenarioWithUsedAreaType_WhenCallGetScenarioInfo_ThenCorrectMapRegionType)
 {
-    const auto [scenario, map_region_type] = GetParam();
-    std::string xosc_file_path{GetScenariosPath(testing::UnitTest::GetInstance()->current_test_info()->file()) + scenario};
-    OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+  const auto [scenario, map_region_type] = GetParam();
+  std::string xosc_file_path{GetScenariosPath(testing::UnitTest::GetInstance()->current_test_info()->file()) + scenario};
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
 
-    EXPECT_NO_THROW(engine.Init());
-    auto scenario_info = engine.GetScenarioInfo();
-    EXPECT_EQ(scenario_info.map_details->map_region_type, map_region_type);
+  EXPECT_NO_THROW(engine.Init());
+  auto scenario_info = engine.GetScenarioInfo();
+  EXPECT_EQ(scenario_info.map_details->map_region_type, map_region_type);
 }
 
 INSTANTIATE_TEST_SUITE_P(MapRegionTypeTests,
@@ -448,10 +448,64 @@ INSTANTIATE_TEST_SUITE_P(MapRegionTypeTests,
 
 TEST_F(OpenScenarioEngineTest, GivenScenarioWithWrongUsedAreaType_WhenCallGetScenarioInfo_ThenThrowError)
 {
-    std::string xosc_file_path{GetScenariosPath(test_info_->file()) +
-                               "wrong_used_area_type.xosc"};
-    OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+  std::string xosc_file_path{GetScenariosPath(test_info_->file()) +
+                             "wrong_used_area_type.xosc"};
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+
+  EXPECT_NO_THROW(engine.Init());
+  EXPECT_THROW(engine.GetScenarioInfo(), std::runtime_error);
+}
 
-    EXPECT_NO_THROW(engine.Init());
-    EXPECT_THROW(engine.GetScenarioInfo(), std::runtime_error);
+TEST_F(OpenScenarioEngineTest, GivenScenarioWithTrajectoryReference_ThenTrajectoryReferenceIsCorrect)
+{
+  std::string xosc_file_path{GetScenariosPath(testing::UnitTest::GetInstance()->current_test_info()->file()) + "trajectory_shape.xosc"};
+  OpenScenarioEngine::v1_3::OpenScenarioEngine engine(xosc_file_path, env_);
+  ASSERT_NO_THROW(engine.Init());
+  auto scenario = engine.GetScenario();
+
+  auto trajectory = scenario->GetOpenScenarioCategory()
+                        ->GetScenarioDefinition()
+                        ->GetStoryboard()
+                        ->GetStories()[0]
+                        ->GetActs()[0]
+                        ->GetManeuverGroups()[0]
+                        ->GetManeuvers()[0]
+                        ->GetEvents()[0]
+                        ->GetActions()[0]
+                        ->GetPrivateAction()
+                        ->GetRoutingAction()
+                        ->GetFollowTrajectoryAction()
+                        ->GetTrajectoryRef()
+                        ->GetTrajectory();
+
+  ASSERT_EQ(trajectory->GetParameterDeclarationsSize(), 1);
+  EXPECT_EQ(trajectory->GetParameterDeclarations()[0]->GetName(), "reference");
+  EXPECT_EQ(trajectory->GetParameterDeclarations()[0]->GetValue(), "rear_axle");
+
+  ASSERT_TRUE(trajectory->GetShape()->IsSetClothoidSpline());
+
+  auto clothoid_spline = trajectory->GetShape()->GetClothoidSpline();
+  ASSERT_EQ(clothoid_spline->GetSegmentsSize(), 2);
+
+  EXPECT_EQ(clothoid_spline->GetSegments()[0]->GetCurvatureEnd(), 0.1);
+  EXPECT_EQ(clothoid_spline->GetSegments()[0]->GetCurvatureStart(), 2.2);
+  EXPECT_FALSE(clothoid_spline->GetSegments()[0]->IsSetHOffset());
+  EXPECT_EQ(clothoid_spline->GetSegments()[0]->GetLength(), 1.6);
+  ASSERT_TRUE(clothoid_spline->GetSegments()[0]->IsSetPositionStart());
+  EXPECT_TRUE(clothoid_spline->GetSegments()[0]->GetPositionStart()->IsSetWorldPosition());
+  EXPECT_EQ(clothoid_spline->GetSegments()[0]->GetPositionStart()->GetWorldPosition()->GetX(), 4.4);
+  EXPECT_EQ(clothoid_spline->GetSegments()[0]->GetPositionStart()->GetWorldPosition()->GetY(), 1.4);
+  EXPECT_EQ(clothoid_spline->GetSegments()[0]->GetPositionStart()->GetWorldPosition()->GetZ(), 3.9);
+  EXPECT_EQ(clothoid_spline->GetSegments()[0]->GetPositionStart()->GetWorldPosition()->GetH(), 5.9);
+  EXPECT_EQ(clothoid_spline->GetSegments()[0]->GetPositionStart()->GetWorldPosition()->GetP(), 9.1);
+  EXPECT_EQ(clothoid_spline->GetSegments()[0]->GetPositionStart()->GetWorldPosition()->GetR(), 0.3);
+
+  EXPECT_EQ(clothoid_spline->GetSegments()[1]->GetCurvatureEnd(), 6.2);
+  EXPECT_EQ(clothoid_spline->GetSegments()[1]->GetCurvatureStart(), 5.4);
+  ASSERT_TRUE(clothoid_spline->GetSegments()[1]->IsSetHOffset());
+  EXPECT_EQ(clothoid_spline->GetSegments()[1]->GetHOffset(), 0.2);
+  EXPECT_EQ(clothoid_spline->GetSegments()[1]->GetLength(), 2.6);
+  ASSERT_FALSE(clothoid_spline->GetSegments()[1]->IsSetPositionStart());
+
+  EXPECT_NO_THROW(engine.SetupDynamicContent());
 }
diff --git a/engine/tests/TestUtils/ClothoidSplineUtils.cpp b/engine/tests/TestUtils/ClothoidSplineUtils.cpp
new file mode 100644
index 0000000000000000000000000000000000000000..957510ee82142892db199af2fe4eb10961d326e1
--- /dev/null
+++ b/engine/tests/TestUtils/ClothoidSplineUtils.cpp
@@ -0,0 +1,52 @@
+/********************************************************************************
+ * Copyright (c) 2025 Bayerische Motoren Werke Aktiengesellschaft (BMW AG)
+ *
+ * This program and the accompanying materials are made available under the
+ * terms of the Eclipse Public License 2.0 which is available at
+ * http://www.eclipse.org/legal/epl-2.0.
+ *
+ * SPDX-License-Identifier: EPL-2.0
+ ********************************************************************************/
+
+#include "TestUtils/ClothoidSplineUtils.h"
+
+#include <MantleAPI/Common/pose.h>
+#include <openScenarioLib/generated/v1_3/impl/ApiClassImplV1_3.h>
+
+namespace testing::OpenScenarioEngine::v1_3::detail
+{
+// Create WorldPosition
+std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::IWorldPositionWriter> CreateWorldPosition(const mantle_api::Pose& world_position)
+{
+  auto position = std::make_shared<NET_ASAM_OPENSCENARIO::v1_3::WorldPositionImpl>();
+  position->SetX(world_position.position.x.value());
+  position->SetY(world_position.position.y.value());
+  position->SetZ(world_position.position.z.value());
+  position->SetH(world_position.orientation.yaw.value());
+  position->SetP(world_position.orientation.pitch.value());
+  position->SetR(world_position.orientation.roll.value());
+  return position;
+}
+}  // namespace testing::OpenScenarioEngine::v1_3::detail
+
+namespace testing::OpenScenarioEngine::v1_3
+{
+
+std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::IClothoidSplineSegmentWriter> CreateClothoidSegment(const mantle_api::ClothoidSplineSegment& clothoid_spline_segment)
+{
+  auto segment = std::make_shared<NET_ASAM_OPENSCENARIO::v1_3::ClothoidSplineSegmentImpl>();
+
+  segment->SetCurvatureEnd(clothoid_spline_segment.curvature_end.value());
+  segment->SetCurvatureStart(clothoid_spline_segment.curvature_start.value());
+  segment->SetHOffset(clothoid_spline_segment.h_offset.value());
+  segment->SetLength(clothoid_spline_segment.length.value());
+  if (clothoid_spline_segment.position_start.has_value())
+  {
+    auto world_position = detail::CreateWorldPosition(clothoid_spline_segment.position_start.value());
+    auto osc_position_start = std::make_shared<NET_ASAM_OPENSCENARIO::v1_3::PositionImpl>();
+    osc_position_start->SetWorldPosition(world_position);
+    segment->SetPositionStart(osc_position_start);
+  }
+  return segment;
+}
+}  // namespace testing::OpenScenarioEngine::v1_3
diff --git a/engine/tests/TestUtils/ClothoidSplineUtils.h b/engine/tests/TestUtils/ClothoidSplineUtils.h
new file mode 100644
index 0000000000000000000000000000000000000000..6f455fe3e380d03c4f8477ed5171fe21b6e173eb
--- /dev/null
+++ b/engine/tests/TestUtils/ClothoidSplineUtils.h
@@ -0,0 +1,21 @@
+/********************************************************************************
+ * Copyright (c) 2025 Bayerische Motoren Werke Aktiengesellschaft (BMW AG)
+ *
+ * This program and the accompanying materials are made available under the
+ * terms of the Eclipse Public License 2.0 which is available at
+ * http://www.eclipse.org/legal/epl-2.0.
+ *
+ * SPDX-License-Identifier: EPL-2.0
+ ********************************************************************************/
+
+#pragma once
+
+#include <MantleAPI/Common/clothoid_spline.h>
+#include <openScenarioLib/generated/v1_3/api/writer/ApiClassWriterInterfacesV1_3.h>
+
+#include <memory>
+
+namespace testing::OpenScenarioEngine::v1_3
+{
+std::shared_ptr<NET_ASAM_OPENSCENARIO::v1_3::IClothoidSplineSegmentWriter> CreateClothoidSegment(const mantle_api::ClothoidSplineSegment& clothoid_spline_segment);
+}  // namespace testing::OpenScenarioEngine::v1_3
diff --git a/engine/tests/data/Scenarios/trajectory_shape.xosc b/engine/tests/data/Scenarios/trajectory_shape.xosc
new file mode 100644
index 0000000000000000000000000000000000000000..fa857e6434579d2c94cf4ebfcf684d914db55421
--- /dev/null
+++ b/engine/tests/data/Scenarios/trajectory_shape.xosc
@@ -0,0 +1,116 @@
+<?xml version="1.0" encoding="utf-8"?>
+<OpenSCENARIO>
+  <FileHeader revMajor="1" revMinor="3" date="2025-01-21T10:00:00"
+    description="Scenario for testing clothoid spline trajectory shape" author="BMW AG" />
+  <ParameterDeclarations>
+    <!-- The ParameterDeclarations section is needed for easy variation. -->
+    <ParameterDeclaration name="Ego_InitPosition_LaneId" parameterType="string"
+      value="-4" />
+    <ParameterDeclaration name="Ego_InitSpeed_Ve0" parameterType="double"
+      value="16.66666667" />
+    <ParameterDeclaration name="Duration" parameterType="double" value="40" />
+    value="1.57" /> </ParameterDeclarations>
+  <CatalogLocations>
+    <VehicleCatalog>
+      <Directory path="Catalogs/Vehicles" />
+    </VehicleCatalog>
+  </CatalogLocations>
+  <RoadNetwork>
+    <LogicFile filepath="../Maps/xodr/ALKS_Road.xodr" />
+  </RoadNetwork>
+  <Entities>
+    <ScenarioObject name="Ego">
+      <CatalogReference catalogName="VehicleCatalog" entryName="car_ego">
+      </CatalogReference>
+    </ScenarioObject>
+  </Entities>
+  <Storyboard>
+    <Init>
+      <Actions>
+        <Private entityRef="Ego">
+          <PrivateAction>
+            <TeleportAction>
+              <Position>
+                <LanePosition roadId="0" laneId="$Ego_InitPosition_LaneId" offset="0.0" s="0.0">
+                </LanePosition>
+              </Position>
+            </TeleportAction>
+          </PrivateAction>
+          <PrivateAction>
+            <LongitudinalAction>
+              <SpeedAction>
+                <SpeedActionDynamics dynamicsShape="step" dynamicsDimension="time" value="0" />
+                <SpeedActionTarget>
+                  <AbsoluteTargetSpeed value="$Ego_InitSpeed_Ve0" />
+                </SpeedActionTarget>
+              </SpeedAction>
+            </LongitudinalAction>
+          </PrivateAction>
+        </Private>
+      </Actions>
+    </Init>
+    <Story name="MovementStory">
+      <Act name="MovementAct">
+        <ManeuverGroup maximumExecutionCount="1" name="MovementSequence">
+          <Actors selectTriggeringEntities="false">
+            <EntityRef entityRef="Ego" />
+          </Actors>
+          <Maneuver name="MovementManeuver">
+            <Event name="MovementEvent" priority="overwrite">
+              <Action name="MovementAction">
+                <PrivateAction>
+                  <RoutingAction>
+                    <FollowTrajectoryAction>
+                      <TrajectoryRef>
+                        <Trajectory name="MovementTrajectory" closed="false">
+                          <ParameterDeclarations>
+                            <ParameterDeclaration name="reference" value="rear_axle"
+                              parameterType="string" />
+                          </ParameterDeclarations>
+                          <Shape>
+                            <ClothoidSpline>
+                              <ClothoidSplineSegment curvatureEnd="0.1" curvatureStart="2.2"
+                                length="1.6">
+                                <PositionStart>
+                                  <WorldPosition x="4.4" y="1.4" z="3.9" h="5.9" p="9.1" r="0.3" />
+                                </PositionStart>
+                              </ClothoidSplineSegment>
+                              <ClothoidSplineSegment curvatureEnd="6.2" curvatureStart="5.4"
+                                hOffset="0.2" length="2.6" />
+                            </ClothoidSpline>
+                          </Shape>
+                        </Trajectory>
+                      </TrajectoryRef>
+                      <TimeReference>
+                        <None />
+                      </TimeReference>
+                      <TrajectoryFollowingMode followingMode="position" />
+                    </FollowTrajectoryAction>
+                  </RoutingAction>
+                </PrivateAction>
+              </Action>
+            </Event>
+          </Maneuver>
+        </ManeuverGroup>
+        <StartTrigger>
+          <ConditionGroup>
+            <Condition name="MovementActStart" delay="0" conditionEdge="rising">
+              <ByValueCondition>
+                <SimulationTimeCondition value="0" rule="greaterThan" />
+              </ByValueCondition>
+            </Condition>
+          </ConditionGroup>
+        </StartTrigger>
+      </Act>
+    </Story>
+    <StopTrigger>
+      <ConditionGroup>
+        <Condition name="End" delay="0" conditionEdge="rising">
+          <ByValueCondition>
+            <SimulationTimeCondition value="$Duration" rule="greaterThan" />
+          </ByValueCondition>
+        </Condition>
+      </ConditionGroup>
+    </StopTrigger>
+  </Storyboard>
+</OpenSCENARIO>
diff --git a/utils/ci/conan/conanfile.txt b/utils/ci/conan/conanfile.txt
index 2a441ba35ce37b88f1ce4209146e527a91d551ea..f733534bc497fc8ef06feeda479bdc65a2268baf 100644
--- a/utils/ci/conan/conanfile.txt
+++ b/utils/ci/conan/conanfile.txt
@@ -1,6 +1,6 @@
 [requires]
 units/2.3.3@openscenarioengine/testing
-mantleapi/v6.0.0@openscenarioengine/testing
+mantleapi/v8.0.0@openscenarioengine/testing
 yase/d0c0e58d17358044cc9018c74308b45f6097ecfb@openscenarioengine/testing
 openscenario_api/v1.4.0@openscenarioengine/testing
 
diff --git a/utils/ci/conan/recipe/mantleapi/all/conandata.yml b/utils/ci/conan/recipe/mantleapi/all/conandata.yml
index e336543c99e7a2e3aaaab6fea068c5166f28d25b..2cd2f925448662842259e731b7e671b2c6858630 100644
--- a/utils/ci/conan/recipe/mantleapi/all/conandata.yml
+++ b/utils/ci/conan/recipe/mantleapi/all/conandata.yml
@@ -1,5 +1,5 @@
 ################################################################################
-# Copyright (c) 2023-2024 Bayerische Motoren Werke Aktiengesellschaft (BMW AG)
+# Copyright (c) 2023-2025 Bayerische Motoren Werke Aktiengesellschaft (BMW AG)
 #
 # This program and the accompanying materials are made available under the
 # terms of the Eclipse Public License 2.0 which is available at
@@ -41,5 +41,9 @@ sources:
     url: https://gitlab.eclipse.org/eclipse/openpass/mantle-api.git
     sha256: "a5530013edcd2028ce48d1dcd7e90a512c158f27"
 
+  "8.0.0":
+    url: https://gitlab.eclipse.org/eclipse/openpass/mantle-api.git
+    sha256: "18eadd8ad4f3ddd78c955ce3d4d637a8ff912091"
+
   "default":
     url: https://gitlab.eclipse.org/eclipse/openpass/mantle-api.git