scenario_simulator_v2 C++ API
distance.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__DISTANCE_HPP_
16 #define TRAFFIC_SIMULATOR__UTILS__DISTANCE_HPP_
17 
21 #include <traffic_simulator_msgs/msg/waypoints_array.hpp>
22 
23 namespace traffic_simulator
24 {
25 inline namespace distance
26 {
27 // Lateral
28 auto lateralDistance(
29  const CanonicalizedLaneletPose & from, const CanonicalizedLaneletPose & to,
30  const RoutingConfiguration & routing_configuration) -> std::optional<double>;
31 
32 auto lateralDistance(
33  const CanonicalizedLaneletPose & from, const CanonicalizedLaneletPose & to,
34  const double matching_distance, const RoutingConfiguration & routing_configuration)
35  -> std::optional<double>;
36 
37 // Lateral (unit: lanes)
38 auto countLaneChanges(
39  const CanonicalizedLaneletPose & from, const CanonicalizedLaneletPose & to,
40  const traffic_simulator::RoutingConfiguration & routing_configuration,
41  const std::shared_ptr<hdmap_utils::HdMapUtils> & hdmap_utils_ptr)
42  -> std::optional<std::pair<int, int>>;
43 
44 // Longitudinal
46  const CanonicalizedLaneletPose & from, const CanonicalizedLaneletPose & to,
47  bool include_adjacent_lanelet, bool include_opposite_direction,
48  const traffic_simulator::RoutingConfiguration & routing_configuration,
49  const std::shared_ptr<hdmap_utils::HdMapUtils> & hdmap_utils_ptr) -> std::optional<double>;
50 
51 // BoundingBox
53  const geometry_msgs::msg::Pose & from,
54  const traffic_simulator_msgs::msg::BoundingBox & from_bounding_box,
55  const geometry_msgs::msg::Pose & to,
56  const traffic_simulator_msgs::msg::BoundingBox & to_bounding_box) -> std::optional<double>;
57 
59  const CanonicalizedLaneletPose & from,
60  const traffic_simulator_msgs::msg::BoundingBox & from_bounding_box,
61  const CanonicalizedLaneletPose & to,
62  const traffic_simulator_msgs::msg::BoundingBox & to_bounding_box,
63  const RoutingConfiguration & routing_configuration) -> std::optional<double>;
64 
66  const CanonicalizedLaneletPose & from,
67  const traffic_simulator_msgs::msg::BoundingBox & from_bounding_box,
68  const CanonicalizedLaneletPose & to,
69  const traffic_simulator_msgs::msg::BoundingBox & to_bounding_box, bool include_adjacent_lanelet,
70  bool include_opposite_direction,
71  const traffic_simulator::RoutingConfiguration & routing_configuration,
72  const std::shared_ptr<hdmap_utils::HdMapUtils> & hdmap_utils_ptr) -> std::optional<double>;
73 
75  const std::optional<double> & longitudinal_distance,
76  const traffic_simulator_msgs::msg::BoundingBox & from_bounding_box,
77  const traffic_simulator_msgs::msg::BoundingBox & to_bounding_box) -> std::optional<double>;
78 
79 // Bounds
81  const geometry_msgs::msg::Pose & map_pose,
82  const traffic_simulator_msgs::msg::BoundingBox & bounding_box, const lanelet::Id lanelet_id)
83  -> double;
84 
86  const geometry_msgs::msg::Pose & map_pose,
87  const traffic_simulator_msgs::msg::BoundingBox & bounding_box, const lanelet::Ids & lanelet_ids)
88  -> double;
89 
91  const geometry_msgs::msg::Pose & map_pose,
92  const traffic_simulator_msgs::msg::BoundingBox & bounding_box, const lanelet::Id lanelet_id)
93  -> double;
94 
96  const geometry_msgs::msg::Pose & map_pose,
97  const traffic_simulator_msgs::msg::BoundingBox & bounding_box, const lanelet::Ids & lanelet_ids)
98  -> double;
99 
101  const geometry_msgs::msg::Pose & map_pose,
102  const traffic_simulator_msgs::msg::BoundingBox & bounding_box, const lanelet::Id lanelet_id)
103  -> double;
104 
106  const geometry_msgs::msg::Pose & map_pose,
107  const traffic_simulator_msgs::msg::BoundingBox & bounding_box, const lanelet::Ids & lanelet_ids)
108  -> double;
109 
110 // Other objects
112  const traffic_simulator_msgs::msg::WaypointsArray & waypoints_array,
113  const lanelet::Id target_crosswalk_id,
114  const std::shared_ptr<hdmap_utils::HdMapUtils> & hdmap_utils_ptr) -> std::optional<double>;
115 
116 template <typename... Ts>
117 auto distanceToStopLine(Ts &&... xs)
118 {
119  return lanelet_wrapper::distance::distanceToStopLine(std::forward<decltype(xs)>(xs)...);
120 }
121 
122 // spline
123 auto distanceToSpline(
124  const geometry_msgs::msg::Pose & map_pose,
125  const traffic_simulator_msgs::msg::BoundingBox & bounding_box,
126  const math::geometry::CatmullRomSplineInterface & spline, const double s_reference) -> double;
127 } // namespace distance
128 } // namespace traffic_simulator
129 #endif // TRAFFIC_SIMULATOR__UTILS__DISTANCE_HPP_
Definition: catmull_rom_spline_interface.hpp:30
Definition: lanelet_pose.hpp:28
auto distance(const geometry_msgs::Pose &pose1, const geometry_msgs::Pose &pose2)
Definition: detection_sensor.cpp:42
auto boundingBoxLaneLongitudinalDistance(const CanonicalizedLaneletPose &from, const traffic_simulator_msgs::msg::BoundingBox &from_bounding_box, const CanonicalizedLaneletPose &to, const traffic_simulator_msgs::msg::BoundingBox &to_bounding_box, bool include_adjacent_lanelet, bool include_opposite_direction, const traffic_simulator::RoutingConfiguration &routing_configuration, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> std::optional< double >
Definition: distance.cpp:170
auto distanceToLaneBound(const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::BoundingBox &bounding_box, const lanelet::Id lanelet_id) -> double
Definition: distance.cpp:295
auto distanceToCrosswalk(const traffic_simulator_msgs::msg::WaypointsArray &waypoints_array, const lanelet::Id target_crosswalk_id, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> std::optional< double >
Definition: distance.cpp:315
auto distanceToSpline(const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::BoundingBox &bounding_box, const math::geometry::CatmullRomSplineInterface &spline, const double s_reference) -> double
Definition: distance.cpp:329
auto distanceToRightLaneBound(const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::BoundingBox &bounding_box, const lanelet::Id lanelet_id) -> double
Definition: distance.cpp:259
auto countLaneChanges(const CanonicalizedLaneletPose &from, const CanonicalizedLaneletPose &to, const traffic_simulator::RoutingConfiguration &routing_configuration, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> std::optional< std::pair< int, int >>
Definition: distance.cpp:51
auto lateralDistance(const CanonicalizedLaneletPose &from, const CanonicalizedLaneletPose &to, const RoutingConfiguration &routing_configuration) -> std::optional< double >
Definition: distance.cpp:29
auto longitudinalDistance(const CanonicalizedLaneletPose &from, const CanonicalizedLaneletPose &to, bool include_adjacent_lanelet, bool include_opposite_direction, const traffic_simulator::RoutingConfiguration &routing_configuration, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> std::optional< double >
Definition: distance.cpp:62
auto distanceToLeftLaneBound(const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::BoundingBox &bounding_box, const lanelet::Id lanelet_id) -> double
Definition: distance.cpp:224
auto boundingBoxDistance(const geometry_msgs::msg::Pose &from, const traffic_simulator_msgs::msg::BoundingBox &from_bounding_box, const geometry_msgs::msg::Pose &to, const traffic_simulator_msgs::msg::BoundingBox &to_bounding_box) -> std::optional< double >
Definition: distance.cpp:135
auto boundingBoxLaneLateralDistance(const CanonicalizedLaneletPose &from, const traffic_simulator_msgs::msg::BoundingBox &from_bounding_box, const CanonicalizedLaneletPose &to, const traffic_simulator_msgs::msg::BoundingBox &to_bounding_box, const RoutingConfiguration &routing_configuration) -> std::optional< double >
Definition: distance.cpp:144
auto distanceToStopLine(Ts &&... xs)
Definition: distance.hpp:117
auto distanceToStopLine(const lanelet::Ids &route_lanelets, const SplineInterface &route_spline) -> std::optional< double >
Definition: distance.cpp:67
geometry_msgs::msg::Pose Pose
Definition: lanelet_wrapper.hpp:66
traffic_simulator_msgs::msg::BoundingBox BoundingBox
Definition: lanelet_wrapper.hpp:62
Definition: api.hpp:32
Definition: junit5.hpp:25
Definition: routing_configuration.hpp:24