scenario_simulator_v2 C++ API
pose.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__POSE_HPP_
16 #define TRAFFIC_SIMULATOR__UTILS__POSE_HPP_
17 
19 #include <traffic_simulator_msgs/msg/bounding_box.hpp>
20 
21 namespace traffic_simulator
22 {
23 inline namespace pose
24 {
26 
28 
29 // Conversions
30 auto canonicalize(const LaneletPose & lanelet_pose) -> LaneletPose;
31 
32 auto canonicalize(const LaneletPose & lanelet_pose, const lanelet::Ids & route_lanelets)
33  -> LaneletPose;
34 
35 auto toMapPose(const CanonicalizedLaneletPose & lanelet_pose) -> geometry_msgs::msg::Pose;
36 
37 auto toMapPose(const LaneletPose & lanelet_pose) -> geometry_msgs::msg::Pose;
38 
39 auto alternativeLaneletPoses(const LaneletPose & lanelet_pose) -> std::vector<LaneletPose>;
40 
41 auto toCanonicalizedLaneletPose(const LaneletPose & lanelet_pose)
42  -> std::optional<CanonicalizedLaneletPose>;
43 
45  const geometry_msgs::msg::Pose & map_pose, const bool include_crosswalk)
46  -> std::optional<CanonicalizedLaneletPose>;
47 
49  const geometry_msgs::msg::Pose & map_pose,
50  const traffic_simulator_msgs::msg::BoundingBox & bounding_box, const bool include_crosswalk,
51  const double matching_distance) -> std::optional<CanonicalizedLaneletPose>;
52 
54  const geometry_msgs::msg::Pose & map_pose,
55  const traffic_simulator_msgs::msg::BoundingBox & bounding_box,
56  const lanelet::Ids & unique_route_lanelets, const bool include_crosswalk,
57  const double matching_distance) -> std::optional<CanonicalizedLaneletPose>;
58 
60  const geometry_msgs::msg::Pose & global_pose, const geometry_msgs::msg::Pose & relative_pose)
62 
64  const CanonicalizedLaneletPose & canonicalized_lanelet_pose, const lanelet::Id next_lanelet_id,
65  const geometry_msgs::msg::Vector3 & desired_velocity, const bool desired_velocity_is_global,
66  const double step_time) -> std::optional<geometry_msgs::msg::Point>;
67 
68 // Relative msg::Pose
70  -> std::optional<geometry_msgs::msg::Pose>;
71 
73  -> std::optional<geometry_msgs::msg::Pose>;
74 
76  -> std::optional<geometry_msgs::msg::Pose>;
77 
79  const geometry_msgs::msg::Pose & from,
80  const traffic_simulator_msgs::msg::BoundingBox & from_bounding_box,
81  const geometry_msgs::msg::Pose & to,
82  const traffic_simulator_msgs::msg::BoundingBox & to_bounding_box)
83  -> std::optional<geometry_msgs::msg::Pose>;
84 
85 // Relative LaneletPose
87  const CanonicalizedLaneletPose & lanelet_pose,
88  const CanonicalizedLaneletPose & target_lanelet_pose) -> bool;
89 
91  const CanonicalizedLaneletPose & from, const CanonicalizedLaneletPose & to,
92  const RoutingConfiguration & routing_configuration,
93  const std::shared_ptr<hdmap_utils::HdMapUtils> & hdmap_utils_ptr) -> LaneletPose;
94 
96  const CanonicalizedLaneletPose & from,
97  const traffic_simulator_msgs::msg::BoundingBox & from_bounding_box,
98  const CanonicalizedLaneletPose & to,
99  const traffic_simulator_msgs::msg::BoundingBox & to_bounding_box,
100  const RoutingConfiguration & routing_configuration,
101  const std::shared_ptr<hdmap_utils::HdMapUtils> & hdmap_utils_ptr) -> LaneletPose;
102 
103 // Others
104 auto isInLanelet(
105  const CanonicalizedLaneletPose & canonicalized_lanelet_pose, const lanelet::Id lanelet_id,
106  const double tolerance, const std::shared_ptr<hdmap_utils::HdMapUtils> & hdmap_utils_ptr) -> bool;
107 
108 auto isInLanelet(const geometry_msgs::msg::Point & point, const lanelet::Id lanelet_id) -> bool;
109 
110 auto isAtEndOfLanelets(
111  const CanonicalizedLaneletPose & canonicalized_lanelet_pose,
112  const std::shared_ptr<hdmap_utils::HdMapUtils> & hdmap_utils_ptr) -> bool;
113 
115  const lanelet::Id from_lanelet_id, const CanonicalizedLaneletPose & canonicalized_lanelet_pose,
116  const traffic_simulator_msgs::msg::BoundingBox & to_bounding_box)
117  -> std::optional<traffic_simulator::CanonicalizedLaneletPose>;
118 
119 namespace pedestrian
120 {
122  const geometry_msgs::msg::Pose & map_pose,
123  const traffic_simulator_msgs::msg::BoundingBox & bounding_box,
124  const lanelet::Ids & unique_route_lanelets, const bool include_crosswalk,
125  const double matching_distance) -> std::optional<CanonicalizedLaneletPose>;
126 } // namespace pedestrian
127 } // namespace pose
128 } // namespace traffic_simulator
129 #endif // TRAFFIC_SIMULATOR__UTILS__POSE_HPP_
Definition: lanelet_pose.hpp:35
geometry_msgs::msg::Pose Pose
Definition: lanelet_wrapper.hpp:65
traffic_simulator_msgs::msg::BoundingBox BoundingBox
Definition: lanelet_wrapper.hpp:61
geometry_msgs::msg::Point Point
Definition: lanelet_wrapper.hpp:64
geometry_msgs::msg::Vector3 Vector3
Definition: lanelet_wrapper.hpp:68
auto transformToCanonicalizedLaneletPose(const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::BoundingBox &bounding_box, const lanelet::Ids &unique_route_lanelets, const bool include_crosswalk, const double matching_distance) -> std::optional< CanonicalizedLaneletPose >
Definition: pose.cpp:450
auto findRoutableAlternativeLaneletPoseFrom(const lanelet::Id from_lanelet_id, const CanonicalizedLaneletPose &canonicalized_lanelet_pose, const traffic_simulator_msgs::msg::BoundingBox &to_bounding_box) -> std::optional< traffic_simulator::CanonicalizedLaneletPose >
Definition: pose.cpp:388
auto quietNaNPose() -> geometry_msgs::msg::Pose
Definition: pose.cpp:34
auto quietNaNLaneletPose() -> LaneletPose
Definition: pose.cpp:44
auto canonicalize(const LaneletPose &lanelet_pose) -> LaneletPose
Definition: pose.cpp:57
auto relativeLaneletPose(const CanonicalizedLaneletPose &from, const CanonicalizedLaneletPose &to, const RoutingConfiguration &routing_configuration, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> LaneletPose
Definition: pose.cpp:285
auto boundingBoxRelativePose(const geometry_msgs::msg::Pose &from, const traffic_simulator_msgs::msg::BoundingBox &from_bounding_box, const geometry_msgs::msg::Pose &to, const traffic_simulator_msgs::msg::BoundingBox &to_bounding_box) -> std::optional< geometry_msgs::msg::Pose >
Definition: pose.cpp:263
auto relativePose(const geometry_msgs::msg::Pose &from, const geometry_msgs::msg::Pose &to) -> std::optional< geometry_msgs::msg::Pose >
Definition: pose.cpp:241
auto boundingBoxRelativeLaneletPose(const CanonicalizedLaneletPose &from, const traffic_simulator_msgs::msg::BoundingBox &from_bounding_box, const CanonicalizedLaneletPose &to, const traffic_simulator_msgs::msg::BoundingBox &to_bounding_box, const RoutingConfiguration &routing_configuration, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> LaneletPose
Definition: pose.cpp:311
auto updatePositionForLaneletTransition(const CanonicalizedLaneletPose &canonicalized_lanelet_pose, const lanelet::Id next_lanelet_id, const geometry_msgs::msg::Vector3 &desired_velocity, const bool desired_velocity_is_global, const double step_time) -> std::optional< geometry_msgs::msg::Point >
Definition: pose.cpp:182
auto isAltitudeMatching(const CanonicalizedLaneletPose &lanelet_pose, const CanonicalizedLaneletPose &target_lanelet_pose) -> bool
Definition: pose.cpp:233
auto isAtEndOfLanelets(const CanonicalizedLaneletPose &canonicalized_lanelet_pose, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> bool
Definition: pose.cpp:379
auto transformRelativePoseToGlobal(const geometry_msgs::msg::Pose &global_pose, const geometry_msgs::msg::Pose &relative_pose) -> geometry_msgs::msg::Pose
Definition: pose.cpp:169
auto isInLanelet(const CanonicalizedLaneletPose &canonicalized_lanelet_pose, const lanelet::Id lanelet_id, const double tolerance, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> bool
Definition: pose.cpp:340
auto toCanonicalizedLaneletPose(const LaneletPose &lanelet_pose) -> std::optional< CanonicalizedLaneletPose >
Definition: pose.cpp:104
auto toMapPose(const CanonicalizedLaneletPose &lanelet_pose) -> geometry_msgs::msg::Pose
Definition: pose.cpp:87
auto alternativeLaneletPoses(const LaneletPose &lanelet_pose) -> std::vector< LaneletPose >
Definition: pose.cpp:99
Definition: api.hpp:48
traffic_simulator_msgs::msg::LaneletPose LaneletPose
Definition: lanelet_pose.hpp:30
Definition: routing_configuration.hpp:24