Go to the documentation of this file. 1 #include <gtest/gtest.h>
3 #include <lanelet2_core/primitives/Point.h>
20 double participantHeight = 2.,
double minLaneChangeLength = 0.) {
23 RoutingCostPtrs costPtrs{std::make_shared<RoutingCostDistance>(laneChangeCost, minLaneChangeLength),
24 std::make_shared<RoutingCostTravelTime>(laneChangeCost)};
33 RoutingCostPtrs costPtrs{std::make_shared<RoutingCostDistance>(laneChangeCost)};
40 RoutingCostPtrs costPtrs{std::make_shared<RoutingCostDistance>(laneChangeCost)};
52 std::unordered_map<Id, Polygon3d>(),
lines,
points);
94 std::unordered_map<Id, Point3d>
points;
95 std::unordered_map<Id, LineString3d>
lines;
96 std::unordered_map<Id, Area>
areas;
481 static RoutingGraphTestData testData;
486 const std::unordered_map<Id, Lanelet>&
lanelets{testData.lanelets};
487 const std::unordered_map<Id, Area>&
areas{testData.areas};
488 const std::unordered_map<Id, Point3d>&
points{testData.points};
489 const std::unordered_map<Id, LineString3d>&
lines{testData.lines};
520 template <
typename T>
523 using AllGraphs = testing::Types<GermanVehicleGraph, GermanPedestrianGraph, GermanBicycleGraph>;
525 #ifndef TYPED_TEST_SUITE
527 #define TYPED_TEST_SUITE TYPED_TEST_CASE
const std::unordered_map< Id, Area > & areas
std::vector< LineString3d > LineStrings3d
RoutingGraphPtr vehicleGraph
const std::unordered_map< Id, Lanelet > & lanelets
std::shared_ptr< LaneletMap > LaneletMapPtr
void addPoint(double x, double y, double z)
static constexpr const char LaneChange[]
static constexpr const char ParticipantHeight[]
Defined configuration attributes.
std::vector< RoutingCostPtr > RoutingCostPtrs
static RoutingGraphUPtr build(const LaneletMap &laneletMap, const traffic_rules::TrafficRules &trafficRules, const RoutingCostPtrs &routingCosts=defaultRoutingCosts(), const Configuration &config=Configuration())
Main constructor with optional configuration.
RoutingGraphConstPtr graph
static constexpr const char Pedestrian[]
static constexpr const char Highway[]
const LaneletMapConstPtr laneletMap
static constexpr const char Low[]
const std::unordered_map< Id, LineString3d > & lines
testing::Types< GermanVehicleGraph, GermanPedestrianGraph, GermanBicycleGraph > AllGraphs
static constexpr const char LineThin[]
std::shared_ptr< const LaneletMap > LaneletMapConstPtr
void addAreaPedestrian(const LineStrings3d &outerBound)
std::unordered_map< Id, Area > areas
RoutingGraphPtr setUpGermanPedestrianGraph(LaneletMap &map, double laneChangeCost=2.)
static constexpr const char Walkway[]
RoutingGraphPtr setUpGermanVehicleGraph(LaneletMap &map, double laneChangeCost=2., double participantHeight=2., double minLaneChangeLength=0.)
RoutingGraphPtr bicycleGraph
std::unordered_map< Id, Lanelet > lanelets
static constexpr const char Virtual[]
static constexpr const char Wall[]
static constexpr const char Subtype[]
const std::unordered_map< Id, Point3d > & points
static constexpr const char Crosswalk[]
static constexpr char Germany[]
std::vector< Point3d > Points3d
std::shared_ptr< RoutingGraph > RoutingGraphPtr
static constexpr const char DashedSolid[]
RoutingGraphPtr setUpGermanBicycleGraph(LaneletMap &map, double laneChangeCost=2.)
void addLaneletVehicle(const LineString3d &left, const LineString3d &right)
static constexpr const char Solid[]
static constexpr const char Curbstone[]
RoutingGraphPtr pedestrianGraph
static constexpr const char SolidDashed[]
TYPED_TEST_SUITE(AllGraphsTest, AllGraphs)
static constexpr const char Bicycle[]
static constexpr const char Vehicle[]
const double laneChangeCost
static constexpr const char Road[]
static TrafficRulesUPtr create(const std::string &location, const std::string &participant, TrafficRules::Configuration configuration=TrafficRules::Configuration())
std::map< std::string, Attribute > Configuration
static constexpr const char Dashed[]
void addLine(const Points3d &points)
std::map< std::string, Attribute > Configuration
std::shared_ptr< const RoutingGraph > RoutingGraphConstPtr
void setAttribute(AttributeName name, const Attribute &attribute)
RoutingGraphConstPtr graph
std::unordered_map< Id, LineString3d > lines
std::unordered_map< Id, Point3d > points
void addLaneletPedestrian(const LineString3d &left, const LineString3d &right)
RoutingGraphConstPtr graph
std::shared_ptr< TrafficRules > TrafficRulesPtr
lanelet2_routing
Author(s): Matthias Mayr
autogenerated on Sun Oct 27 2024 02:27:49