scenario_simulator_v2 C++ API
lanelet_loader.hpp
Go to the documentation of this file.
1 // Copyright 2015 TIER IV, Inc. All rights reserved.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 #ifndef TRAFFIC_SIMULATOR__LANELET_LOADER_HPP_
15 #define TRAFFIC_SIMULATOR__LANELET_LOADER_HPP_
16 
17 #include <lanelet2_io/Io.h>
18 
19 #include <filesystem>
20 
21 namespace traffic_simulator
22 {
23 namespace lanelet_wrapper
24 {
26 {
27 public:
28  static auto load(const std::filesystem::path & lanelet_map_path) -> lanelet::LaneletMapPtr;
29 
30 private:
31  static auto overwriteLaneletsCenterline(lanelet::LaneletMapPtr) -> void;
32  static auto resamplePoints(
33  const lanelet::ConstLineString3d & line_string, const std::int32_t num_segments)
34  -> lanelet::BasicPoints3d;
35  static auto calculateAccumulatedLengths(const lanelet::ConstLineString3d & line_string)
36  -> std::vector<double>;
37 };
38 } // namespace lanelet_wrapper
39 } // namespace traffic_simulator
40 #endif // TRAFFIC_SIMULATOR__LANELET_LOADER_HPP_
Definition: lanelet_loader.hpp:26
static auto load(const std::filesystem::path &lanelet_map_path) -> lanelet::LaneletMapPtr
Definition: lanelet_loader.cpp:26
Definition: api.hpp:48