15 #ifndef TRAFFIC_SIMULATOR__DATA_TYPE__LANELET_POSE_HPP_
16 #define TRAFFIC_SIMULATOR__DATA_TYPE__LANELET_POSE_HPP_
18 #include <lanelet2_core/geometry/Lanelet.h>
20 #include <geometry_msgs/msg/pose.hpp>
26 #include <traffic_simulator_msgs/msg/lanelet_pose.hpp>
32 inline namespace lanelet_pose
39 const LaneletPose & non_canonicalized_lanelet_pose,
const lanelet::Ids & route_lanelets);
67 #define DEFINE_COMPARISON_OPERATOR(OPERATOR) \
68 bool operator OPERATOR(const CanonicalizedLaneletPose & rhs) const \
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) { \
82 #undef DEFINE_COMPARISON_OPERATOR
85 auto adjustOrientationAndOzPosition() -> void;
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
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