Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
WorldModel.hpp
Go to the documentation of this file.
1#pragma once
2
3/*
4 * Copyright (C) 2022 LEIDOS.
5 *
6 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
7 * use this file except in compliance with the License. You may obtain a copy of
8 * the License at
9 *
10 * http://www.apache.org/licenses/LICENSE-2.0
11 *
12 * Unless required by applicable law or agreed to in writing, software
13 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15 * License for the specific language governing permissions and limitations under
16 * the License.
17 */
18
19#include <exception>
20#include <memory>
21#include <tuple>
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>
37#include "carma_wm/TrackPos.hpp"
38#include <lanelet2_extension/regulatory_elements/BusStopRule.h>
39
40
41namespace carma_wm
42{
43
44// Helpful using declarations which are not defined by lanelet::routing module
45using LaneletRoutePtr = std::shared_ptr<lanelet::routing::Route>;
46using LaneletRouteConstPtr = std::shared_ptr<const lanelet::routing::Route>;
47using LaneletRouteUPtr = std::unique_ptr<lanelet::routing::Route>;
48using LaneletRouteUConstPtr = std::unique_ptr<const lanelet::routing::Route>;
49
50using LaneletRoutingGraphPtr = std::shared_ptr<lanelet::routing::RoutingGraph>;
51using LaneletRoutingGraphConstPtr = std::shared_ptr<const lanelet::routing::RoutingGraph>;
52using LaneletRoutingGraphUPtr = std::unique_ptr<lanelet::routing::RoutingGraph>;
53using LaneletRoutingGraphConstUPtr = std::unique_ptr<const lanelet::routing::RoutingGraph>;
54
55using TrafficRulesConstPtr = std::shared_ptr<const lanelet::traffic_rules::TrafficRules>;
56using TrafficRulesUConstPtr = std::unique_ptr<const lanelet::traffic_rules::TrafficRules>;
57
58// Helpful enums for dividing lane into sections of interest.
60{
64};
65
73{
74 public:
79 virtual ~WorldModel() {};
80
95 virtual std::pair<TrackPos, TrackPos> routeTrackPos(const lanelet::ConstArea& area) const = 0;
96
97
110 virtual TrackPos routeTrackPos(const lanelet::ConstLanelet& lanelet) const = 0;
111
123 virtual TrackPos routeTrackPos(const lanelet::BasicPoint2d& point) const = 0;
124
140 virtual std::vector<lanelet::ConstLanelet> getLaneletsBetween(double start, double end, bool shortest_path_only = false,
141 bool bounds_inclusive = true) const = 0;
142
163 virtual std::vector<lanelet::BasicPoint2d> sampleRoutePoints(double start_downtrack, double end_downtrack,
164 double step_size) const = 0;
165
166
178 virtual boost::optional<lanelet::BasicPoint2d> pointFromRouteTrackPos(const TrackPos& route_pos) const = 0;
179
185 virtual lanelet::LaneletMapConstPtr getMap() const = 0;
186
193 virtual LaneletRouteConstPtr getRoute() const = 0;
194
199 virtual std::string getRouteName() const = 0;
200
205 virtual TrackPos getRouteEndTrackPos() const = 0;
206
214
219 virtual std::vector<carma_perception_msgs::msg::RoadwayObstacle> getRoadwayObjects() const = 0;
220
229 virtual lanelet::Optional<TrafficRulesConstPtr>
230 getTrafficRules(const std::string& participant) const = 0;
231
237 virtual lanelet::Optional<TrafficRulesConstPtr>
238 getTrafficRules() const = 0;
239
251 virtual lanelet::Optional<carma_perception_msgs::msg::RoadwayObstacle>
252 toRoadwayObstacle(const carma_perception_msgs::msg::ExternalObject& object) const = 0;
253
266 virtual lanelet::Optional<lanelet::Lanelet> getIntersectingLanelet(const carma_perception_msgs::msg::ExternalObject& object) const = 0;
267
278 virtual std::vector<lanelet::BusStopRulePtr> getBusStopsAlongRoute(const lanelet::BasicPoint2d& loc) const = 0;
279
293 virtual std::vector<carma_perception_msgs::msg::RoadwayObstacle> getInLaneObjects(const lanelet::ConstLanelet& lanelet,
294 const LaneSection& section = LANE_AHEAD) const = 0;
295
307 virtual lanelet::Optional<double> distToNearestObjInLane(const lanelet::BasicPoint2d& object_center) const = 0;
308
323 virtual lanelet::Optional<std::tuple<TrackPos, carma_perception_msgs::msg::RoadwayObstacle>>
324 nearestObjectAheadInLane(const lanelet::BasicPoint2d& object_center) const = 0;
325
340 virtual lanelet::Optional<std::tuple<TrackPos, carma_perception_msgs::msg::RoadwayObstacle>>
341 nearestObjectBehindInLane(const lanelet::BasicPoint2d& object_center) const = 0;
342
355 virtual std::vector<lanelet::ConstLanelet> getLane(const lanelet::ConstLanelet& lanelet,
356 const LaneSection& section = LANE_AHEAD) const = 0;
357
364 virtual size_t getMapVersion() const = 0;
365
375 virtual std::vector<lanelet::ConstLanelet> getLaneletsFromPoint(const lanelet::BasicPoint2d& point, const unsigned int n = 10) const = 0;
376
387 virtual std::vector<lanelet::CarmaTrafficSignalPtr> getSignalsAlongRoute(const lanelet::BasicPoint2d& loc) const = 0;
388
398 virtual boost::optional<std::pair<lanelet::ConstLanelet, lanelet::ConstLanelet>> getEntryExitOfSignalAlongRoute(const lanelet::CarmaTrafficSignalPtr& traffic_signal) const = 0;
399
410 virtual std::vector<std::shared_ptr<lanelet::AllWayStop>> getIntersectionsAlongRoute(const lanelet::BasicPoint2d& loc) const = 0;
411
422 virtual std::vector<lanelet::SignalizedIntersectionPtr> getSignalizedIntersectionsAlongRoute(const lanelet::BasicPoint2d &loc) const = 0;
423
438 virtual std::vector<lanelet::ConstLanelet> nonConnectedAdjacentLeft(const lanelet::BasicPoint2d& input_point, const unsigned int n = 10) const = 0;
439
448 virtual std::optional<lanelet::ConstLanelet> getFirstLaneletOnShortestPath(const std::vector<lanelet::ConstLanelet>& lanelets_to_filter) const = 0;
449
450};
451// Helpful using declarations for carma_wm classes
452using WorldModelConstPtr = std::shared_ptr<const WorldModel>;
453} // namespace carma_wm
Position in a track based coordinate system where the axis are downtrack and crosstrack....
Definition: TrackPos.hpp:35
An interface which provides read access to the semantic map and route. This class is not thread safe....
Definition: WorldModel.hpp:73
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 &section=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 &section=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.
Definition: WorldModel.hpp:79
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
Definition: WorldModel.hpp:53
std::shared_ptr< lanelet::routing::RoutingGraph > LaneletRoutingGraphPtr
Definition: WorldModel.hpp:50
std::shared_ptr< const WorldModel > WorldModelConstPtr
Definition: WorldModel.hpp:452
std::shared_ptr< const lanelet::traffic_rules::TrafficRules > TrafficRulesConstPtr
Definition: WorldModel.hpp:55
std::shared_ptr< const lanelet::routing::Route > LaneletRouteConstPtr
Definition: WorldModel.hpp:46
std::unique_ptr< const lanelet::traffic_rules::TrafficRules > TrafficRulesUConstPtr
Definition: WorldModel.hpp:56
std::unique_ptr< lanelet::routing::Route > LaneletRouteUPtr
Definition: WorldModel.hpp:47
std::unique_ptr< lanelet::routing::RoutingGraph > LaneletRoutingGraphUPtr
Definition: WorldModel.hpp:52
std::shared_ptr< const lanelet::routing::RoutingGraph > LaneletRoutingGraphConstPtr
Definition: WorldModel.hpp:51
std::shared_ptr< lanelet::routing::Route > LaneletRoutePtr
Definition: WorldModel.hpp:45
std::unique_ptr< const lanelet::routing::Route > LaneletRouteUConstPtr
Definition: WorldModel.hpp:48