scenario_simulator_v2 C++ API
lanelet_map.hpp
Go to the documentation of this file.
1 // Copyright 2015 TIER IV, Inc. All rights reserved.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef TRAFFIC_SIMULATOR__UTILS__LANELET_MAP_HPP_
16 #define TRAFFIC_SIMULATOR__UTILS__LANELET_MAP_HPP_
17 
18 #include <autoware_lanelet2_extension/visualization/visualization.hpp>
19 #include <geometry_msgs/msg/point.hpp>
24 
25 namespace traffic_simulator
26 {
27 inline namespace lanelet_map
28 {
31 
32 template <typename... Ts>
33 inline auto activate(Ts &&... xs)
34 {
35  return lanelet_wrapper::LaneletWrapper::activate(std::forward<decltype(xs)>(xs)...);
36 }
37 
38 auto laneletLength(const lanelet::Id lanelet_id) -> double;
39 
40 template <typename... Ts>
41 inline auto laneletAltitude(Ts &&... xs)
42 {
43  return lanelet_wrapper::lanelet_map::laneletAltitude(std::forward<decltype(xs)>(xs)...);
44 }
45 
48 auto noNextLaneletPoses() -> std::vector<std::pair<lanelet::Id, Pose>>;
49 } // namespace lanelet_map
50 } // namespace traffic_simulator
51 #endif // TRAFFIC_SIMULATOR__UTILS__LANELET_MAP_HPP_
static auto activate(const std::string &lanelet_map_path) -> void
Definition: lanelet_wrapper.cpp:23
auto activate(Ts &&... xs)
Definition: lanelet_map.hpp:33
geometry_msgs::msg::Pose Pose
Definition: lanelet_map.hpp:30
auto laneletAltitude(Ts &&... xs)
Definition: lanelet_map.hpp:41
geometry_msgs::msg::Point Point
Definition: lanelet_map.hpp:29
auto noNextLaneletPoses() -> std::vector< std::pair< lanelet::Id, Pose >>
Calculates all poses on the map that have no next lanelet (dead ends)
Definition: lanelet_map.cpp:26
auto laneletLength(const lanelet::Id lanelet_id) -> double
Definition: lanelet_map.cpp:21
auto laneletAltitude(const lanelet::Id &lanelet_id, const geometry_msgs::msg::Pose &pose, const double matching_distance) -> std::optional< double >
Definition: lanelet_map.cpp:47
Definition: api.hpp:48
Definition: junit5.hpp:25