Program Listing for File Route.h

Return to documentation for file (include/lanelet2_routing/Route.h)

#pragma once
#include <lanelet2_core/Forward.h>
#include <lanelet2_core/LaneletMap.h>
#include <lanelet2_core/primitives/LaneletSequence.h>

#include <memory>
#include <string>
#include <vector>

#include "lanelet2_routing/Forward.h"
#include "lanelet2_routing/LaneletPath.h"
#include "lanelet2_routing/Types.h"

namespace lanelet {
namespace routing {

class Route {
 public:
  using Errors = std::vector<std::string>;
  Route();
  Route(const Route& other) = delete;
  Route& operator=(const Route& other) = delete;
  Route& operator=(Route&& other) noexcept;
  Route(Route&& other) noexcept;
  ~Route() noexcept;

  Route(LaneletPath shortestPath, std::unique_ptr<internal::RouteGraph> graph,
        LaneletSubmapConstPtr laneletSubmap) noexcept;

  inline const LaneletPath& shortestPath() const noexcept { return shortestPath_; }

  LaneletPath remainingShortestPath(const ConstLanelet& ll) const;

  LaneletSequence fullLane(const ConstLanelet& ll) const;

  LaneletSequence remainingLane(const ConstLanelet& ll) const;

  double length2d() const;

  size_t numLanes() const;

  inline LaneletSubmapConstPtr laneletSubmap() const noexcept { return laneletSubmap_; }

  [[deprecated("Use laneletSubmap() to obtain a view on the elements within this route")]] inline LaneletMapConstPtr
  laneletMap() const noexcept {
    return laneletSubmap_->laneletMap();
  }

  LaneletMapPtr getDebugLaneletMap() const;

  size_t size() const;

  LaneletRelations followingRelations(const ConstLanelet& lanelet) const;

  ConstLanelets following(const ConstLanelet& lanelet) const;

  LaneletRelations previousRelations(const ConstLanelet& lanelet) const;

  ConstLanelets previous(const ConstLanelet& lanelet) const;

  Optional<LaneletRelation> leftRelation(const ConstLanelet& lanelet) const;

  LaneletRelations leftRelations(const ConstLanelet& lanelet) const;

  Optional<LaneletRelation> rightRelation(const ConstLanelet& lanelet) const;

  LaneletRelations rightRelations(const ConstLanelet& lanelet) const;

  void forEachSuccessor(const ConstLanelet& lanelet, const LaneletVisitFunction& f) const;

  void forEachPredecessor(const ConstLanelet& lanelet, const LaneletVisitFunction& f) const;

  ConstLanelets conflictingInRoute(const ConstLanelet& lanelet) const;

  ConstLaneletOrAreas conflictingInMap(const ConstLanelet& lanelet) const;

  ConstLaneletOrAreas allConflictingInMap() const;

  bool contains(const ConstLanelet& lanelet) const;

  Errors checkValidity(bool throwOnError = false) const;

 private:
  std::unique_ptr<internal::RouteGraph> graph_;
  LaneletPath shortestPath_;
  LaneletSubmapConstPtr laneletSubmap_;
};
}  // namespace routing
}  // namespace lanelet