Program Listing for File RoutingGraph.h
↰ Return to documentation for file (include/lanelet2_routing/RoutingGraph.h)
#pragma once
#include <lanelet2_core/Forward.h>
#include <lanelet2_core/LaneletMap.h>
#include <lanelet2_core/primitives/Lanelet.h>
#include <lanelet2_core/primitives/LaneletOrArea.h>
#include <lanelet2_core/utility/Optional.h>
#include <map>
#include "lanelet2_routing/Forward.h"
#include "lanelet2_routing/LaneletPath.h"
#include "lanelet2_routing/RoutingCost.h"
#include "lanelet2_routing/Types.h"
namespace lanelet {
namespace routing {
struct PossiblePathsParams {
Optional<double> routingCostLimit;
Optional<uint32_t> elementLimit;
RoutingCostId routingCostId{};
bool includeLaneChanges{false};
bool includeShorterPaths{false};
};
class RoutingGraph {
public:
using Errors = std::vector<std::string>;
using Configuration = std::map<std::string, Attribute>;
static constexpr const char ParticipantHeight[] = "participant_height";
static RoutingGraphUPtr build(const LaneletMap& laneletMap, const traffic_rules::TrafficRules& trafficRules,
const RoutingCostPtrs& routingCosts = defaultRoutingCosts(),
const Configuration& config = Configuration());
static RoutingGraphUPtr build(const LaneletSubmap& laneletSubmap, const traffic_rules::TrafficRules& trafficRules,
const RoutingCostPtrs& routingCosts = defaultRoutingCosts(),
const Configuration& config = Configuration());
RoutingGraph() = delete;
RoutingGraph(const RoutingGraph&) = delete;
RoutingGraph& operator=(const RoutingGraph&) = delete;
RoutingGraph(RoutingGraph&& /*other*/) noexcept;
RoutingGraph& operator=(RoutingGraph&& /*other*/) noexcept;
~RoutingGraph();
Optional<Route> getRoute(const ConstLanelet& from, const ConstLanelet& to, RoutingCostId routingCostId = {},
bool withLaneChanges = true) const;
Optional<Route> getRouteVia(const ConstLanelet& from, const ConstLanelets& via, const ConstLanelet& to,
RoutingCostId routingCostId = {}, bool withLaneChanges = true) const;
Optional<LaneletPath> shortestPath(const ConstLanelet& from, const ConstLanelet& to, RoutingCostId routingCostId = {},
bool withLaneChanges = true) const;
Optional<LaneletOrAreaPath> shortestPathIncludingAreas(const ConstLaneletOrArea& from, const ConstLaneletOrArea& to,
RoutingCostId routingCostId = {},
bool withLaneChanges = true) const;
Optional<LaneletPath> shortestPathVia(const ConstLanelet& start, const ConstLanelets& via, const ConstLanelet& end,
RoutingCostId routingCostId = {}, bool withLaneChanges = true) const;
Optional<LaneletOrAreaPath> shortestPathIncludingAreasVia(const ConstLaneletOrArea& start,
const ConstLaneletOrAreas& via,
const ConstLaneletOrArea& end,
RoutingCostId routingCostId = {},
bool withLaneChanges = true) const;
Optional<RelationType> routingRelation(const ConstLanelet& from, const ConstLanelet& to,
bool includeConflicting = false) const;
ConstLanelets following(const ConstLanelet& lanelet, bool withLaneChanges = false) const;
LaneletRelations followingRelations(const ConstLanelet& lanelet, bool withLaneChanges = false) const;
ConstLanelets previous(const ConstLanelet& lanelet, bool withLaneChanges = false) const;
LaneletRelations previousRelations(const ConstLanelet& lanelet, bool withLaneChanges = false) const;
ConstLanelets besides(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const;
Optional<ConstLanelet> left(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const;
Optional<ConstLanelet> adjacentLeft(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const;
Optional<ConstLanelet> right(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const;
Optional<ConstLanelet> adjacentRight(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const;
ConstLanelets lefts(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const;
ConstLanelets adjacentLefts(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const;
LaneletRelations leftRelations(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const;
ConstLanelets rights(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const;
ConstLanelets adjacentRights(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const;
LaneletRelations rightRelations(const ConstLanelet& lanelet, RoutingCostId routingCostId = {}) const;
ConstLaneletOrAreas conflicting(const ConstLaneletOrArea& laneletOrArea) const;
ConstLanelets reachableSet(const ConstLanelet& lanelet, double maxRoutingCost, RoutingCostId routingCostId = {},
bool allowLaneChanges = true) const;
ConstLaneletOrAreas reachableSetIncludingAreas(const ConstLaneletOrArea& llOrAr, double maxRoutingCost,
RoutingCostId routingCostId = {}) const;
ConstLanelets reachableSetTowards(const ConstLanelet& lanelet, double maxRoutingCost,
RoutingCostId routingCostId = {}, bool allowLaneChanges = true) const;
LaneletPaths possiblePaths(const ConstLanelet& startPoint, const PossiblePathsParams& params) const;
LaneletPaths possiblePaths(const ConstLanelet& startPoint, double minRoutingCost, RoutingCostId routingCostId = {},
bool allowLaneChanges = false) const;
LaneletPaths possiblePaths(const ConstLanelet& startPoint, uint32_t minLanelets, bool allowLaneChanges = false,
RoutingCostId routingCostId = {}) const;
LaneletPaths possiblePathsTowards(const ConstLanelet& targetLanelet, const PossiblePathsParams& params) const;
LaneletPaths possiblePathsTowards(const ConstLanelet& targetLanelet, double minRoutingCost,
RoutingCostId routingCostId = {}, bool allowLaneChanges = false) const;
LaneletPaths possiblePathsTowards(const ConstLanelet& targetLanelet, uint32_t minLanelets,
bool allowLaneChanges = false, RoutingCostId routingCostId = {}) const;
LaneletOrAreaPaths possiblePathsIncludingAreas(const ConstLaneletOrArea& startPoint,
const PossiblePathsParams& params) const;
LaneletOrAreaPaths possiblePathsIncludingAreas(const ConstLaneletOrArea& startPoint, double minRoutingCost,
RoutingCostId routingCostId = {}, bool allowLaneChanges = false) const;
LaneletOrAreaPaths possiblePathsIncludingAreas(const ConstLaneletOrArea& startPoint, uint32_t minElements,
bool allowLaneChanges = false, RoutingCostId routingCostId = {}) const;
void forEachSuccessor(const ConstLanelet& lanelet, const LaneletVisitFunction& f, bool allowLaneChanges = true,
RoutingCostId routingCostId = {}) const;
void forEachSuccessorIncludingAreas(const ConstLaneletOrArea& lanelet, const LaneletOrAreaVisitFunction& f,
bool allowLaneChanges = true, RoutingCostId routingCostId = {}) const;
void forEachPredecessor(const ConstLanelet& lanelet, const LaneletVisitFunction& f, bool allowLaneChanges = true,
RoutingCostId routingCostId = {}) const;
void forEachPredecessorIncludingAreas(const ConstLaneletOrArea& lanelet, const LaneletOrAreaVisitFunction& f,
bool allowLaneChanges = true, RoutingCostId routingCostId = {}) const;
void exportGraphML(const std::string& filename, const RelationType& edgeTypesToExclude = RelationType::None,
RoutingCostId routingCostId = {}) const;
void exportGraphViz(const std::string& filename, const RelationType& edgeTypesToExclude = RelationType::None,
RoutingCostId routingCostId = {}) const;
LaneletMapPtr getDebugLaneletMap(RoutingCostId routingCostId = {}, bool includeAdjacent = false,
bool includeConflicting = false) const;
inline LaneletSubmapConstPtr passableSubmap() const noexcept { return passableLaneletSubmap_; }
[[deprecated(
"Use passableSubmap to obtain the lanelets and areas within the routing graph!")]] inline LaneletMapConstPtr
passableMap() const noexcept {
return passableSubmap()->laneletMap();
}
Errors checkValidity(bool throwOnError = true) const;
RoutingGraph(std::unique_ptr<internal::RoutingGraphGraph>&& graph, lanelet::LaneletSubmapConstPtr&& passableMap);
private:
std::unique_ptr<internal::RoutingGraphGraph> graph_;
LaneletSubmapConstPtr passableLaneletSubmap_;
};
} // namespace routing
} // namespace lanelet