|
scenario_simulator_v2 C++ API
|
Functions | |
| auto | toMapPose (const LaneletPose &lanelet_pose, const bool fill_pitch=true) -> PoseStamped |
| auto | isAltitudeWithinThreshold (const double current_altitude, const double target_altitude) -> bool |
| auto | isAltitudeWithinRange (const double current_altitude, const double min_altitude, const double max_altitude) -> bool |
| auto | toLaneletPose (const Pose &map_pose, const lanelet::Id lanelet_id, const double matching_distance=1.0) -> std::optional< LaneletPose > |
| auto | toLaneletPose (const Pose &map_pose, const lanelet::Ids &lanelet_ids, const double matching_distance=1.0) -> std::optional< LaneletPose > |
| auto | toLaneletPose (const Pose &map_pose, const bool include_crosswalk, const double matching_distance=1.0) -> std::optional< LaneletPose > |
| auto | toLaneletPose (const Pose &map_pose, const BoundingBox &bounding_box, const bool include_crosswalk, const double matching_distance=1.0, const RoutingGraphType type=RoutingConfiguration().routing_graph_type) -> std::optional< LaneletPose > |
| auto | toLaneletPoses (const Pose &map_pose, const lanelet::Id lanelet_id, const double matching_distance=5.0, const bool include_opposite_direction=true, const RoutingGraphType type=RoutingConfiguration().routing_graph_type) -> std::vector< LaneletPose > |
| auto | alternativeLaneletPoses (const LaneletPose &reference_lanelet_pose) -> std::vector< LaneletPose > |
| Retrieves alternative lanelet poses based on the reference lanelet pose. More... | |
| auto | alongLaneletPose (const LaneletPose &from_pose, const lanelet::Ids &route_lanelets, const double distance) -> LaneletPose |
| auto | alongLaneletPose (const LaneletPose &from_pose, const double distance, const RoutingGraphType type=RoutingConfiguration().routing_graph_type) -> LaneletPose |
| auto | canonicalizeLaneletPose (const LaneletPose &lanelet_pose) -> std::tuple< std::optional< LaneletPose >, std::optional< lanelet::Id >> |
| Canonicalizes a given LaneletPose by adjusting the longitudinal position (s) to ensure it lies within the bounds of the specified lanelet. If the position is out of bounds, it traverses to previous or next lanelets to find the canonicalized position. More... | |
| auto | canonicalizeLaneletPose (const LaneletPose &lanelet_pose, const lanelet::Ids &route_lanelets) -> std::tuple< std::optional< LaneletPose >, std::optional< lanelet::Id >> |
| auto | findMatchingLanes (const geometry_msgs::msg::Pose &, const traffic_simulator_msgs::msg::BoundingBox &, const bool include_crosswalk, const double matching_distance=1.0, const double reduction_ratio=DEFAULT_MATCH_TO_LANE_REDUCTION_RATIO, const traffic_simulator::RoutingGraphType type=traffic_simulator::RoutingConfiguration().routing_graph_type) -> std::optional< std::set< std::pair< double, lanelet::Id >>> |
| auto | matchToLane (const Pose &map_pose, const BoundingBox &bounding_box, const bool include_crosswalk, const double matching_distance=1.0, const double reduction_ratio=DEFAULT_MATCH_TO_LANE_REDUCTION_RATIO, const RoutingGraphType type=RoutingConfiguration().routing_graph_type) -> std::optional< lanelet::Id > |
| auto | leftLaneletIds (const lanelet::Id lanelet_id, const RoutingGraphType type, const bool include_opposite_direction) -> lanelet::Ids |
| auto | rightLaneletIds (const lanelet::Id lanelet_id, const RoutingGraphType type, const bool include_opposite_direction) -> lanelet::Ids |
| auto traffic_simulator::lanelet_wrapper::pose::alongLaneletPose | ( | const LaneletPose & | from_pose, |
| const double | distance, | ||
| const RoutingGraphType | type = RoutingConfiguration().routing_graph_type |
||
| ) | -> LaneletPose |
| auto traffic_simulator::lanelet_wrapper::pose::alongLaneletPose | ( | const LaneletPose & | from_pose, |
| const lanelet::Ids & | route_lanelets, | ||
| const double | distance | ||
| ) | -> LaneletPose |
| auto traffic_simulator::lanelet_wrapper::pose::alternativeLaneletPoses | ( | const LaneletPose & | reference_lanelet_pose | ) | -> std::vector<LaneletPose> |
Retrieves alternative lanelet poses based on the reference lanelet pose.
This method computes alternative lanelet poses in the previous and next lanelets relative to a given reference lanelet pose. It recursively explores the neighboring lanelets until no further alternatives are found. The decision of whether a pose belongs to a previous or next lanelet is based on the s value of the reference pose:
s is negative, the pose is assumed to be on the previous lanelet.s exceeds the lanelet length, the pose is assumed to be on the next lanelet.s is within the valid range of the lanelet (from 0 to the lanelet's length), the reference lanelet pose is returned directly.| reference_lanelet_pose | The reference pose on a lanelet, used to determine its position and compute alternatives in neighboring lanelets. |
LaneletPose objects representing poses in the neighboring lanelets, or the reference pose if no alternatives are found. | auto traffic_simulator::lanelet_wrapper::pose::canonicalizeLaneletPose | ( | const LaneletPose & | lanelet_pose | ) | -> std::tuple< std::optional< LaneletPose >, std::optional< lanelet::Id >> |
Canonicalizes a given LaneletPose by adjusting the longitudinal position (s) to ensure it lies within the bounds of the specified lanelet. If the position is out of bounds, it traverses to previous or next lanelets to find the canonicalized position.
If the provided pose has a longitudinal position (s) less than 0, the function traverses to previous lanelets until a valid position is found or no previous lanelets exist.
If the longitudinal position (s) exceeds the length of the current lanelet, the function traverses to next lanelets until the position is valid or no next lanelets exist.
| lanelet_pose | The input LaneletPose to canonicalize, containing a lanelet ID and longitudinal position (s). |
| auto traffic_simulator::lanelet_wrapper::pose::canonicalizeLaneletPose | ( | const LaneletPose & | lanelet_pose, |
| const lanelet::Ids & | route_lanelets | ||
| ) | -> std::tuple<std::optional<LaneletPose>, std::optional<lanelet::Id>> |
| auto traffic_simulator::lanelet_wrapper::pose::findMatchingLanes | ( | const geometry_msgs::msg::Pose & | map_pose, |
| const traffic_simulator_msgs::msg::BoundingBox & | bounding_box, | ||
| const bool | include_crosswalk, | ||
| const double | matching_distance = 1.0, |
||
| const double | reduction_ratio = DEFAULT_MATCH_TO_LANE_REDUCTION_RATIO, |
||
| const traffic_simulator::RoutingGraphType | type = traffic_simulator::RoutingConfiguration().routing_graph_type |
||
| ) | -> std::optional<std::set<std::pair<double, lanelet::Id>>> |
| auto traffic_simulator::lanelet_wrapper::pose::isAltitudeWithinRange | ( | const double | current_altitude, |
| const double | min_altitude, | ||
| const double | max_altitude | ||
| ) | -> bool |
| auto traffic_simulator::lanelet_wrapper::pose::isAltitudeWithinThreshold | ( | const double | current_altitude, |
| const double | target_altitude | ||
| ) | -> bool |
| auto traffic_simulator::lanelet_wrapper::pose::leftLaneletIds | ( | const lanelet::Id | lanelet_id, |
| const RoutingGraphType | type, | ||
| const bool | include_opposite_direction | ||
| ) | -> lanelet::Ids |
| auto traffic_simulator::lanelet_wrapper::pose::matchToLane | ( | const Pose & | map_pose, |
| const BoundingBox & | bounding_box, | ||
| const bool | include_crosswalk, | ||
| const double | matching_distance = 1.0, |
||
| const double | reduction_ratio = DEFAULT_MATCH_TO_LANE_REDUCTION_RATIO, |
||
| const RoutingGraphType | type = RoutingConfiguration().routing_graph_type |
||
| ) | -> std::optional<lanelet::Id> |
| auto traffic_simulator::lanelet_wrapper::pose::rightLaneletIds | ( | const lanelet::Id | lanelet_id, |
| const RoutingGraphType | type, | ||
| const bool | include_opposite_direction | ||
| ) | -> lanelet::Ids |
| auto traffic_simulator::lanelet_wrapper::pose::toLaneletPose | ( | const Pose & | map_pose, |
| const bool | include_crosswalk, | ||
| const double | matching_distance = 1.0 |
||
| ) | -> std::optional<LaneletPose> |
| auto traffic_simulator::lanelet_wrapper::pose::toLaneletPose | ( | const Pose & | map_pose, |
| const BoundingBox & | bounding_box, | ||
| const bool | include_crosswalk, | ||
| const double | matching_distance = 1.0, |
||
| const RoutingGraphType | type = RoutingConfiguration().routing_graph_type |
||
| ) | -> std::optional<LaneletPose> |
| auto traffic_simulator::lanelet_wrapper::pose::toLaneletPose | ( | const Pose & | map_pose, |
| const lanelet::Id | lanelet_id, | ||
| const double | matching_distance = 1.0 |
||
| ) | -> std::optional<LaneletPose> |
| auto traffic_simulator::lanelet_wrapper::pose::toLaneletPose | ( | const Pose & | map_pose, |
| const lanelet::Ids & | lanelet_ids, | ||
| const double | matching_distance = 1.0 |
||
| ) | -> std::optional<LaneletPose> |
| auto traffic_simulator::lanelet_wrapper::pose::toLaneletPoses | ( | const Pose & | map_pose, |
| const lanelet::Id | lanelet_id, | ||
| const double | matching_distance = 5.0, |
||
| const bool | include_opposite_direction = true, |
||
| const RoutingGraphType | type = RoutingConfiguration().routing_graph_type |
||
| ) | -> std::vector<LaneletPose> |
| auto traffic_simulator::lanelet_wrapper::pose::toMapPose | ( | const LaneletPose & | lanelet_pose, |
| const bool | fill_pitch = true |
||
| ) | -> PoseStamped |