scenario_simulator_v2 C++ API
Functions
traffic_simulator::distance Namespace Reference

Functions

auto lateralDistance (const CanonicalizedLaneletPose &from, const CanonicalizedLaneletPose &to, const RoutingConfiguration &routing_configuration) -> std::optional< double >
 
auto lateralDistance (const CanonicalizedLaneletPose &from, const CanonicalizedLaneletPose &to, const double matching_distance, const RoutingConfiguration &routing_configuration) -> std::optional< double >
 
auto countLaneChanges (const CanonicalizedLaneletPose &from, const CanonicalizedLaneletPose &to, const traffic_simulator::RoutingConfiguration &routing_configuration, const std::shared_ptr< hdmap_utils::HdMapUtils > &hdmap_utils_ptr) -> std::optional< std::pair< int, int >>
 
auto longitudinalDistance (const CanonicalizedLaneletPose &from, const CanonicalizedLaneletPose &to, const bool include_adjacent_lanelet, const bool include_opposite_direction, const RoutingConfiguration &routing_configuration) -> std::optional< double >
 
auto boundingBoxDistance (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< double >
 
auto boundingBoxLaneLateralDistance (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) -> std::optional< double >
 
auto boundingBoxLaneLongitudinalDistance (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 bool include_adjacent_lanelet, const bool include_opposite_direction, const RoutingConfiguration &routing_configuration) -> std::optional< double >
 
auto boundingBoxLaneLongitudinalDistance (const std::optional< double > &longitudinal_distance, const traffic_simulator_msgs::msg::BoundingBox &from_bounding_box, const traffic_simulator_msgs::msg::BoundingBox &to_bounding_box) -> std::optional< double >
 
auto splineDistanceToBoundingBox (const math::geometry::CatmullRomSplineInterface &spline, const CanonicalizedLaneletPose &from_lanelet_pose, const traffic_simulator_msgs::msg::BoundingBox &from_bounding_box, const CanonicalizedLaneletPose &target_lanelet_pose, const traffic_simulator_msgs::msg::BoundingBox &target_bounding_box, const double lateral_collision_threshold=-1.0) -> std::optional< double >
 
auto distanceToLaneBound (const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::BoundingBox &bounding_box, const lanelet::Id lanelet_id) -> double
 
auto distanceToLaneBound (const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::BoundingBox &bounding_box, const lanelet::Ids &lanelet_ids) -> double
 
auto distanceToLeftLaneBound (const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::BoundingBox &bounding_box, const lanelet::Id lanelet_id) -> double
 
auto distanceToLeftLaneBound (const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::BoundingBox &bounding_box, const lanelet::Ids &lanelet_ids) -> double
 
auto distanceToRightLaneBound (const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::BoundingBox &bounding_box, const lanelet::Id lanelet_id) -> double
 
auto distanceToRightLaneBound (const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::BoundingBox &bounding_box, const lanelet::Ids &lanelet_ids) -> double
 
template<typename... Ts>
auto distanceToStopLine (Ts &&... xs)
 
template<typename... Ts>
auto distanceToTrafficLightStopLine (Ts &&... xs)
 
template<typename... Ts>
auto distanceToCrosswalk (Ts &&... xs)
 
auto distanceToYieldStop (const CanonicalizedLaneletPose &reference_pose, const lanelet::Ids &following_lanelets, const std::vector< CanonicalizedLaneletPose > &other_poses) -> std::optional< double >
 
auto distanceToSpline (const geometry_msgs::msg::Pose &map_pose, const traffic_simulator_msgs::msg::BoundingBox &bounding_box, const math::geometry::CatmullRomSplineInterface &spline, const double s_reference) -> double
 

Function Documentation

◆ boundingBoxDistance()

auto traffic_simulator::distance::boundingBoxDistance ( 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<double>

◆ boundingBoxLaneLateralDistance()

auto traffic_simulator::distance::boundingBoxLaneLateralDistance ( 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 
) -> std::optional<double>

◆ boundingBoxLaneLongitudinalDistance() [1/2]

auto traffic_simulator::distance::boundingBoxLaneLongitudinalDistance ( 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 bool  include_adjacent_lanelet,
const bool  include_opposite_direction,
const RoutingConfiguration routing_configuration 
) -> std::optional<double>

◆ boundingBoxLaneLongitudinalDistance() [2/2]

auto traffic_simulator::distance::boundingBoxLaneLongitudinalDistance ( const std::optional< double > &  longitudinal_distance,
const traffic_simulator_msgs::msg::BoundingBox &  from_bounding_box,
const traffic_simulator_msgs::msg::BoundingBox &  to_bounding_box 
) -> std::optional<double>

◆ countLaneChanges()

auto traffic_simulator::distance::countLaneChanges ( const CanonicalizedLaneletPose from,
const CanonicalizedLaneletPose to,
const traffic_simulator::RoutingConfiguration routing_configuration,
const std::shared_ptr< hdmap_utils::HdMapUtils > &  hdmap_utils_ptr 
) -> std::optional<std::pair<int, int>>

◆ distanceToCrosswalk()

template<typename... Ts>
auto traffic_simulator::distance::distanceToCrosswalk ( Ts &&...  xs)

◆ distanceToLaneBound() [1/2]

auto traffic_simulator::distance::distanceToLaneBound ( const geometry_msgs::msg::Pose &  map_pose,
const traffic_simulator_msgs::msg::BoundingBox &  bounding_box,
const lanelet::Id  lanelet_id 
) -> double

◆ distanceToLaneBound() [2/2]

auto traffic_simulator::distance::distanceToLaneBound ( const geometry_msgs::msg::Pose &  map_pose,
const traffic_simulator_msgs::msg::BoundingBox &  bounding_box,
const lanelet::Ids &  lanelet_ids 
) -> double

◆ distanceToLeftLaneBound() [1/2]

auto traffic_simulator::distance::distanceToLeftLaneBound ( const geometry_msgs::msg::Pose &  map_pose,
const traffic_simulator_msgs::msg::BoundingBox &  bounding_box,
const lanelet::Id  lanelet_id 
) -> double

◆ distanceToLeftLaneBound() [2/2]

auto traffic_simulator::distance::distanceToLeftLaneBound ( const geometry_msgs::msg::Pose &  map_pose,
const traffic_simulator_msgs::msg::BoundingBox &  bounding_box,
const lanelet::Ids &  lanelet_ids 
) -> double

◆ distanceToRightLaneBound() [1/2]

auto traffic_simulator::distance::distanceToRightLaneBound ( const geometry_msgs::msg::Pose &  map_pose,
const traffic_simulator_msgs::msg::BoundingBox &  bounding_box,
const lanelet::Id  lanelet_id 
) -> double

◆ distanceToRightLaneBound() [2/2]

auto traffic_simulator::distance::distanceToRightLaneBound ( const geometry_msgs::msg::Pose &  map_pose,
const traffic_simulator_msgs::msg::BoundingBox &  bounding_box,
const lanelet::Ids &  lanelet_ids 
) -> double

◆ distanceToSpline()

auto traffic_simulator::distance::distanceToSpline ( const geometry_msgs::msg::Pose &  map_pose,
const traffic_simulator_msgs::msg::BoundingBox &  bounding_box,
const math::geometry::CatmullRomSplineInterface spline,
const double  s_reference 
) -> double
Note
it may be a good idea to develop spline.getSquaredDistanceIn2D(point, s_start, s_end);
it may be a good idea to develop spline.getSquaredDistanceIn2D(point, s_start, s_end);

◆ distanceToStopLine()

template<typename... Ts>
auto traffic_simulator::distance::distanceToStopLine ( Ts &&...  xs)

◆ distanceToTrafficLightStopLine()

template<typename... Ts>
auto traffic_simulator::distance::distanceToTrafficLightStopLine ( Ts &&...  xs)

◆ distanceToYieldStop()

auto traffic_simulator::distance::distanceToYieldStop ( const CanonicalizedLaneletPose reference_pose,
const lanelet::Ids &  following_lanelets,
const std::vector< CanonicalizedLaneletPose > &  other_poses 
) -> std::optional<double>

◆ lateralDistance() [1/2]

auto traffic_simulator::distance::lateralDistance ( const CanonicalizedLaneletPose from,
const CanonicalizedLaneletPose to,
const double  matching_distance,
const RoutingConfiguration routing_configuration 
) -> std::optional<double>

◆ lateralDistance() [2/2]

auto traffic_simulator::distance::lateralDistance ( const CanonicalizedLaneletPose from,
const CanonicalizedLaneletPose to,
const RoutingConfiguration routing_configuration 
) -> std::optional<double>

◆ longitudinalDistance()

auto traffic_simulator::distance::longitudinalDistance ( const CanonicalizedLaneletPose from,
const CanonicalizedLaneletPose to,
bool const  include_adjacent_lanelet,
bool const  include_opposite_direction,
const RoutingConfiguration routing_configuration 
) -> std::optional< double >
See also
https://github.com/tier4/scenario_simulator_v2/blob/729e4e6372cdba60e377ae097d032905b80763a9/docs/developer_guide/lane_pose_calculation/GetLongitudinalDistance.md

A matching distance of about 1.5*lane widths is given as the matching distance to match the Entity present on the adjacent Lanelet. The length of the horizontal bar must intersect with the adjacent lanelet, so it is always 10m regardless of the entity type.

A matching distance of about 1.5*lane widths is given as the matching distance to match the Entity present on the adjacent Lanelet. The length of the horizontal bar must intersect with the adjacent lanelet, so it is always 10m regardless of the entity type.

◆ splineDistanceToBoundingBox()

auto traffic_simulator::distance::splineDistanceToBoundingBox ( const math::geometry::CatmullRomSplineInterface spline,
const CanonicalizedLaneletPose from_lanelet_pose,
const traffic_simulator_msgs::msg::BoundingBox &  from_bounding_box,
const CanonicalizedLaneletPose target_lanelet_pose,
const traffic_simulator_msgs::msg::BoundingBox &  target_bounding_box,
const double  lateral_collision_threshold = -1.0 
) -> std::optional<double>

boundingBoxLaneLongitudinalDistance requires routing_configuration, allow_lane_change = true is needed to check distances to entities on neighbour lanelets

Todo:
rotation of NPC is not taken into account, same as in boundingBoxLaneLongitudinalDistance this should be considered to be changed in separate task in the future
Note
if the distance of the target entity to the spline cannot be calculated because a collision occurs

boundingBoxLaneLongitudinalDistance requires routing_configuration, allow_lane_change = true is needed to check distances to entities on neighbour lanelets

Todo:
rotation of NPC is not taken into account, same as in boundingBoxLaneLongitudinalDistance this should be considered to be changed in separate task in the future
Note
if the distance of the target entity to the spline cannot be calculated because a collision occurs