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.
|
An interface which provides read access to the semantic map and route. This class is not thread safe. All units of distance are in meters. More...
#include <WorldModel.hpp>
Public Member Functions | |
virtual | ~WorldModel () |
Virtual destructor to ensure delete safety for pointers to implementing classes. More... | |
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. The distance is based on the Area vertex with the smallest and largest downtrack distance This method overload is the most expensive of the routeTrackPos methods. More... | |
virtual TrackPos | routeTrackPos (const lanelet::ConstLanelet &lanelet) const =0 |
Returns the TrackPos, computed in 2d, of the provided lanelet relative to the current route. The distance is based on the first point in the lanelet centerline. More... | |
virtual TrackPos | routeTrackPos (const lanelet::BasicPoint2d &point) const =0 |
Returns the TrackPos, computed in 2d, of the provided point relative to the current route. More... | |
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 provided start and end distances. More... | |
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. At lane changes the points should exhibit a discontinuous jump at the end of the initial lanelet to the end of the lane change lanelet as expected by the route definition. Returned points are always inclusive of provided bounds, so the last step might be less than step_size. More... | |
virtual boost::optional< lanelet::BasicPoint2d > | pointFromRouteTrackPos (const TrackPos &route_pos) const =0 |
Converts a route track position into a map frame cartesian point. More... | |
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 reacquired. More... | |
virtual LaneletRouteConstPtr | getRoute () const =0 |
Get a pointer to the current route. If the underlying route has changed the pointer will also need to be reacquired. More... | |
virtual std::string | getRouteName () const =0 |
Get the current route name. More... | |
virtual TrackPos | getRouteEndTrackPos () const =0 |
Get trackpos of the end of route point relative to the route. More... | |
virtual LaneletRoutingGraphConstPtr | getMapRoutingGraph () const =0 |
Get a pointer to the routing graph for the current map. If the underlying map has changed the pointer will also need to be reacquired. More... | |
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. More... | |
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 system default. More... | |
virtual lanelet::Optional< TrafficRulesConstPtr > | getTrafficRules () const =0 |
Get the Traffic Rules object. More... | |
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. Can also be used to determine if the object is on the roadway. More... | |
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. If it's across multiple lanelets, get the closest one. More... | |
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 ahead of us on the route specifically, so a sorted list (by downtrack distance) of bus stop on the route ahead of us thus eliminating those behind the vehicle. More... | |
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. More... | |
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. More... | |
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. Also returns crosstrack distance relative to that object. Plus downtrack if the object is ahead along the lane, and also plus crosstrack if the object is to the right relative to the reference line that crosses given object_center and is parallel to the centerline of the lane. More... | |
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. Also returns crosstrack distance relative to that object. Plus downtrack if the object is ahead along the lane, and also plus crosstrack if the object is to the right relative to the reference line that crosses given object_center and is parallel to the centerline of the lane. More... | |
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, that includes the given lanelet. More... | |
virtual size_t | getMapVersion () const =0 |
Returns a monotonically increasing version number which represents the version stamp of the map geometry data It is possible for the non-geometric aspects of the map to change without this value increasing. More... | |
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. More... | |
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 route and the next traffic light ahead of us on the route specifically, so a sorted list (by downtrack distance) of traffic lights on the route ahead of us thus eliminating those behind the vehicle. More... | |
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. This is useful if traffic_signal controls both directions in an intersection for example. More... | |
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 along a route and the next all way stop intersections ahead of us on the route specifically, so a sorted list (by downtrack distance) of all way stop intersections on the route ahead of us thus eliminating those behind the vehicle. More... | |
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 a route and the next signalized intersections ahead of us on the route specifically, so a sorted list (by downtrack distance) of signalized intersections on the route ahead of us thus eliminating those behind the vehicle. More... | |
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 function is intended to find "adjacentLeft lanelets" that doesn't share points between lanelets where adjacentLeft of lanelet library fails. More... | |
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 lanelet possible on the shortest path. More... | |
An interface which provides read access to the semantic map and route. This class is not thread safe. All units of distance are in meters.
Utility functions are provided by this interface for functionality not present in the lanelet2 library such as computing downtrack and crosstrack distances or road curvatures.
Definition at line 72 of file WorldModel.hpp.
|
inlinevirtual |
Virtual destructor to ensure delete safety for pointers to implementing classes.
Definition at line 79 of file WorldModel.hpp.
|
pure virtual |
Gets Cartesian distance to the closest object on the same lane as the given point.
object_center | the point to measure the distance from |
std::invalid_argument | if the map is not set, contains no lanelets, or the given point is not on the current semantic map |
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Return a list of bus stop along the current route. The bus stop along a route and the next bus stop ahead of us on the route specifically, so a sorted list (by downtrack distance) of bus stop on the route ahead of us thus eliminating those behind the vehicle.
loc | location |
std::invalid_argument | if the map is not set, contains no lanelets, or route is not set |
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Returns the entry and exit lanelet of the signal along the SHORTEST PATH of route. This is useful if traffic_signal controls both directions in an intersection for example.
traffic_signal | traffic signal of interest |
std::invalid_argument | if nullptr is passed in traffic_signal |
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Given the vector of lanelets, returns the lanelet that's on the shortest path. Returns earliest lanelet possible on the shortest path.
lanelets_to_filter | lanelets to pick from |
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Gets all roadway objects currently in the same lane as the given lanelet.
lanelet | the lanelet that is part of the continuous lane |
section | either of LANE_AHEAD, LANE_BEHIND, LANE_FULL each including the current lanelet |
std::invalid_argument | if the map is not set, contains no lanelets, or if the given lanelet is not on the current semantic map, or lane section input is not of the three |
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Gets the a lanelet the object is currently on determined by its position on the semantic map. If it's across multiple lanelets, get the closest one.
object | the external object to get the lanelet of |
std::invalid_argument | if the map is not set or contains no lanelets |
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Return a list of all way stop intersections along the current route. The tall way stop intersections along a route and the next all way stop intersections ahead of us on the route specifically, so a sorted list (by downtrack distance) of all way stop intersections on the route ahead of us thus eliminating those behind the vehicle.
loc | location |
std::invalid_argument | if the map is not set, contains no lanelets, or route is not set |
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Gets the specified lane section achievable without lane change, sorted from the start, that includes the given lanelet.
lanelet | the lanelet to get the full lane of |
section | either of LANE_AHEAD, LANE_BEHIND, LANE_FULL each including the current lanelet |
std::invalid_argument | if the map is not set, contains no lanelets, or the given lanelet is not on the current semantic map, or lane section input is not of the three |
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Returns a list of lanelets which are part of the route and whose downtrack bounds exist within the provided start and end distances.
start | The starting downtrack for the query |
end | The ending downtrack for the query. |
shortest_path_only | If true the lanelets returned will be part of the route shortest path param bounds_inclusive If true, the bounds are included so areas which end exactly at start or start exactly at end are included. NOTE: Non-inclusive behavior toggled by !bounds_inclusive is not equivalent to a != check as it merely shrinks bounds by 0.00001 to get new start and end distances. |
std::invalid_argument | If the route is not yet loaded or if start > end |
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Gets the underlying lanelet, given the cartesian point on the map.
point | Cartesian point to check the corressponding lanelet |
n | Number of lanelets to return. Default is 10. As there could be many lanelets overlapping. |
std::invalid_argument | if the map is not set, contains no lanelets |
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Get a pointer to the current map. If the underlying map has changed the pointer will also need to be reacquired.
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Get a pointer to the routing graph for the current map. If the underlying map has changed the pointer will also need to be reacquired.
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Returns a monotonically increasing version number which represents the version stamp of the map geometry data It is possible for the non-geometric aspects of the map to change without this value increasing.
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Get most recent roadway objects - all objects on the road detected by perception stack.
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Get a pointer to the current route. If the underlying route has changed the pointer will also need to be reacquired.
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Get trackpos of the end of route point relative to the route.
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Get the current route name.
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Return a list of signalized intersections along the current route. The signalized intersections along a route and the next signalized intersections ahead of us on the route specifically, so a sorted list (by downtrack distance) of signalized intersections on the route ahead of us thus eliminating those behind the vehicle.
loc | location |
std::invalid_argument | if the map is not set, contains no lanelets, or route is not set |
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Return a list of traffic lights/intersections along the current route. The traffic lights along a route and the next traffic light ahead of us on the route specifically, so a sorted list (by downtrack distance) of traffic lights on the route ahead of us thus eliminating those behind the vehicle.
loc | location |
std::invalid_argument | if the map is not set, contains no lanelets, or route is not set |
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Get the Traffic Rules object.
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Get a pointer to the traffic rules object used internally by the world model and considered the carma system default.
participant | The lanelet participant to return the traffic rules object for. Defaults to a generic vehicle |
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Gets Downtrack distance to AND copy of the closest object AHEAD on the same lane as the given point. Also returns crosstrack distance relative to that object. Plus downtrack if the object is ahead along the lane, and also plus crosstrack if the object is to the right relative to the reference line that crosses given object_center and is parallel to the centerline of the lane.
object_center | the point to measure the distance from |
std::invalid_argument | if the map is not set, contains no lanelets, or the given point is not on the current semantic map |
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Gets Downtrack distance to AND copy of the closest object BEHIND on the same lane as the given point. Also returns crosstrack distance relative to that object. Plus downtrack if the object is ahead along the lane, and also plus crosstrack if the object is to the right relative to the reference line that crosses given object_center and is parallel to the centerline of the lane.
object_center | the point to measure the distance from |
std::invalid_argument | if the map is not set, contains no lanelets, or the given point is not on the current semantic map |
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Given the cartesian point on the map, tries to get the opposite direction lanelet on the left This function is intended to find "adjacentLeft lanelets" that doesn't share points between lanelets where adjacentLeft of lanelet library fails.
semantic_map | Lanelet Map Ptr |
point | Cartesian point to check the corressponding lanelet |
n | Number of lanelets to return. Default is 10. As there could be many lanelets overlapping. |
std::invalid_argument | if the map is not set, contains no lanelets, or if adjacent lanelet is not opposite direction NOTE: Only to be used on 2 lane, opposite direction road. Number of points in all linestrings are assumed to be roughly the same. The point is assumed to be on roughly similar shape of overlapping lanelets if any |
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Converts a route track position into a map frame cartesian point.
route_pos | The TrackPos to convert to and x,y point. This position should be relative to the route |
NOTE: This method will run faster if the crosstrack is unset or set to 0. The default implementation lookup has complexity O(log n) where n is the number of lane changes is a route + 1
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Returns the TrackPos, computed in 2d, of the provided point relative to the current route.
NOTE: The route definition used in this class contains discontinuities in the reference line at lane changes. It is important to consider that when using route related functions.
point | The lanelet2 point which will have its distance computed |
std::invalid_argument | If the route is not yet loaded |
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Returns a pair of TrackPos, computed in 2d, of the provided area relative to the current route. The distance is based on the Area vertex with the smallest and largest downtrack distance This method overload is the most expensive of the routeTrackPos methods.
NOTE: The route definition used in this class contains discontinuities in the reference line at lane changes. It is important to consider that when using route related functions.
area | The lanelet2 area which will have its distance computed |
std::invalid_argument | If the route is not yet loaded or the area does not contain vertices |
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Returns the TrackPos, computed in 2d, of the provided lanelet relative to the current route. The distance is based on the first point in the lanelet centerline.
NOTE: The route definition used in this class contains discontinuities in the reference line at lane changes. It is important to consider that when using route related functions.
lanelet | The lanelet2 lanelet which will have its distance computed |
std::invalid_argument | If the route is not yet loaded or the lanelet centerline cannot be found |
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Samples the route centerline between the provided downtracks with the provided step size. At lane changes the points should exhibit a discontinuous jump at the end of the initial lanelet to the end of the lane change lanelet as expected by the route definition. Returned points are always inclusive of provided bounds, so the last step might be less than step_size.
NOTE: If start_downtrack == end_downtrack a single point is returned. If the route is not set or the bounds lie outside the route an empty vector is returned.
In the default implementation, this method has m * O(log n) complexity where n is the number of lane changes in the route + 1 and m is the number of sampled points which is nominally 1 + ((start_downtrack - end_downtrack) / step_size). Since the route is fixed for the duration of method execution this can generally be thought of as a linear complexity call dominated by m.
start_downtrack | The starting route downtrack to sample from in meters |
end_downtrack | The ending downtrack to stop sampling at in meters |
step_size | The sampling step size in meters. |
NOTE: This method really needs clarification of behavior for lane changes.
Implemented in carma_wm::CARMAWorldModel.
|
pure virtual |
Converts an ExternalObject in a RoadwayObstacle by mapping its position onto the semantic map. Can also be used to determine if the object is on the roadway.
object | the external object to convert |
std::invalid_argument | if the map is not set or contains no lanelets |
Implemented in carma_wm::CARMAWorldModel.