scenario_simulator_v2 C++ API
Functions
traffic_simulator::pose::pedestrian Namespace Reference

Functions

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, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> std::optional< CanonicalizedLaneletPose >
 

Function Documentation

◆ transformToCanonicalizedLaneletPose()

auto traffic_simulator::pose::pedestrian::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,
const std::shared_ptr< hdmap_utils::HdMapUtils > &  hdmap_utils_ptr 
) -> std::optional<CanonicalizedLaneletPose>
Note
Hard coded parameter. 2.0 is a matching threshold for lanelet. In this branch, the algorithm only consider entity pose.
If canonicalize failed, set end of road lanelet pose.
Hard coded parameter. 2.0 is a matching threshold for lanelet. In this branch, the algorithm only consider entity pose.
If canonicalize failed, set end of road lanelet pose.