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.
carma_wm::WorldModel Class Referenceabstract

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>

Inheritance diagram for carma_wm::WorldModel:
Inheritance graph
Collaboration diagram for carma_wm::WorldModel:
Collaboration graph

Public Member Functions

virtual ~WorldModel ()
 Virtual destructor to ensure delete safety for pointers to implementing classes. More...
 
virtual std::pair< TrackPos, TrackPosrouteTrackPos (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< TrafficRulesConstPtrgetTrafficRules (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< TrafficRulesConstPtrgetTrafficRules () 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 &section=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 &section=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...
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ ~WorldModel()

virtual carma_wm::WorldModel::~WorldModel ( )
inlinevirtual

Virtual destructor to ensure delete safety for pointers to implementing classes.

Definition at line 79 of file WorldModel.hpp.

79{};

Member Function Documentation

◆ distToNearestObjInLane()

virtual lanelet::Optional< double > carma_wm::WorldModel::distToNearestObjInLane ( const lanelet::BasicPoint2d &  object_center) const
pure virtual

Gets Cartesian distance to the closest object on the same lane as the given point.

Parameters
object_centerthe point to measure the distance from
Exceptions
std::invalid_argumentif the map is not set, contains no lanelets, or the given point is not on the current semantic map
Returns
An optional Cartesian distance in double to the closest in lane object. Return empty if there is no objects on current lane or the road

Implemented in carma_wm::CARMAWorldModel.

◆ getBusStopsAlongRoute()

virtual std::vector< lanelet::BusStopRulePtr > carma_wm::WorldModel::getBusStopsAlongRoute ( const lanelet::BasicPoint2d &  loc) const
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.

Parameters
loclocation
Exceptions
std::invalid_argumentif the map is not set, contains no lanelets, or route is not set
Returns
list of bus stop along the current route

Implemented in carma_wm::CARMAWorldModel.

◆ getEntryExitOfSignalAlongRoute()

virtual boost::optional< std::pair< lanelet::ConstLanelet, lanelet::ConstLanelet > > carma_wm::WorldModel::getEntryExitOfSignalAlongRoute ( const lanelet::CarmaTrafficSignalPtr &  traffic_signal) const
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.

Parameters
traffic_signaltraffic signal of interest
Exceptions
std::invalid_argumentif nullptr is passed in traffic_signal
Returns
pair of entry and exit lanelet of the signal along the route. boost::none if the given signal doesn't have both entry/exit pair along the shortest path route.

Implemented in carma_wm::CARMAWorldModel.

◆ getFirstLaneletOnShortestPath()

virtual std::optional< lanelet::ConstLanelet > carma_wm::WorldModel::getFirstLaneletOnShortestPath ( const std::vector< lanelet::ConstLanelet > &  lanelets_to_filter) const
pure virtual

Given the vector of lanelets, returns the lanelet that's on the shortest path. Returns earliest lanelet possible on the shortest path.

Parameters
lanelets_to_filterlanelets to pick from
Returns
the first lanelet on the shortest path from the input list. std::nullopt if no route is available or no lanelet is on the route

Implemented in carma_wm::CARMAWorldModel.

◆ getInLaneObjects()

virtual std::vector< carma_perception_msgs::msg::RoadwayObstacle > carma_wm::WorldModel::getInLaneObjects ( const lanelet::ConstLanelet &  lanelet,
const LaneSection section = LANE_AHEAD 
) const
pure virtual

Gets all roadway objects currently in the same lane as the given lanelet.

Parameters
laneletthe lanelet that is part of the continuous lane
sectioneither of LANE_AHEAD, LANE_BEHIND, LANE_FULL each including the current lanelet
Exceptions
std::invalid_argumentif 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
Returns
A vector of RoadwayObstacle objects that is on the current lane. Return empty vector if there is no objects on current lane or the road

Implemented in carma_wm::CARMAWorldModel.

◆ getIntersectingLanelet()

virtual lanelet::Optional< lanelet::Lanelet > carma_wm::WorldModel::getIntersectingLanelet ( const carma_perception_msgs::msg::ExternalObject &  object) const
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.

Parameters
objectthe external object to get the lanelet of
Exceptions
std::invalid_argumentif the map is not set or contains no lanelets
Returns
An optional lanelet primitive that is on the semantic map. If the external object is not on the roadway then the optional will be empty.

Implemented in carma_wm::CARMAWorldModel.

◆ getIntersectionsAlongRoute()

virtual std::vector< std::shared_ptr< lanelet::AllWayStop > > carma_wm::WorldModel::getIntersectionsAlongRoute ( const lanelet::BasicPoint2d &  loc) const
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.

Parameters
loclocation
Exceptions
std::invalid_argumentif the map is not set, contains no lanelets, or route is not set
Returns
list of all way stop intersections along the current route

Implemented in carma_wm::CARMAWorldModel.

◆ getLane()

virtual std::vector< lanelet::ConstLanelet > carma_wm::WorldModel::getLane ( const lanelet::ConstLanelet &  lanelet,
const LaneSection section = LANE_AHEAD 
) const
pure virtual

Gets the specified lane section achievable without lane change, sorted from the start, that includes the given lanelet.

Parameters
laneletthe lanelet to get the full lane of
sectioneither of LANE_AHEAD, LANE_BEHIND, LANE_FULL each including the current lanelet
Exceptions
std::invalid_argumentif 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
Returns
An optional vector of ConstLanalet. Returns at least the vector of given lanelet if no other is found

Implemented in carma_wm::CARMAWorldModel.

◆ getLaneletsBetween()

virtual std::vector< lanelet::ConstLanelet > carma_wm::WorldModel::getLaneletsBetween ( double  start,
double  end,
bool  shortest_path_only = false,
bool  bounds_inclusive = true 
) const
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.

Parameters
startThe starting downtrack for the query
endThe ending downtrack for the query.
shortest_path_onlyIf 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.
Exceptions
std::invalid_argumentIf the route is not yet loaded or if start > end
Returns
A list of lanelets which contain regions that lie between start and end along the route. This function will not return lanelets which are not part of the route

Implemented in carma_wm::CARMAWorldModel.

◆ getLaneletsFromPoint()

virtual std::vector< lanelet::ConstLanelet > carma_wm::WorldModel::getLaneletsFromPoint ( const lanelet::BasicPoint2d &  point,
const unsigned int  n = 10 
) const
pure virtual

Gets the underlying lanelet, given the cartesian point on the map.

Parameters
pointCartesian point to check the corressponding lanelet
nNumber of lanelets to return. Default is 10. As there could be many lanelets overlapping.
Exceptions
std::invalid_argumentif the map is not set, contains no lanelets
Returns
vector of underlying lanelet, empty vector if it is not part of any lanelet

Implemented in carma_wm::CARMAWorldModel.

◆ getMap()

virtual lanelet::LaneletMapConstPtr carma_wm::WorldModel::getMap ( ) const
pure virtual

Get a pointer to the current map. If the underlying map has changed the pointer will also need to be reacquired.

Returns
Shared pointer to underlying lanelet map. Pointer will return false on boolean check if no map is loaded

Implemented in carma_wm::CARMAWorldModel.

◆ getMapRoutingGraph()

virtual LaneletRoutingGraphConstPtr carma_wm::WorldModel::getMapRoutingGraph ( ) const
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.

Returns
Shared pointer to underlying lanelet route graph. Pointer will return false on boolean check if no map is loaded

Implemented in carma_wm::CARMAWorldModel.

◆ getMapVersion()

virtual size_t carma_wm::WorldModel::getMapVersion ( ) const
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.

Returns
map version

Implemented in carma_wm::CARMAWorldModel.

◆ getRoadwayObjects()

virtual std::vector< carma_perception_msgs::msg::RoadwayObstacle > carma_wm::WorldModel::getRoadwayObjects ( ) const
pure virtual

Get most recent roadway objects - all objects on the road detected by perception stack.

Returns
Vector list of RoadwayObstacle which are lanelet compatible. Empty vector if no object found.

Implemented in carma_wm::CARMAWorldModel.

◆ getRoute()

virtual LaneletRouteConstPtr carma_wm::WorldModel::getRoute ( ) const
pure virtual

Get a pointer to the current route. If the underlying route has changed the pointer will also need to be reacquired.

Returns
Shared pointer to underlying lanelet route. Pointer will return false on boolean check if no route or map is loaded

Implemented in carma_wm::CARMAWorldModel.

◆ getRouteEndTrackPos()

virtual TrackPos carma_wm::WorldModel::getRouteEndTrackPos ( ) const
pure virtual

Get trackpos of the end of route point relative to the route.

Returns
Trackpos

Implemented in carma_wm::CARMAWorldModel.

◆ getRouteName()

virtual std::string carma_wm::WorldModel::getRouteName ( ) const
pure virtual

Get the current route name.

Returns
A string that matches the name of the current route.

Implemented in carma_wm::CARMAWorldModel.

◆ getSignalizedIntersectionsAlongRoute()

virtual std::vector< lanelet::SignalizedIntersectionPtr > carma_wm::WorldModel::getSignalizedIntersectionsAlongRoute ( const lanelet::BasicPoint2d &  loc) const
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.

Parameters
loclocation
Exceptions
std::invalid_argumentif the map is not set, contains no lanelets, or route is not set
Returns
list of signalized intersections along the current route

Implemented in carma_wm::CARMAWorldModel.

◆ getSignalsAlongRoute()

virtual std::vector< lanelet::CarmaTrafficSignalPtr > carma_wm::WorldModel::getSignalsAlongRoute ( const lanelet::BasicPoint2d &  loc) const
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.

Parameters
loclocation
Exceptions
std::invalid_argumentif the map is not set, contains no lanelets, or route is not set
Returns
list of traffic lights along the current route

Implemented in carma_wm::CARMAWorldModel.

◆ getTrafficRules() [1/2]

virtual lanelet::Optional< TrafficRulesConstPtr > carma_wm::WorldModel::getTrafficRules ( ) const
pure virtual

Get the Traffic Rules object.

Returns
Optional Shared pointer to an intialized traffic rules object which is used by carma. A default participant value will be used in case setVehicleParticipationType is not called. Acceptable participants are Vehicle, VehicleCar, and VehicleTruck

Implemented in carma_wm::CARMAWorldModel.

◆ getTrafficRules() [2/2]

virtual lanelet::Optional< TrafficRulesConstPtr > carma_wm::WorldModel::getTrafficRules ( const std::string &  participant) const
pure virtual

Get a pointer to the traffic rules object used internally by the world model and considered the carma system default.

Parameters
participantThe lanelet participant to return the traffic rules object for. Defaults to a generic vehicle
Returns
Optional Shared pointer to an intialized traffic rules object which is used by carma. Optional is false if no rule set is available for the requested participant.

Implemented in carma_wm::CARMAWorldModel.

◆ nearestObjectAheadInLane()

virtual lanelet::Optional< std::tuple< TrackPos, carma_perception_msgs::msg::RoadwayObstacle > > carma_wm::WorldModel::nearestObjectAheadInLane ( const lanelet::BasicPoint2d &  object_center) const
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.

Parameters
object_centerthe point to measure the distance from
Exceptions
std::invalid_argumentif the map is not set, contains no lanelets, or the given point is not on the current semantic map
Returns
An optional tuple of <TrackPos, carma_perception_msgs::msg::RoadwayObstacle> to the closest in lane object AHEAD. Return empty if there is no objects on current lane or the road

Implemented in carma_wm::CARMAWorldModel.

◆ nearestObjectBehindInLane()

virtual lanelet::Optional< std::tuple< TrackPos, carma_perception_msgs::msg::RoadwayObstacle > > carma_wm::WorldModel::nearestObjectBehindInLane ( const lanelet::BasicPoint2d &  object_center) const
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.

Parameters
object_centerthe point to measure the distance from
Exceptions
std::invalid_argumentif the map is not set, contains no lanelets, or the given point is not on the current semantic map
Returns
An optional tuple of <TrackPos, carma_perception_msgs::msg::RoadwayObstacle> to the closest in lane object BEHIND. Return empty if there is no objects on current lane or the road

Implemented in carma_wm::CARMAWorldModel.

◆ nonConnectedAdjacentLeft()

virtual std::vector< lanelet::ConstLanelet > carma_wm::WorldModel::nonConnectedAdjacentLeft ( const lanelet::BasicPoint2d &  input_point,
const unsigned int  n = 10 
) const
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.

Parameters
semantic_mapLanelet Map Ptr
pointCartesian point to check the corressponding lanelet
nNumber of lanelets to return. Default is 10. As there could be many lanelets overlapping.
Exceptions
std::invalid_argumentif 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
Returns
vector of underlying lanelet, empty vector if it is not part of any lanelet

Implemented in carma_wm::CARMAWorldModel.

◆ pointFromRouteTrackPos()

virtual boost::optional< lanelet::BasicPoint2d > carma_wm::WorldModel::pointFromRouteTrackPos ( const TrackPos route_pos) const
pure virtual

Converts a route track position into a map frame cartesian point.

Parameters
route_posThe TrackPos to convert to and x,y point. This position should be relative to the route
Returns
If the provided downtrack position is not within the route bounds or the route is not set then boost::none is returned. Otherwise the point is converted to x,y.

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.

◆ routeTrackPos() [1/3]

virtual TrackPos carma_wm::WorldModel::routeTrackPos ( const lanelet::BasicPoint2d &  point) const
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.

Parameters
pointThe lanelet2 point which will have its distance computed
Exceptions
std::invalid_argumentIf the route is not yet loaded
Returns
The TrackPos of the point

Implemented in carma_wm::CARMAWorldModel.

◆ routeTrackPos() [2/3]

virtual std::pair< TrackPos, TrackPos > carma_wm::WorldModel::routeTrackPos ( const lanelet::ConstArea &  area) const
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.

Parameters
areaThe lanelet2 area which will have its distance computed
Exceptions
std::invalid_argumentIf the route is not yet loaded or the area does not contain vertices
Returns
A pair where the first element contains the TrackPos area's earliest downtrack vertex and the second element contains the area's latest downtrack point

Implemented in carma_wm::CARMAWorldModel.

◆ routeTrackPos() [3/3]

virtual TrackPos carma_wm::WorldModel::routeTrackPos ( const lanelet::ConstLanelet &  lanelet) const
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.

Parameters
laneletThe lanelet2 lanelet which will have its distance computed
Exceptions
std::invalid_argumentIf the route is not yet loaded or the lanelet centerline cannot be found
Returns
The TrackPos containing the downtrack and crosstrack location of the lanelet's first centerline point

Implemented in carma_wm::CARMAWorldModel.

◆ sampleRoutePoints()

virtual std::vector< lanelet::BasicPoint2d > carma_wm::WorldModel::sampleRoutePoints ( double  start_downtrack,
double  end_downtrack,
double  step_size 
) const
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.

Parameters
start_downtrackThe starting route downtrack to sample from in meters
end_downtrackThe ending downtrack to stop sampling at in meters
step_sizeThe sampling step size in meters.
Returns
The sampled x,y points

NOTE: This method really needs clarification of behavior for lane changes.

Implemented in carma_wm::CARMAWorldModel.

◆ toRoadwayObstacle()

virtual lanelet::Optional< carma_perception_msgs::msg::RoadwayObstacle > carma_wm::WorldModel::toRoadwayObstacle ( const carma_perception_msgs::msg::ExternalObject &  object) const
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.

Parameters
objectthe external object to convert
Exceptions
std::invalid_argumentif the map is not set or contains no lanelets
Returns
An optional RoadwayObstacle message created from the provided object. If the external object is not on the roadway then the optional will be empty.

Implemented in carma_wm::CARMAWorldModel.


The documentation for this class was generated from the following file: