15 #ifndef TRAFFIC_SIMULATOR__DATA_TYPE__LANELET_POSE_HPP_
16 #define TRAFFIC_SIMULATOR__DATA_TYPE__LANELET_POSE_HPP_
24 inline namespace lanelet_pose
30 const LaneletPose & maybe_non_canonicalized_lanelet_pose,
31 const std::shared_ptr<hdmap_utils::HdMapUtils> &
hdmap_utils);
33 const LaneletPose & maybe_non_canonicalized_lanelet_pose,
const lanelet::Ids & route_lanelets,
34 const std::shared_ptr<hdmap_utils::HdMapUtils> &
hdmap_utils);
39 explicit operator geometry_msgs::msg::Pose() const noexcept {
return map_pose_; }
57 #define DEFINE_COMPARISON_OPERATOR(OPERATOR) \
58 bool operator OPERATOR(const CanonicalizedLaneletPose & rhs) const \
61 static_cast<LaneletPose>(*this).lanelet_id == static_cast<LaneletPose>(rhs).lanelet_id && \
62 static_cast<LaneletPose>(*this).s OPERATOR static_cast<LaneletPose>(rhs).s) { \
72 #undef DEFINE_COMPARISON_OPERATOR
75 auto adjustOrientationAndOzPosition(
const std::shared_ptr<hdmap_utils::HdMapUtils> &
hdmap_utils)
78 const LaneletPose & may_non_canonicalized_lanelet_pose,
81 const LaneletPose & may_non_canonicalized_lanelet_pose,
const lanelet::Ids & route_lanelets,
Definition: lanelet_pose.hpp:27
LaneletPose lanelet_pose_
Definition: lanelet_pose.hpp:83
static bool consider_pose_by_road_slope_
Definition: lanelet_pose.hpp:86
CanonicalizedLaneletPose(const LaneletPose &maybe_non_canonicalized_lanelet_pose, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils)
Definition: lanelet_pose.cpp:27
auto getAlternativeLaneletPoseBaseOnShortestRouteFrom(LaneletPose from, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils, const traffic_simulator::RoutingConfiguration &routing_configuration=traffic_simulator::RoutingConfiguration()) const -> std::optional< LaneletPose >
Definition: lanelet_pose.cpp:112
auto hasAlternativeLaneletPose() const -> bool
Definition: lanelet_pose.hpp:41
static auto setConsiderPoseByRoadSlope(bool consider_pose_by_road_slope) -> void
Definition: lanelet_pose.hpp:46
auto canonicalize(const LaneletPose &may_non_canonicalized_lanelet_pose, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils) -> LaneletPose
Definition: lanelet_pose.cpp:72
std::vector< LaneletPose > lanelet_poses_
Definition: lanelet_pose.hpp:84
geometry_msgs::msg::Pose map_pose_
Definition: lanelet_pose.hpp:85
CanonicalizedLaneletPose & operator=(const CanonicalizedLaneletPose &obj)
Definition: lanelet_pose.cpp:63
DEFINE_COMPARISON_OPERATOR(<=) DEFINE_COMPARISON_OPERATOR(<) DEFINE_COMPARISON_OPERATOR(>
auto getLaneletPose() const -> const LaneletPose &
Definition: lanelet_pose.hpp:40
static auto getConsiderPoseByRoadSlope() -> bool
Definition: lanelet_pose.hpp:50
traffic_simulator_msgs::msg::LaneletPose LaneletPose
Definition: lanelet_pose.hpp:22
auto isSameLaneletId(const CanonicalizedEntityStatus &first_status, const CanonicalizedEntityStatus &second_status) -> bool
Definition: entity_status.cpp:200
Definition: routing_configuration.hpp:24