22#include <lanelet2_core/LaneletMap.h>
23#include <lanelet2_core/primitives/Area.h>
24#include <lanelet2_core/primitives/Lanelet.h>
25#include <lanelet2_core/primitives/Point.h>
26#include <lanelet2_routing/Route.h>
27#include <lanelet2_routing/RoutingGraph.h>
28#include <lanelet2_traffic_rules/TrafficRules.h>
29#include <lanelet2_core/utility/Optional.h>
30#include <carma_perception_msgs/msg/roadway_obstacle.hpp>
31#include <carma_perception_msgs/msg/roadway_obstacle_list.hpp>
32#include <carma_perception_msgs/msg/external_object.hpp>
33#include <carma_perception_msgs/msg/external_object_list.hpp>
34#include <lanelet2_extension/regulatory_elements/CarmaTrafficSignal.h>
35#include <lanelet2_extension/regulatory_elements/SignalizedIntersection.h>
36#include <lanelet2_core/primitives/BasicRegulatoryElements.h>
38#include <lanelet2_extension/regulatory_elements/BusStopRule.h>
95 virtual std::pair<TrackPos, TrackPos>
routeTrackPos(
const lanelet::ConstArea& area)
const = 0;
140 virtual std::vector<lanelet::ConstLanelet>
getLaneletsBetween(
double start,
double end,
bool shortest_path_only =
false,
141 bool bounds_inclusive =
true)
const = 0;
163 virtual std::vector<lanelet::BasicPoint2d>
sampleRoutePoints(
double start_downtrack,
double end_downtrack,
164 double step_size)
const = 0;
185 virtual lanelet::LaneletMapConstPtr
getMap()
const = 0;
229 virtual lanelet::Optional<TrafficRulesConstPtr>
237 virtual lanelet::Optional<TrafficRulesConstPtr>
251 virtual lanelet::Optional<carma_perception_msgs::msg::RoadwayObstacle>
266 virtual lanelet::Optional<lanelet::Lanelet>
getIntersectingLanelet(
const carma_perception_msgs::msg::ExternalObject&
object)
const = 0;
323 virtual lanelet::Optional<std::tuple<TrackPos, carma_perception_msgs::msg::RoadwayObstacle>>
340 virtual lanelet::Optional<std::tuple<TrackPos, carma_perception_msgs::msg::RoadwayObstacle>>
355 virtual std::vector<lanelet::ConstLanelet>
getLane(
const lanelet::ConstLanelet&
lanelet,
375 virtual std::vector<lanelet::ConstLanelet>
getLaneletsFromPoint(
const lanelet::BasicPoint2d&
point,
const unsigned int n = 10)
const = 0;
387 virtual std::vector<lanelet::CarmaTrafficSignalPtr>
getSignalsAlongRoute(
const lanelet::BasicPoint2d& loc)
const = 0;
398 virtual boost::optional<std::pair<lanelet::ConstLanelet, lanelet::ConstLanelet>>
getEntryExitOfSignalAlongRoute(
const lanelet::CarmaTrafficSignalPtr& traffic_signal)
const = 0;
438 virtual std::vector<lanelet::ConstLanelet>
nonConnectedAdjacentLeft(
const lanelet::BasicPoint2d& input_point,
const unsigned int n = 10)
const = 0;
Position in a track based coordinate system where the axis are downtrack and crosstrack....
An interface which provides read access to the semantic map and route. This class is not thread safe....
virtual boost::optional< std::pair< lanelet::ConstLanelet, lanelet::ConstLanelet > > getEntryExitOfSignalAlongRoute(const lanelet::CarmaTrafficSignalPtr &traffic_signal) const =0
Returns the entry and exit lanelet of the signal along the SHORTEST PATH of route....
virtual std::vector< lanelet::CarmaTrafficSignalPtr > getSignalsAlongRoute(const lanelet::BasicPoint2d &loc) const =0
Return a list of traffic lights/intersections along the current route. The traffic lights along a rou...
virtual std::vector< lanelet::BasicPoint2d > sampleRoutePoints(double start_downtrack, double end_downtrack, double step_size) const =0
Samples the route centerline between the provided downtracks with the provided step size....
virtual lanelet::Optional< lanelet::Lanelet > getIntersectingLanelet(const carma_perception_msgs::msg::ExternalObject &object) const =0
Gets the a lanelet the object is currently on determined by its position on the semantic map....
virtual TrackPos routeTrackPos(const lanelet::BasicPoint2d &point) const =0
Returns the TrackPos, computed in 2d, of the provided point relative to the current route.
virtual std::vector< lanelet::SignalizedIntersectionPtr > getSignalizedIntersectionsAlongRoute(const lanelet::BasicPoint2d &loc) const =0
Return a list of signalized intersections along the current route. The signalized intersections along...
virtual std::vector< lanelet::ConstLanelet > nonConnectedAdjacentLeft(const lanelet::BasicPoint2d &input_point, const unsigned int n=10) const =0
Given the cartesian point on the map, tries to get the opposite direction lanelet on the left This fu...
virtual TrackPos getRouteEndTrackPos() const =0
Get trackpos of the end of route point relative to the route.
virtual lanelet::LaneletMapConstPtr getMap() const =0
Get a pointer to the current map. If the underlying map has changed the pointer will also need to be ...
virtual LaneletRoutingGraphConstPtr getMapRoutingGraph() const =0
Get a pointer to the routing graph for the current map. If the underlying map has changed the pointer...
virtual TrackPos routeTrackPos(const lanelet::ConstLanelet &lanelet) const =0
Returns the TrackPos, computed in 2d, of the provided lanelet relative to the current route....
virtual std::vector< lanelet::ConstLanelet > getLane(const lanelet::ConstLanelet &lanelet, const LaneSection §ion=LANE_AHEAD) const =0
Gets the specified lane section achievable without lane change, sorted from the start,...
virtual size_t getMapVersion() const =0
Returns a monotonically increasing version number which represents the version stamp of the map geome...
virtual lanelet::Optional< std::tuple< TrackPos, carma_perception_msgs::msg::RoadwayObstacle > > nearestObjectBehindInLane(const lanelet::BasicPoint2d &object_center) const =0
Gets Downtrack distance to AND copy of the closest object BEHIND on the same lane as the given point....
virtual std::optional< lanelet::ConstLanelet > getFirstLaneletOnShortestPath(const std::vector< lanelet::ConstLanelet > &lanelets_to_filter) const =0
Given the vector of lanelets, returns the lanelet that's on the shortest path. Returns earliest lanel...
virtual lanelet::Optional< TrafficRulesConstPtr > getTrafficRules() const =0
Get the Traffic Rules object.
virtual std::vector< carma_perception_msgs::msg::RoadwayObstacle > getInLaneObjects(const lanelet::ConstLanelet &lanelet, const LaneSection §ion=LANE_AHEAD) const =0
Gets all roadway objects currently in the same lane as the given lanelet.
virtual lanelet::Optional< std::tuple< TrackPos, carma_perception_msgs::msg::RoadwayObstacle > > nearestObjectAheadInLane(const lanelet::BasicPoint2d &object_center) const =0
Gets Downtrack distance to AND copy of the closest object AHEAD on the same lane as the given point....
virtual std::pair< TrackPos, TrackPos > routeTrackPos(const lanelet::ConstArea &area) const =0
Returns a pair of TrackPos, computed in 2d, of the provided area relative to the current route....
virtual ~WorldModel()
Virtual destructor to ensure delete safety for pointers to implementing classes.
virtual lanelet::Optional< carma_perception_msgs::msg::RoadwayObstacle > toRoadwayObstacle(const carma_perception_msgs::msg::ExternalObject &object) const =0
Converts an ExternalObject in a RoadwayObstacle by mapping its position onto the semantic map....
virtual boost::optional< lanelet::BasicPoint2d > pointFromRouteTrackPos(const TrackPos &route_pos) const =0
Converts a route track position into a map frame cartesian point.
virtual std::vector< carma_perception_msgs::msg::RoadwayObstacle > getRoadwayObjects() const =0
Get most recent roadway objects - all objects on the road detected by perception stack.
virtual std::vector< lanelet::ConstLanelet > getLaneletsBetween(double start, double end, bool shortest_path_only=false, bool bounds_inclusive=true) const =0
Returns a list of lanelets which are part of the route and whose downtrack bounds exist within the pr...
virtual lanelet::Optional< double > distToNearestObjInLane(const lanelet::BasicPoint2d &object_center) const =0
Gets Cartesian distance to the closest object on the same lane as the given point.
virtual std::vector< lanelet::ConstLanelet > getLaneletsFromPoint(const lanelet::BasicPoint2d &point, const unsigned int n=10) const =0
Gets the underlying lanelet, given the cartesian point on the map.
virtual std::string getRouteName() const =0
Get the current route name.
virtual std::vector< std::shared_ptr< lanelet::AllWayStop > > getIntersectionsAlongRoute(const lanelet::BasicPoint2d &loc) const =0
Return a list of all way stop intersections along the current route. The tall way stop intersections ...
virtual lanelet::Optional< TrafficRulesConstPtr > getTrafficRules(const std::string &participant) const =0
Get a pointer to the traffic rules object used internally by the world model and considered the carma...
virtual std::vector< lanelet::BusStopRulePtr > getBusStopsAlongRoute(const lanelet::BasicPoint2d &loc) const =0
Return a list of bus stop along the current route. The bus stop along a route and the next bus stop a...
virtual LaneletRouteConstPtr getRoute() const =0
Get a pointer to the current route. If the underlying route has changed the pointer will also need to...
std::unique_ptr< const lanelet::routing::RoutingGraph > LaneletRoutingGraphConstUPtr
std::shared_ptr< lanelet::routing::RoutingGraph > LaneletRoutingGraphPtr
std::shared_ptr< const WorldModel > WorldModelConstPtr
std::shared_ptr< const lanelet::traffic_rules::TrafficRules > TrafficRulesConstPtr
std::shared_ptr< const lanelet::routing::Route > LaneletRouteConstPtr
std::unique_ptr< const lanelet::traffic_rules::TrafficRules > TrafficRulesUConstPtr
std::unique_ptr< lanelet::routing::Route > LaneletRouteUPtr
std::unique_ptr< lanelet::routing::RoutingGraph > LaneletRoutingGraphUPtr
std::shared_ptr< const lanelet::routing::RoutingGraph > LaneletRoutingGraphConstPtr
std::shared_ptr< lanelet::routing::Route > LaneletRoutePtr
std::unique_ptr< const lanelet::routing::Route > LaneletRouteUConstPtr