15 #ifndef TRAFFIC_SIMULATOR__UTILS__POSE_HPP_
16 #define TRAFFIC_SIMULATOR__UTILS__POSE_HPP_
19 #include <traffic_simulator_msgs/msg/bounding_box.hpp>
42 -> std::optional<CanonicalizedLaneletPose>;
46 -> std::optional<CanonicalizedLaneletPose>;
51 const double matching_distance) -> std::optional<CanonicalizedLaneletPose>;
56 const lanelet::Ids & unique_route_lanelets,
const bool include_crosswalk,
57 const double matching_distance) -> std::optional<CanonicalizedLaneletPose>;
66 const double step_time) -> std::optional<geometry_msgs::msg::Point>;
70 -> std::optional<geometry_msgs::msg::Pose>;
73 -> std::optional<geometry_msgs::msg::Pose>;
76 -> std::optional<geometry_msgs::msg::Pose>;
83 -> std::optional<geometry_msgs::msg::Pose>;
93 const std::shared_ptr<hdmap_utils::HdMapUtils> & hdmap_utils_ptr) ->
LaneletPose;
101 const std::shared_ptr<hdmap_utils::HdMapUtils> & hdmap_utils_ptr) ->
LaneletPose;
106 const double tolerance,
const std::shared_ptr<hdmap_utils::HdMapUtils> & hdmap_utils_ptr) -> bool;
112 const std::shared_ptr<hdmap_utils::HdMapUtils> & hdmap_utils_ptr) -> bool;
117 -> std::optional<traffic_simulator::CanonicalizedLaneletPose>;
124 const lanelet::Ids & unique_route_lanelets,
const bool include_crosswalk,
125 const double matching_distance) -> std::optional<CanonicalizedLaneletPose>;
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
traffic_simulator_msgs::msg::LaneletPose LaneletPose
Definition: lanelet_pose.hpp:30
Definition: routing_configuration.hpp:24