scenario_simulator_v2 C++ API
lanelet_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__DATA_TYPE__LANELET_POSE_HPP_
16 #define TRAFFIC_SIMULATOR__DATA_TYPE__LANELET_POSE_HPP_
17 
18 #include <lanelet2_core/geometry/Lanelet.h>
19 
20 #include <geometry_msgs/msg/pose.hpp>
21 #include <optional>
26 #include <traffic_simulator_msgs/msg/lanelet_pose.hpp>
27 
28 namespace traffic_simulator
29 {
31 
32 inline namespace lanelet_pose
33 {
35 {
36 public:
37  explicit CanonicalizedLaneletPose(const LaneletPose & non_canonicalized_lanelet_pose);
38  explicit CanonicalizedLaneletPose(
39  const LaneletPose & non_canonicalized_lanelet_pose, const lanelet::Ids & route_lanelets);
43  explicit operator LaneletPose() const noexcept { return lanelet_pose_; }
44  explicit operator geometry_msgs::msg::Pose() const noexcept { return map_pose_; }
45 
46  auto getLaneletPose() const -> const LaneletPose & { return lanelet_pose_; }
47  auto getAltitude() const -> double { return map_pose_.position.z; }
48  auto getLaneletId() const noexcept -> lanelet::Id { return lanelet_pose_.lanelet_id; }
49  auto alignOrientationToLanelet() -> void;
50  auto hasAlternativeLaneletPose() const -> bool { return lanelet_poses_.size() > 1; }
52  LaneletPose from,
53  const RoutingConfiguration & routing_configuration = RoutingConfiguration()) const
54  -> std::optional<LaneletPose>;
55 
56  static auto setConsiderPoseByRoadSlope(bool consider_pose_by_road_slope) -> void
57  {
58  consider_pose_by_road_slope_ = consider_pose_by_road_slope;
59  }
60  static auto getConsiderPoseByRoadSlope() -> bool { return consider_pose_by_road_slope_; }
61 
67 #define DEFINE_COMPARISON_OPERATOR(OPERATOR) \
68  bool operator OPERATOR(const CanonicalizedLaneletPose & rhs) const \
69  { \
70  if ( \
71  static_cast<LaneletPose>(*this).lanelet_id == static_cast<LaneletPose>(rhs).lanelet_id && \
72  static_cast<LaneletPose>(*this).s OPERATOR static_cast<LaneletPose>(rhs).s) { \
73  return true; \
74  } \
75  return false; \
76  }
77 
82 #undef DEFINE_COMPARISON_OPERATOR
83 
84 private:
85  auto adjustOrientationAndOzPosition() -> void;
87  std::vector<LaneletPose> lanelet_poses_;
89  inline static bool consider_pose_by_road_slope_{false};
90 };
91 } // namespace lanelet_pose
92 
94 auto isSameLaneletId(const CanonicalizedLaneletPose &, const lanelet::Id lanelet_id) -> bool;
95 } // namespace traffic_simulator
96 
97 #endif // TRAFFIC_SIMULATOR__DATA_TYPE__LANELET_POSE_HPP_
Definition: lanelet_pose.hpp:35
LaneletPose lanelet_pose_
Definition: lanelet_pose.hpp:86
static bool consider_pose_by_road_slope_
Definition: lanelet_pose.hpp:89
auto hasAlternativeLaneletPose() const -> bool
Definition: lanelet_pose.hpp:50
static auto setConsiderPoseByRoadSlope(bool consider_pose_by_road_slope) -> void
Definition: lanelet_pose.hpp:56
auto getAlternativeLaneletPoseBaseOnShortestRouteFrom(LaneletPose from, const RoutingConfiguration &routing_configuration=RoutingConfiguration()) const -> std::optional< LaneletPose >
Definition: lanelet_pose.cpp:70
auto getLaneletId() const noexcept -> lanelet::Id
Definition: lanelet_pose.hpp:48
auto alignOrientationToLanelet() -> void
Definition: lanelet_pose.cpp:90
std::vector< LaneletPose > lanelet_poses_
Definition: lanelet_pose.hpp:87
geometry_msgs::msg::Pose map_pose_
Definition: lanelet_pose.hpp:88
auto getAltitude() const -> double
Definition: lanelet_pose.hpp:47
CanonicalizedLaneletPose & operator=(const CanonicalizedLaneletPose &obj)
Definition: lanelet_pose.cpp:61
DEFINE_COMPARISON_OPERATOR(<=) DEFINE_COMPARISON_OPERATOR(<) DEFINE_COMPARISON_OPERATOR(>
CanonicalizedLaneletPose(const LaneletPose &non_canonicalized_lanelet_pose)
Definition: lanelet_pose.cpp:29
auto getLaneletPose() const -> const LaneletPose &
Definition: lanelet_pose.hpp:46
static auto getConsiderPoseByRoadSlope() -> bool
Definition: lanelet_pose.hpp:60
Definition: lanelet_wrapper.hpp:39
geometry_msgs::msg::Pose Pose
Definition: lanelet_wrapper.hpp:65
Definition: api.hpp:48
traffic_simulator_msgs::msg::LaneletPose LaneletPose
Definition: lanelet_pose.hpp:30
auto isSameLaneletId(const CanonicalizedEntityStatus &first_status, const CanonicalizedEntityStatus &second_status) -> bool
Definition: entity_status.cpp:198
Definition: routing_configuration.hpp:24