scenario_simulator_v2 C++ API
Classes | Public Member Functions | List of all members
hdmap_utils::HdMapUtils Class Reference

#include <hdmap_utils.hpp>

Public Member Functions

 HdMapUtils (const boost::filesystem::path &, const geographic_msgs::msg::GeoPoint &)
 
auto canChangeLane (const lanelet::Id from, const lanelet::Id to, const traffic_simulator::RoutingGraphType type=traffic_simulator::RoutingConfiguration().routing_graph_type) const -> bool
 
auto clipTrajectoryFromLaneletIds (const lanelet::Id, const double s, const lanelet::Ids &, const double forward_distance=20) const -> std::vector< geometry_msgs::msg::Point >
 
auto countLaneChanges (const traffic_simulator_msgs::msg::LaneletPose &from, const traffic_simulator_msgs::msg::LaneletPose &to, const traffic_simulator::RoutingConfiguration &routing_configuration=traffic_simulator::RoutingConfiguration()) const -> std::optional< std::pair< int, int >>
 
auto filterLaneletIds (const lanelet::Ids &, const char subtype[]) const -> lanelet::Ids
 
auto generateMarker () const -> visualization_msgs::msg::MarkerArray
 
auto getCenterPoints (const lanelet::Ids &) const -> std::vector< geometry_msgs::msg::Point >
 
auto getCenterPoints (const lanelet::Id) const -> std::vector< geometry_msgs::msg::Point >
 
auto getCenterPointsSpline (const lanelet::Id) const -> std::shared_ptr< math::geometry::CatmullRomSpline >
 
auto getClosestLaneletId (const geometry_msgs::msg::Pose &, const double distance_thresh=30.0, const bool include_crosswalk=false) const -> std::optional< lanelet::Id >
 
auto getCollisionPointInLaneCoordinate (const lanelet::Id lanelet_id, const lanelet::Id crossing_lanelet_id) const -> std::optional< double >
 
auto getConflictingCrosswalkIds (const lanelet::Ids &) const -> lanelet::Ids
 
auto getConflictingLaneIds (const lanelet::Ids &, const traffic_simulator::RoutingGraphType type=traffic_simulator::RoutingConfiguration().routing_graph_type) const -> lanelet::Ids
 
auto getDistanceToStopLine (const lanelet::Ids &route_lanelets, const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
 
auto getDistanceToStopLine (const lanelet::Ids &route_lanelets, const std::vector< geometry_msgs::msg::Point > &waypoints) const -> std::optional< double >
 
auto getDistanceToTrafficLightStopLine (const lanelet::Ids &route_lanelets, const math::geometry::CatmullRomSplineInterface &spline) const -> std::optional< double >
 
auto getDistanceToTrafficLightStopLine (const lanelet::Ids &route_lanelets, const std::vector< geometry_msgs::msg::Point > &waypoints) const -> std::optional< double >
 
auto getDistanceToTrafficLightStopLine (const math::geometry::CatmullRomSplineInterface &spline, const lanelet::Id traffic_light_id) const -> std::optional< double >
 
auto getDistanceToTrafficLightStopLine (const std::vector< geometry_msgs::msg::Point > &waypoints, const lanelet::Id traffic_light_id) const -> std::optional< double >
 
auto getFollowingLanelets (const lanelet::Id current_lanelet_id, const lanelet::Ids &route, const double horizon=100, const bool include_current_lanelet_id=true, const traffic_simulator::RoutingGraphType type=traffic_simulator::RoutingConfiguration().routing_graph_type) const -> lanelet::Ids
 
auto getFollowingLanelets (const lanelet::Id, const double distance=100, const bool include_self=true, const traffic_simulator::RoutingGraphType type=traffic_simulator::RoutingConfiguration().routing_graph_type) const -> lanelet::Ids
 
auto getAltitude (const traffic_simulator_msgs::msg::LaneletPose &) const -> double
 
auto getLaneChangeTrajectory (const geometry_msgs::msg::Pose &from, const traffic_simulator::lane_change::Parameter &lane_change_parameter, const double maximum_curvature_threshold, const double target_trajectory_length, const double forward_distance_threshold) const -> std::optional< std::pair< math::geometry::HermiteCurve, double >>
 
auto getLaneChangeTrajectory (const traffic_simulator_msgs::msg::LaneletPose &from, const traffic_simulator::lane_change::Parameter &lane_change_parameter) const -> std::optional< std::pair< math::geometry::HermiteCurve, double >>
 
auto getLaneChangeableLaneletId (const lanelet::Id, const traffic_simulator::lane_change::Direction, const traffic_simulator::RoutingGraphType type=traffic_simulator::RoutingConfiguration().routing_graph_type) const -> std::optional< lanelet::Id >
 
auto getLaneChangeableLaneletId (const lanelet::Id, const traffic_simulator::lane_change::Direction, const std::uint8_t shift, const traffic_simulator::RoutingGraphType type=traffic_simulator::RoutingConfiguration().routing_graph_type) const -> std::optional< lanelet::Id >
 
auto getLaneletIds () const -> lanelet::Ids
 
auto getLaneletPolygon (const lanelet::Id) const -> std::vector< geometry_msgs::msg::Point >
 
auto getLanelets (const lanelet::Ids &) const -> lanelet::Lanelets
 
auto getLateralDistance (const traffic_simulator_msgs::msg::LaneletPose &from, const traffic_simulator_msgs::msg::LaneletPose &to, const traffic_simulator::RoutingConfiguration &routing_configuration=traffic_simulator::RoutingConfiguration()) const -> std::optional< double >
 
auto getLeftBound (const lanelet::Id) const -> std::vector< geometry_msgs::msg::Point >
 
auto getLongitudinalDistance (const traffic_simulator_msgs::msg::LaneletPose &from_pose, const traffic_simulator_msgs::msg::LaneletPose &to_pose, const traffic_simulator::RoutingConfiguration &routing_configuration=traffic_simulator::RoutingConfiguration()) const -> std::optional< double >
 
auto getNearbyLaneletIds (const geometry_msgs::msg::Point &, const double distance_threshold, const bool include_crosswalk, const std::size_t search_count=5) const -> lanelet::Ids
 
auto getNearbyLaneletIds (const geometry_msgs::msg::Point &, const double distance_threshold, const std::size_t search_count=5) const -> lanelet::Ids
 
auto getPreviousLanelets (const lanelet::Id, const double backward_horizon=100, const traffic_simulator::RoutingGraphType type=traffic_simulator::RoutingConfiguration().routing_graph_type) const -> lanelet::Ids
 
auto getRightBound (const lanelet::Id) const -> std::vector< geometry_msgs::msg::Point >
 
auto getRightOfWayLaneletIds (const lanelet::Ids &) const -> std::unordered_map< lanelet::Id, lanelet::Ids >
 
auto getRightOfWayLaneletIds (const lanelet::Id) const -> lanelet::Ids
 
auto getRoute (const lanelet::Id from, const lanelet::Id to, const traffic_simulator::RoutingConfiguration &routing_configuration=traffic_simulator::RoutingConfiguration()) const -> lanelet::Ids
 
auto getSpeedLimit (const lanelet::Ids &, const traffic_simulator::RoutingGraphType type=traffic_simulator::RoutingConfiguration().routing_graph_type) const -> double
 
auto getStopLineIds () const -> lanelet::Ids
 
auto getStopLineIdsOnPath (const lanelet::Ids &route_lanelets) const -> lanelet::Ids
 
auto getStopLinePolygon (const lanelet::Id) const -> std::vector< geometry_msgs::msg::Point >
 
auto getTangentVector (const lanelet::Id, const double s) const -> std::optional< geometry_msgs::msg::Vector3 >
 
auto getTrafficLightBulbPosition (const lanelet::Id traffic_light_id, const std::string &) const -> std::optional< geometry_msgs::msg::Point >
 
auto getTrafficLightIds () const -> lanelet::Ids
 
auto getTrafficLightIdsOnPath (const lanelet::Ids &route_lanelets) const -> lanelet::Ids
 
auto getTrafficLightRegulatoryElement (const lanelet::Id) const -> lanelet::TrafficLight::Ptr
 
auto getTrafficLightRegulatoryElementIDsFromTrafficLight (const lanelet::Id) const -> lanelet::Ids
 
auto getTrafficLightStopLineIds (const lanelet::Id traffic_light_id) const -> lanelet::Ids
 
auto getTrafficLightStopLinesPoints (const lanelet::Id traffic_light_id) const -> std::vector< std::vector< geometry_msgs::msg::Point >>
 
auto insertMarkerArray (visualization_msgs::msg::MarkerArray &, const visualization_msgs::msg::MarkerArray &) const -> void
 
auto isInIntersection (const lanelet::Id) const -> bool
 
auto isInLanelet (const lanelet::Id, const double s) const -> bool
 
auto isInRoute (const lanelet::Id, const lanelet::Ids &route) const -> bool
 
auto isTrafficLight (const lanelet::Id) const -> bool
 
auto isTrafficLightRegulatoryElement (const lanelet::Id) const -> bool
 
auto toMapBin () const -> autoware_map_msgs::msg::LaneletMapBin
 
auto toMapPoints (const lanelet::Id, const std::vector< double > &s) const -> std::vector< geometry_msgs::msg::Point >
 

Constructor & Destructor Documentation

◆ HdMapUtils()

hdmap_utils::HdMapUtils::HdMapUtils ( const boost::filesystem::path &  lanelet2_map_path,
const geographic_msgs::msg::GeoPoint &   
)
explicit

Member Function Documentation

◆ canChangeLane()

auto hdmap_utils::HdMapUtils::canChangeLane ( const lanelet::Id  from,
const lanelet::Id  to,
const traffic_simulator::RoutingGraphType  type = traffic_simulator::RoutingConfiguration().routing_graph_type 
) const -> bool

◆ clipTrajectoryFromLaneletIds()

auto hdmap_utils::HdMapUtils::clipTrajectoryFromLaneletIds ( const lanelet::Id  lanelet_id,
const double  s,
const lanelet::Ids &  lanelet_ids,
const double  forward_distance = 20 
) const -> std::vector<geometry_msgs::msg::Point>

◆ countLaneChanges()

auto hdmap_utils::HdMapUtils::countLaneChanges ( const traffic_simulator_msgs::msg::LaneletPose &  from,
const traffic_simulator_msgs::msg::LaneletPose &  to,
const traffic_simulator::RoutingConfiguration routing_configuration = traffic_simulator::RoutingConfiguration() 
) const -> std::optional<std::pair<int, int>>
Note
a lane change considers the lanes in the same direction as the original, so ignore the lanes in the opposite direction

◆ filterLaneletIds()

auto hdmap_utils::HdMapUtils::filterLaneletIds ( const lanelet::Ids &  lanelet_ids,
const char  subtype[] 
) const -> lanelet::Ids

◆ generateMarker()

auto hdmap_utils::HdMapUtils::generateMarker ( ) const -> visualization_msgs::msg::MarkerArray

◆ getAltitude()

auto hdmap_utils::HdMapUtils::getAltitude ( const traffic_simulator_msgs::msg::LaneletPose &  lanelet_pose) const -> double

◆ getCenterPoints() [1/2]

auto hdmap_utils::HdMapUtils::getCenterPoints ( const lanelet::Id  lanelet_id) const -> std::vector<geometry_msgs::msg::Point>

◆ getCenterPoints() [2/2]

auto hdmap_utils::HdMapUtils::getCenterPoints ( const lanelet::Ids &  lanelet_ids) const -> std::vector<geometry_msgs::msg::Point>

◆ getCenterPointsSpline()

auto hdmap_utils::HdMapUtils::getCenterPointsSpline ( const lanelet::Id  lanelet_id) const -> std::shared_ptr<math::geometry::CatmullRomSpline>

◆ getClosestLaneletId()

auto hdmap_utils::HdMapUtils::getClosestLaneletId ( const geometry_msgs::msg::Pose &  pose,
const double  distance_thresh = 30.0,
const bool  include_crosswalk = false 
) const -> std::optional<lanelet::Id>

◆ getCollisionPointInLaneCoordinate()

auto hdmap_utils::HdMapUtils::getCollisionPointInLaneCoordinate ( const lanelet::Id  lanelet_id,
const lanelet::Id  crossing_lanelet_id 
) const -> std::optional<double>

◆ getConflictingCrosswalkIds()

auto hdmap_utils::HdMapUtils::getConflictingCrosswalkIds ( const lanelet::Ids &  lanelet_ids) const -> lanelet::Ids

◆ getConflictingLaneIds()

auto hdmap_utils::HdMapUtils::getConflictingLaneIds ( const lanelet::Ids &  lanelet_ids,
const traffic_simulator::RoutingGraphType  type = traffic_simulator::RoutingConfiguration().routing_graph_type 
) const -> lanelet::Ids

◆ getDistanceToStopLine() [1/2]

auto hdmap_utils::HdMapUtils::getDistanceToStopLine ( const lanelet::Ids &  route_lanelets,
const math::geometry::CatmullRomSplineInterface spline 
) const -> std::optional<double>

◆ getDistanceToStopLine() [2/2]

auto hdmap_utils::HdMapUtils::getDistanceToStopLine ( const lanelet::Ids &  route_lanelets,
const std::vector< geometry_msgs::msg::Point > &  waypoints 
) const -> std::optional<double>

◆ getDistanceToTrafficLightStopLine() [1/4]

auto hdmap_utils::HdMapUtils::getDistanceToTrafficLightStopLine ( const lanelet::Ids &  route_lanelets,
const math::geometry::CatmullRomSplineInterface spline 
) const -> std::optional<double>

◆ getDistanceToTrafficLightStopLine() [2/4]

auto hdmap_utils::HdMapUtils::getDistanceToTrafficLightStopLine ( const lanelet::Ids &  route_lanelets,
const std::vector< geometry_msgs::msg::Point > &  waypoints 
) const -> std::optional<double>

◆ getDistanceToTrafficLightStopLine() [3/4]

auto hdmap_utils::HdMapUtils::getDistanceToTrafficLightStopLine ( const math::geometry::CatmullRomSplineInterface spline,
const lanelet::Id  traffic_light_id 
) const -> std::optional<double>

◆ getDistanceToTrafficLightStopLine() [4/4]

auto hdmap_utils::HdMapUtils::getDistanceToTrafficLightStopLine ( const std::vector< geometry_msgs::msg::Point > &  waypoints,
const lanelet::Id  traffic_light_id 
) const -> std::optional<double>

◆ getFollowingLanelets() [1/2]

auto hdmap_utils::HdMapUtils::getFollowingLanelets ( const lanelet::Id  current_lanelet_id,
const lanelet::Ids &  route,
const double  horizon = 100,
const bool  include_current_lanelet_id = true,
const traffic_simulator::RoutingGraphType  type = traffic_simulator::RoutingConfiguration().routing_graph_type 
) const -> lanelet::Ids

◆ getFollowingLanelets() [2/2]

auto hdmap_utils::HdMapUtils::getFollowingLanelets ( const lanelet::Id  lanelet_id,
const double  distance = 100,
const bool  include_self = true,
const traffic_simulator::RoutingGraphType  type = traffic_simulator::RoutingConfiguration().routing_graph_type 
) const -> lanelet::Ids

◆ getLaneChangeableLaneletId() [1/2]

auto hdmap_utils::HdMapUtils::getLaneChangeableLaneletId ( const lanelet::Id  lanelet_id,
const traffic_simulator::lane_change::Direction  direction,
const std::uint8_t  shift,
const traffic_simulator::RoutingGraphType  type = traffic_simulator::RoutingConfiguration().routing_graph_type 
) const -> std::optional<lanelet::Id>

◆ getLaneChangeableLaneletId() [2/2]

auto hdmap_utils::HdMapUtils::getLaneChangeableLaneletId ( const lanelet::Id  lanelet_id,
const traffic_simulator::lane_change::Direction  direction,
const traffic_simulator::RoutingGraphType  type = traffic_simulator::RoutingConfiguration().routing_graph_type 
) const -> std::optional<lanelet::Id>

◆ getLaneChangeTrajectory() [1/2]

auto hdmap_utils::HdMapUtils::getLaneChangeTrajectory ( const geometry_msgs::msg::Pose &  from,
const traffic_simulator::lane_change::Parameter lane_change_parameter,
const double  maximum_curvature_threshold,
const double  target_trajectory_length,
const double  forward_distance_threshold 
) const -> std::optional<std::pair<math::geometry::HermiteCurve, double>>

◆ getLaneChangeTrajectory() [2/2]

auto hdmap_utils::HdMapUtils::getLaneChangeTrajectory ( const traffic_simulator_msgs::msg::LaneletPose &  from,
const traffic_simulator::lane_change::Parameter lane_change_parameter 
) const -> std::optional<std::pair<math::geometry::HermiteCurve, double>>

◆ getLaneletIds()

auto hdmap_utils::HdMapUtils::getLaneletIds ( ) const -> lanelet::Ids

◆ getLaneletPolygon()

auto hdmap_utils::HdMapUtils::getLaneletPolygon ( const lanelet::Id  lanelet_id) const -> std::vector<geometry_msgs::msg::Point>

◆ getLanelets()

auto hdmap_utils::HdMapUtils::getLanelets ( const lanelet::Ids &  lanelet_ids) const -> lanelet::Lanelets

◆ getLateralDistance()

auto hdmap_utils::HdMapUtils::getLateralDistance ( const traffic_simulator_msgs::msg::LaneletPose &  from,
const traffic_simulator_msgs::msg::LaneletPose &  to,
const traffic_simulator::RoutingConfiguration routing_configuration = traffic_simulator::RoutingConfiguration() 
) const -> std::optional<double>

◆ getLeftBound()

auto hdmap_utils::HdMapUtils::getLeftBound ( const lanelet::Id  lanelet_id) const -> std::vector<geometry_msgs::msg::Point>

◆ getLongitudinalDistance()

auto hdmap_utils::HdMapUtils::getLongitudinalDistance ( const traffic_simulator_msgs::msg::LaneletPose &  from_pose,
const traffic_simulator_msgs::msg::LaneletPose &  to_pose,
const traffic_simulator::RoutingConfiguration routing_configuration = traffic_simulator::RoutingConfiguration() 
) const -> std::optional<double>
See also
https://tier4.github.io/scenario_simulator_v2-docs/developer_guide/DistanceCalculation/
Note
horizontal bar must intersect with the lanelet spline, so the distance was set arbitrarily to 10 meters.

◆ getNearbyLaneletIds() [1/2]

auto hdmap_utils::HdMapUtils::getNearbyLaneletIds ( const geometry_msgs::msg::Point &  point,
const double  distance_threshold,
const bool  include_crosswalk,
const std::size_t  search_count = 5 
) const -> lanelet::Ids

◆ getNearbyLaneletIds() [2/2]

auto hdmap_utils::HdMapUtils::getNearbyLaneletIds ( const geometry_msgs::msg::Point &  position,
const double  distance_threshold,
const std::size_t  search_count = 5 
) const -> lanelet::Ids

◆ getPreviousLanelets()

auto hdmap_utils::HdMapUtils::getPreviousLanelets ( const lanelet::Id  current_lanelet_id,
const double  backward_horizon = 100,
const traffic_simulator::RoutingGraphType  type = traffic_simulator::RoutingConfiguration().routing_graph_type 
) const -> lanelet::Ids

◆ getRightBound()

auto hdmap_utils::HdMapUtils::getRightBound ( const lanelet::Id  lanelet_id) const -> std::vector<geometry_msgs::msg::Point>

◆ getRightOfWayLaneletIds() [1/2]

auto hdmap_utils::HdMapUtils::getRightOfWayLaneletIds ( const lanelet::Id  lanelet_id) const -> lanelet::Ids

◆ getRightOfWayLaneletIds() [2/2]

auto hdmap_utils::HdMapUtils::getRightOfWayLaneletIds ( const lanelet::Ids &  lanelet_ids) const -> std::unordered_map<lanelet::Id, lanelet::Ids>

◆ getRoute()

auto hdmap_utils::HdMapUtils::getRoute ( const lanelet::Id  from,
const lanelet::Id  to,
const traffic_simulator::RoutingConfiguration routing_configuration = traffic_simulator::RoutingConfiguration() 
) const -> lanelet::Ids

◆ getSpeedLimit()

auto hdmap_utils::HdMapUtils::getSpeedLimit ( const lanelet::Ids &  lanelet_ids,
const traffic_simulator::RoutingGraphType  type = traffic_simulator::RoutingConfiguration().routing_graph_type 
) const -> double

◆ getStopLineIds()

auto hdmap_utils::HdMapUtils::getStopLineIds ( ) const -> lanelet::Ids

◆ getStopLineIdsOnPath()

auto hdmap_utils::HdMapUtils::getStopLineIdsOnPath ( const lanelet::Ids &  route_lanelets) const -> lanelet::Ids

◆ getStopLinePolygon()

auto hdmap_utils::HdMapUtils::getStopLinePolygon ( const lanelet::Id  lanelet_id) const -> std::vector<geometry_msgs::msg::Point>

◆ getTangentVector()

auto hdmap_utils::HdMapUtils::getTangentVector ( const lanelet::Id  lanelet_id,
const double  s 
) const -> std::optional<geometry_msgs::msg::Vector3>

◆ getTrafficLightBulbPosition()

auto hdmap_utils::HdMapUtils::getTrafficLightBulbPosition ( const lanelet::Id  traffic_light_id,
const std::string &  color_name 
) const -> std::optional<geometry_msgs::msg::Point>

◆ getTrafficLightIds()

auto hdmap_utils::HdMapUtils::getTrafficLightIds ( ) const -> lanelet::Ids

◆ getTrafficLightIdsOnPath()

auto hdmap_utils::HdMapUtils::getTrafficLightIdsOnPath ( const lanelet::Ids &  route_lanelets) const -> lanelet::Ids

◆ getTrafficLightRegulatoryElement()

auto hdmap_utils::HdMapUtils::getTrafficLightRegulatoryElement ( const lanelet::Id  lanelet_id) const -> lanelet::TrafficLight::Ptr

◆ getTrafficLightRegulatoryElementIDsFromTrafficLight()

auto hdmap_utils::HdMapUtils::getTrafficLightRegulatoryElementIDsFromTrafficLight ( const lanelet::Id  traffic_light_way_id) const -> lanelet::Ids

◆ getTrafficLightStopLineIds()

auto hdmap_utils::HdMapUtils::getTrafficLightStopLineIds ( const lanelet::Id  traffic_light_id) const -> lanelet::Ids

◆ getTrafficLightStopLinesPoints()

auto hdmap_utils::HdMapUtils::getTrafficLightStopLinesPoints ( const lanelet::Id  traffic_light_id) const -> std::vector<std::vector<geometry_msgs::msg::Point>>

◆ insertMarkerArray()

auto hdmap_utils::HdMapUtils::insertMarkerArray ( visualization_msgs::msg::MarkerArray &  a1,
const visualization_msgs::msg::MarkerArray &  a2 
) const -> void

◆ isInIntersection()

auto hdmap_utils::HdMapUtils::isInIntersection ( const lanelet::Id  lanelet_id) const -> bool

◆ isInLanelet()

auto hdmap_utils::HdMapUtils::isInLanelet ( const lanelet::Id  lanelet_id,
const double  s 
) const -> bool

◆ isInRoute()

auto hdmap_utils::HdMapUtils::isInRoute ( const lanelet::Id  lanelet_id,
const lanelet::Ids &  route 
) const -> bool

◆ isTrafficLight()

auto hdmap_utils::HdMapUtils::isTrafficLight ( const lanelet::Id  lanelet_id) const -> bool

◆ isTrafficLightRegulatoryElement()

auto hdmap_utils::HdMapUtils::isTrafficLightRegulatoryElement ( const lanelet::Id  lanelet_id) const -> bool

◆ toMapBin()

auto hdmap_utils::HdMapUtils::toMapBin ( ) const -> autoware_map_msgs::msg::LaneletMapBin

◆ toMapPoints()

auto hdmap_utils::HdMapUtils::toMapPoints ( const lanelet::Id  lanelet_id,
const std::vector< double > &  s 
) const -> std::vector<geometry_msgs::msg::Point>

The documentation for this class was generated from the following files: