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 
20 
21 namespace traffic_simulator
22 {
24 
25 inline namespace lanelet_pose
26 {
28 {
29 public:
30  explicit CanonicalizedLaneletPose(const LaneletPose & non_canonicalized_lanelet_pose);
31  explicit CanonicalizedLaneletPose(
32  const LaneletPose & non_canonicalized_lanelet_pose, const lanelet::Ids & route_lanelets);
36  explicit operator LaneletPose() const noexcept { return lanelet_pose_; }
37  explicit operator geometry_msgs::msg::Pose() const noexcept { return map_pose_; }
38 
39  auto getLaneletPose() const -> const LaneletPose & { return lanelet_pose_; }
40  auto getAltitude() const -> double { return map_pose_.position.z; }
41  auto getLaneletId() const noexcept -> lanelet::Id { return lanelet_pose_.lanelet_id; }
42  auto alignOrientationToLanelet() -> void;
43  auto hasAlternativeLaneletPose() const -> bool { return lanelet_poses_.size() > 1; }
45  LaneletPose from,
46  const RoutingConfiguration & routing_configuration = RoutingConfiguration()) const
47  -> std::optional<LaneletPose>;
48 
49  static auto setConsiderPoseByRoadSlope(bool consider_pose_by_road_slope) -> void
50  {
51  consider_pose_by_road_slope_ = consider_pose_by_road_slope;
52  }
53  static auto getConsiderPoseByRoadSlope() -> bool { return consider_pose_by_road_slope_; }
54 
60 #define DEFINE_COMPARISON_OPERATOR(OPERATOR) \
61  bool operator OPERATOR(const CanonicalizedLaneletPose & rhs) const \
62  { \
63  if ( \
64  static_cast<LaneletPose>(*this).lanelet_id == static_cast<LaneletPose>(rhs).lanelet_id && \
65  static_cast<LaneletPose>(*this).s OPERATOR static_cast<LaneletPose>(rhs).s) { \
66  return true; \
67  } \
68  return false; \
69  }
70 
75 #undef DEFINE_COMPARISON_OPERATOR
76 
77  friend std::ostream & operator<<(std::ostream & os, const CanonicalizedLaneletPose & obj)
78  {
79  os << "CanonicalizedLaneletPose(\n";
80  os << obj.lanelet_pose_ << "\n";
81  if (obj.lanelet_poses_.size() == 1) {
82  os << " alternative from lanelet_poses_: " << obj.lanelet_poses_.front() << "\n";
83  } else if (obj.lanelet_poses_.size() > 1) {
84  os << " lanelet_poses_: [\n";
85  for (const auto & pose : obj.lanelet_poses_) {
86  os << " - " << pose << "\n";
87  }
88  os << " ]\n";
89  }
90  os << " map_pose_: " << obj.map_pose_ << "\n";
91  os << " consider_pose_by_road_slope_: "
92  << (CanonicalizedLaneletPose::consider_pose_by_road_slope_ ? "true" : "false") << "\n";
93  os << ")";
94  return os;
95  }
96 
97 private:
98  auto adjustOrientationAndOzPosition() -> void;
100  std::vector<LaneletPose> lanelet_poses_;
102  inline static bool consider_pose_by_road_slope_{false};
103 };
104 } // namespace lanelet_pose
105 
107 auto isSameLaneletId(const CanonicalizedLaneletPose &, const lanelet::Id lanelet_id) -> bool;
108 } // namespace traffic_simulator
109 
110 #endif // TRAFFIC_SIMULATOR__DATA_TYPE__LANELET_POSE_HPP_
Definition: lanelet_pose.hpp:28
LaneletPose lanelet_pose_
Definition: lanelet_pose.hpp:99
static bool consider_pose_by_road_slope_
Definition: lanelet_pose.hpp:102
auto hasAlternativeLaneletPose() const -> bool
Definition: lanelet_pose.hpp:43
static auto setConsiderPoseByRoadSlope(bool consider_pose_by_road_slope) -> void
Definition: lanelet_pose.hpp:49
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:41
auto alignOrientationToLanelet() -> void
Definition: lanelet_pose.cpp:90
std::vector< LaneletPose > lanelet_poses_
Definition: lanelet_pose.hpp:100
geometry_msgs::msg::Pose map_pose_
Definition: lanelet_pose.hpp:101
auto getAltitude() const -> double
Definition: lanelet_pose.hpp:40
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:39
static auto getConsiderPoseByRoadSlope() -> bool
Definition: lanelet_pose.hpp:53
Definition: lanelet_wrapper.hpp:40
geometry_msgs::msg::Pose Pose
Definition: lanelet_wrapper.hpp:66
Definition: api.hpp:32
traffic_simulator_msgs::msg::LaneletPose LaneletPose
Definition: lanelet_pose.hpp:23
auto isSameLaneletId(const CanonicalizedEntityStatus &first_status, const CanonicalizedEntityStatus &second_status) -> bool
Definition: entity_status.cpp:198
std::ostream & operator<<(std::ostream &os, const geometry_msgs::msg::Point &point)
Definition: ostream_helpers.cpp:20
Definition: routing_configuration.hpp:24