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::CARMAWorldModel Class Reference

Class which implements the WorldModel interface. In addition this class provides write access to the world model. Write access is achieved through setters for the Map and Route and getMutableMap(). NOTE: This class should NOT be used in runtime code by users and is exposed solely for use in unit tests where the WMListener class cannot be instantiated. More...

#include <CARMAWorldModel.hpp>

Inheritance diagram for carma_wm::CARMAWorldModel:
Inheritance graph
Collaboration diagram for carma_wm::CARMAWorldModel:
Collaboration graph

Public Member Functions

 CARMAWorldModel ()=default
 Constructor. More...
 
 ~CARMAWorldModel ()=default
 Destructor as required by interface. More...
 
void setMap (lanelet::LaneletMapPtr map, size_t map_version=0, bool recompute_routing_graph=true)
 Set the current map. More...
 
void setRoutingGraph (LaneletRoutingGraphPtr graph)
 Set the routing graph for the participant type. This function may serve as an optimization to recomputing the routing graph when it is already available. More...
 
void setRoute (LaneletRoutePtr route)
 Set the current route. This route must match the current map for this class to function properly. More...
 
void setTrafficLightIds (uint32_t id, lanelet::Id lanelet_id)
 Sets the id mapping between intersection/signal group and lanelet::Id for traffic lights in the map. More...
 
lanelet::LaneletMapPtr getMutableMap () const
 Get a mutable version of the current map. More...
 
void setRoadwayObjects (const std::vector< carma_perception_msgs::msg::RoadwayObstacle > &rw_objs)
 Update internal records of roadway objects. These objects MUST be guaranteed to be on the road. More...
 
void processSpatFromMsg (const carma_v2x_msgs::msg::SPAT &spat_msg, bool use_sim_time=false, bool is_spat_wall_time=true)
 processSpatFromMsg update map's traffic light states with SPAT msg More...
 
lanelet::Optional< std::tuple< TrackPos, carma_perception_msgs::msg::RoadwayObstacle > > getNearestObjInLane (const lanelet::BasicPoint2d &object_center, const LaneSection &section=LANE_AHEAD) const
 This function is called by distanceToObjectBehindInLane or distanceToObjectAheadInLane. Gets Downtrack distance to AND copy of the closest object 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...
 
boost::posix_time::ptime min_end_time_converter_minute_of_year (boost::posix_time::ptime min_end_time, bool moy_exists, uint32_t moy=0, bool is_simulation=true, bool is_spat_wall_time=false)
 update minimum end time to account for minute of the year More...
 
void setConfigSpeedLimit (double config_lim)
 
void setVehicleParticipationType (const std::string &participant)
 Set vehicle participation type. More...
 
std::string getVehicleParticipationType ()
 Get vehicle participation type. More...
 
void setRouteEndPoint (const lanelet::BasicPoint3d &end_point)
 Set endpoint of the route. More...
 
void setRouteName (const std::string &route_name)
 Set the name of the route. More...
 
void setRos1Clock (const rclcpp::Time &time_now)
 Set current Ros1 clock (only used in simulation runs) More...
 
void setSimulationClock (const rclcpp::Time &time_now)
 Set simulation clock clock (only used in simulation runs) More...
 
lanelet::Id getTrafficSignalId (uint16_t intersection_id, uint8_t signal_id)
 helper for traffic signal Id More...
 
lanelet::CarmaTrafficSignalPtr getTrafficSignal (const lanelet::Id &id) const
 helper for getting traffic signal with given lanelet::Id More...
 
std::vector< lanelet::Lanelet > getLaneletsFromPoint (const lanelet::BasicPoint2d &point, const unsigned int n)
 (non-const version) Gets the underlying lanelet, given the cartesian point on the map More...
 
std::vector< lanelet::Lanelet > nonConnectedAdjacentLeft (const lanelet::BasicPoint2d &input_point, const unsigned int n=10)
 (non-const version) 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...
 
std::pair< TrackPos, TrackPosrouteTrackPos (const lanelet::ConstArea &area) const override
 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...
 
TrackPos routeTrackPos (const lanelet::ConstLanelet &lanelet) const override
 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...
 
TrackPos routeTrackPos (const lanelet::BasicPoint2d &point) const override
 Returns the TrackPos, computed in 2d, of the provided point relative to the current route. More...
 
std::vector< lanelet::ConstLanelet > getLaneletsBetween (double start, double end, bool shortest_path_only=false, bool bounds_inclusive=true) const override
 Returns a list of lanelets which are part of the route and whose downtrack bounds exist within the provided start and end distances. More...
 
std::vector< lanelet::BasicPoint2d > sampleRoutePoints (double start_downtrack, double end_downtrack, double step_size) const override
 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...
 
boost::optional< lanelet::BasicPoint2d > pointFromRouteTrackPos (const TrackPos &route_pos) const override
 Converts a route track position into a map frame cartesian point. More...
 
lanelet::LaneletMapConstPtr getMap () const override
 Get a pointer to the current map. If the underlying map has changed the pointer will also need to be reacquired. More...
 
LaneletRouteConstPtr getRoute () const override
 Get a pointer to the current route. If the underlying route has changed the pointer will also need to be reacquired. More...
 
std::string getRouteName () const override
 Get the current route name. More...
 
TrackPos getRouteEndTrackPos () const override
 Get trackpos of the end of route point relative to the route. More...
 
LaneletRoutingGraphConstPtr getMapRoutingGraph () const override
 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...
 
lanelet::Optional< TrafficRulesConstPtrgetTrafficRules (const std::string &participant) const override
 Get a pointer to the traffic rules object used internally by the world model and considered the carma system default. More...
 
lanelet::Optional< TrafficRulesConstPtrgetTrafficRules () const override
 Get the Traffic Rules object. More...
 
std::vector< carma_perception_msgs::msg::RoadwayObstacle > getRoadwayObjects () const override
 Get most recent roadway objects - all objects on the road detected by perception stack. More...
 
std::vector< carma_perception_msgs::msg::RoadwayObstacle > getInLaneObjects (const lanelet::ConstLanelet &lanelet, const LaneSection &section=LANE_AHEAD) const override
 Gets all roadway objects currently in the same lane as the given lanelet. More...
 
lanelet::Optional< lanelet::Lanelet > getIntersectingLanelet (const carma_perception_msgs::msg::ExternalObject &object) const override
 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...
 
lanelet::Optional< carma_perception_msgs::msg::RoadwayObstacle > toRoadwayObstacle (const carma_perception_msgs::msg::ExternalObject &object) const override
 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...
 
lanelet::Optional< double > distToNearestObjInLane (const lanelet::BasicPoint2d &object_center) const override
 Gets Cartesian distance to the closest object on the same lane as the given point. More...
 
lanelet::Optional< std::tuple< TrackPos, carma_perception_msgs::msg::RoadwayObstacle > > nearestObjectAheadInLane (const lanelet::BasicPoint2d &object_center) const override
 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...
 
lanelet::Optional< std::tuple< TrackPos, carma_perception_msgs::msg::RoadwayObstacle > > nearestObjectBehindInLane (const lanelet::BasicPoint2d &object_center) const override
 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...
 
std::vector< lanelet::ConstLanelet > getLane (const lanelet::ConstLanelet &lanelet, const LaneSection &section=LANE_AHEAD) const override
 Gets the specified lane section achievable without lane change, sorted from the start, that includes the given lanelet. More...
 
size_t getMapVersion () const override
 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...
 
std::vector< lanelet::ConstLanelet > getLaneletsFromPoint (const lanelet::BasicPoint2d &point, const unsigned int n=10) const override
 Gets the underlying lanelet, given the cartesian point on the map. More...
 
std::vector< lanelet::ConstLanelet > nonConnectedAdjacentLeft (const lanelet::BasicPoint2d &input_point, const unsigned int n=10) const override
 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...
 
std::vector< lanelet::CarmaTrafficSignalPtr > getSignalsAlongRoute (const lanelet::BasicPoint2d &loc) const override
 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...
 
std::vector< lanelet::BusStopRulePtr > getBusStopsAlongRoute (const lanelet::BasicPoint2d &loc) const override
 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...
 
boost::optional< std::pair< lanelet::ConstLanelet, lanelet::ConstLanelet > > getEntryExitOfSignalAlongRoute (const lanelet::CarmaTrafficSignalPtr &traffic_signal) const override
 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...
 
std::vector< std::shared_ptr< lanelet::AllWayStop > > getIntersectionsAlongRoute (const lanelet::BasicPoint2d &loc) const override
 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...
 
std::vector< lanelet::SignalizedIntersectionPtr > getSignalizedIntersectionsAlongRoute (const lanelet::BasicPoint2d &loc) const
 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...
 
std::optional< lanelet::ConstLanelet > getFirstLaneletOnShortestPath (const std::vector< lanelet::ConstLanelet > &lanelets_to_filter) const
 Given the vector of lanelets, returns the lanelet that's on the shortest path. Returns earliest lanelet possible on the shortest path. More...
 
- Public Member Functions inherited from carma_wm::WorldModel
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...
 

Public Attributes

std::unordered_map< uint32_t, lanelet::Id > traffic_light_ids_
 
carma_wm::SignalizedIntersectionManager sim_
 

Private Member Functions

void computeDowntrackReferenceLine ()
 Helper function to compute the geometry of the route downtrack/crosstrack reference line This function should generally only be called from inside the setRoute function as it uses member variables set in that function. More...
 
lanelet::LineString3d copyConstructLineString (const lanelet::ConstLineString3d &line) const
 Helper function to perform a deep copy of a LineString and assign new ids to all the elements. Used during route centerline construction. More...
 
 FRIEND_TEST (CARMAWorldModelTest, getFirstLaneletOnShortestPath)
 

Private Attributes

double config_speed_limit_
 
std::string participant_type_ = lanelet::Participants::Vehicle
 
std::optional< rclcpp::Time > ros1_clock_ = std::nullopt
 
std::optional< rclcpp::Time > simulation_clock_ = std::nullopt
 
std::shared_ptr< lanelet::LaneletMap > semantic_map_
 
LaneletRoutePtr route_
 
LaneletRoutingGraphPtr map_routing_graph_
 
double route_length_ = 0
 
lanelet::LaneletSubmapConstUPtr shortest_path_view_
 
std::vector< lanelet::LineString3d > shortest_path_centerlines_
 
IndexedDistanceMap shortest_path_distance_map_
 
lanelet::LaneletMapUPtr shortest_path_filtered_centerline_view_
 
std::vector< carma_perception_msgs::msg::RoadwayObstacle > roadway_objects_
 
size_t map_version_ = 0
 
std::string route_name_
 

Static Private Attributes

static constexpr double RED_LIGHT_DURATION = 20.0
 
static constexpr double YELLOW_LIGHT_DURATION = 3.0
 
static constexpr double GREEN_LIGHT_DURATION = 20.0
 

Detailed Description

Class which implements the WorldModel interface. In addition this class provides write access to the world model. Write access is achieved through setters for the Map and Route and getMutableMap(). NOTE: This class should NOT be used in runtime code by users and is exposed solely for use in unit tests where the WMListener class cannot be instantiated.

Proper usage of this class dictates that the Map and Route object be kept in sync. For this reason normal WorldModel users should not try to construct this class directly unless in unit tests.

NOTE: This class uses the CarmaUSTrafficRules class internally to interpret routes. So routes which are set on this model should use the getTrafficRules() method to build using the correct rule set

Definition at line 48 of file CARMAWorldModel.hpp.

Constructor & Destructor Documentation

◆ CARMAWorldModel()

carma_wm::CARMAWorldModel::CARMAWorldModel ( )
default

Constructor.

◆ ~CARMAWorldModel()

carma_wm::CARMAWorldModel::~CARMAWorldModel ( )
default

Destructor as required by interface.

Member Function Documentation

◆ computeDowntrackReferenceLine()

void carma_wm::CARMAWorldModel::computeDowntrackReferenceLine ( )
private

Helper function to compute the geometry of the route downtrack/crosstrack reference line This function should generally only be called from inside the setRoute function as it uses member variables set in that function.

Sets the shortest_path_centerlines_, shortest_path_centerlines_lengths_, and shortest_path_filtered_centerline_view_ member variables

Definition at line 675 of file CARMAWorldModel.cpp.

676 {
677 IndexedDistanceMap distance_map;
678
679 lanelet::routing::LaneletPath shortest_path = route_->shortestPath();
680 // Build shortest path routing graph
682
683 lanelet::routing::RoutingGraphUPtr shortest_path_graph =
684 lanelet::routing::RoutingGraph::build(*shortest_path_view_, *traffic_rules);
685
686 std::vector<lanelet::LineString3d> lineStrings; // List of continuos line strings representing segments of the route
687 // reference line
688
689 bool first = true;
690 size_t next_index = 0;
691 // Iterate over each lanelet in the shortest path this loop works by looking one lanelet ahead to detect lane changes
692 for (lanelet::ConstLanelet ll : shortest_path)
693 {
694 next_index++;
695 if (first)
696 { // For the first lanelet store its centerline and length
697 lineStrings.push_back(copyConstructLineString(ll.centerline()));
698 first = false;
699 }
700 if (next_index < shortest_path.size())
701 { // Check for remaining lanelets
702 auto nextLanelet = shortest_path[next_index];
703 lanelet::LineString3d nextCenterline = copyConstructLineString(nextLanelet.centerline());
704 size_t connectionCount = shortest_path_graph->possiblePaths(ll, (uint32_t)2, false).size();
705
706 if (connectionCount == 1)
707 { // Get list of connected lanelets without lanechanges. On the shortest path this should only return 1 or 0
708 // No lane change
709 // Append distance to current centerline
710 size_t offset =
711 lineStrings.size() == 0 || lineStrings.back().size() == 0 ?
712 0 :
713 1; // Prevent duplicate points when concatenating. Not clear if causes an issue at lane changes
714 if ((nextCenterline.size() <= 1) || (nextCenterline.size() <= 2 && offset == 1))
715 {
716 throw std::invalid_argument("Cannot process route with lanelet containing very short centerline");
717 }
718 lineStrings.back().insert(lineStrings.back().end(), nextCenterline.begin() + offset, nextCenterline.end());
719 }
720 else if (connectionCount == 0)
721 {
722 // Lane change required
723 // Break the point chain when a lanechange occurs
724 if (lineStrings.back().size() == 0)
725 continue; // we don't have to create empty_linestring if we already have one
726 // occurs when route is changing lanes multiple times in sequence
727 lanelet::LineString3d empty_linestring;
728 empty_linestring.setId(lanelet::utils::getId());
729 distance_map.pushBack(lanelet::utils::to2D(lineStrings.back()));
730 lineStrings.push_back(empty_linestring);
731 }
732 else
733 {
734 assert(false); // It should not be possable to reach this point. Doing so demonstrates a bug
735 }
736 }
737 }
738 // Copy values to member variables
739 while (lineStrings.back().size() == 0)
740 lineStrings.pop_back(); // clear empty linestrings that was never used in the end
741 shortest_path_centerlines_ = lineStrings;
742 shortest_path_distance_map_ = distance_map;
743
744 // Add length of final sections
746 {
747 shortest_path_distance_map_.pushBack(lanelet::utils::to2D(lineStrings.back())); // Record length of last continuous
748 // segment
749 }
750
751 // Since our copy constructed linestrings do not contain references to lanelets they can be added to a full map
752 // instead of a submap
754 }
IndexedDistanceMap shortest_path_distance_map_
lanelet::LineString3d copyConstructLineString(const lanelet::ConstLineString3d &line) const
Helper function to perform a deep copy of a LineString and assign new ids to all the elements....
lanelet::LaneletSubmapConstUPtr shortest_path_view_
lanelet::Optional< TrafficRulesConstPtr > getTrafficRules() const override
Get the Traffic Rules object.
lanelet::LaneletMapUPtr shortest_path_filtered_centerline_view_
std::vector< lanelet::LineString3d > shortest_path_centerlines_
void pushBack(const lanelet::LineString2d &ls)
Add a linestring to this structure. This function will iterate over the line string to compute distan...
size_t size() const
Returns number of linestrings in this structure.
std::shared_ptr< const lanelet::traffic_rules::TrafficRules > TrafficRulesConstPtr
Definition: WorldModel.hpp:55

References copyConstructLineString(), getTrafficRules(), participant_type_, carma_wm::IndexedDistanceMap::pushBack(), route_, shortest_path_centerlines_, shortest_path_distance_map_, shortest_path_filtered_centerline_view_, shortest_path_view_, and carma_wm::IndexedDistanceMap::size().

Referenced by setRoute().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ copyConstructLineString()

lanelet::LineString3d carma_wm::CARMAWorldModel::copyConstructLineString ( const lanelet::ConstLineString3d &  line) const
private

Helper function to perform a deep copy of a LineString and assign new ids to all the elements. Used during route centerline construction.

Parameters
lineThe linestring to be coppied
Returns
A new linestring containing unique ids for all points and the linestring itself

Definition at line 662 of file CARMAWorldModel.cpp.

663 {
664 std::vector<lanelet::Point3d> coppied_points;
665 coppied_points.reserve(line.size());
666
667 for (auto basic_p : line.basicLineString())
668 {
669 coppied_points.push_back(lanelet::Point3d(lanelet::utils::getId(), basic_p));
670 }
671
672 return lanelet::LineString3d(lanelet::utils::getId(), coppied_points);
673 }

Referenced by computeDowntrackReferenceLine().

Here is the caller graph for this function:

◆ distToNearestObjInLane()

lanelet::Optional< double > carma_wm::CARMAWorldModel::distToNearestObjInLane ( const lanelet::BasicPoint2d &  object_center) const
overridevirtual

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

Implements carma_wm::WorldModel.

Definition at line 950 of file CARMAWorldModel.cpp.

951 {
952 // Check if the map is loaded yet
953 if (!semantic_map_ || semantic_map_->laneletLayer.size() == 0)
954 {
955 throw std::invalid_argument("Map is not set or does not contain lanelets");
956 }
957
958 // return empty if there is no object nearby
959 if (roadway_objects_.size() == 0)
960 return boost::none;
961
962 // Get the lanelet of this point
963 auto curr_lanelet = semantic_map_->laneletLayer.nearest(object_center, 1)[0];
964
965 // Check if this point at least is actually within this lanelet; otherwise, it wouldn't be "in-lane"
966 if (!boost::geometry::within(object_center, curr_lanelet.polygon2d().basicPolygon()))
967 throw std::invalid_argument("Given point is not within any lanelet");
968
969 std::vector<carma_perception_msgs::msg::RoadwayObstacle> lane_objects = getInLaneObjects(curr_lanelet);
970
971 // return empty if there is no object in the lane
972 if (lane_objects.size() == 0)
973 return boost::none;
974
975 // Record the closest distance out of all polygons, 4 points each
976 double min_dist = INFINITY;
977 for (auto obj : roadway_objects_)
978 {
979 lanelet::BasicPolygon2d object_polygon = geometry::objectToMapPolygon(obj.object.pose.pose, obj.object.size);
980
981 // Point to closest edge on polygon distance by boost library
982 double curr_dist = lanelet::geometry::distance(object_center, object_polygon);
983 if (min_dist > curr_dist)
984 min_dist = curr_dist;
985 }
986
987 // Return the closest distance out of all polygons
988 return min_dist;
989 }
std::vector< carma_perception_msgs::msg::RoadwayObstacle > roadway_objects_
std::vector< carma_perception_msgs::msg::RoadwayObstacle > getInLaneObjects(const lanelet::ConstLanelet &lanelet, const LaneSection &section=LANE_AHEAD) const override
Gets all roadway objects currently in the same lane as the given lanelet.
std::shared_ptr< lanelet::LaneletMap > semantic_map_
lanelet::BasicPolygon2d objectToMapPolygon(const geometry_msgs::msg::Pose &pose, const geometry_msgs::msg::Vector3 &size)
Uses the provided pose and size vector of an ExternalObject to compute what the polygon would be of t...
Definition: Geometry.cpp:289

References getInLaneObjects(), carma_wm::geometry::objectToMapPolygon(), roadway_objects_, and semantic_map_.

Here is the call graph for this function:

◆ FRIEND_TEST()

carma_wm::CARMAWorldModel::FRIEND_TEST ( CARMAWorldModelTest  ,
getFirstLaneletOnShortestPath   
)
private

◆ getBusStopsAlongRoute()

std::vector< lanelet::BusStopRulePtr > carma_wm::CARMAWorldModel::getBusStopsAlongRoute ( const lanelet::BasicPoint2d &  loc) const
overridevirtual

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

Implements carma_wm::WorldModel.

Definition at line 119 of file CARMAWorldModel.cpp.

120 {
121 // Check if the map is loaded yet
122 if (!semantic_map_ || semantic_map_->laneletLayer.empty())
123 {
124 RCLCPP_ERROR_STREAM(rclcpp::get_logger("carma_wm"), "Map is not set or does not contain lanelets");
125 return {};
126 }
127 // Check if the route was loaded yet
128 if (!route_)
129 {
130 RCLCPP_ERROR_STREAM(rclcpp::get_logger("carma_wm"), "Route has not yet been loaded");
131 return {};
132 }
133 std::vector<lanelet::BusStopRulePtr> bus_stop_list;
134 auto curr_downtrack = routeTrackPos(loc).downtrack;
135 // shortpath is already sorted by distance
136
137 for (const auto &ll : route_->shortestPath())
138 {
139 auto bus_stops = semantic_map_->laneletLayer.get(ll.id()).regulatoryElementsAs<lanelet::BusStopRule>();
140 if (bus_stops.empty())
141 {
142 continue;
143 }
144
145 for (auto bus_stop : bus_stops)
146 {
147 auto stop_line = bus_stop->stopAndWaitLine();
148 if (stop_line.empty())
149 {
150 RCLCPP_ERROR_STREAM(rclcpp::get_logger("carma_wm"), "No stop line");
151 continue;
152 }
153 else
154 {
155 double bus_stop_downtrack = routeTrackPos(stop_line.front().front().basicPoint2d()).downtrack;
156 double distance_remaining_to_bus_stop = bus_stop_downtrack - curr_downtrack;
157
158 if (distance_remaining_to_bus_stop < 0)
159 {
160 continue;
161 }
162 bus_stop_list.push_back(bus_stop);
163 }
164 }
165 }
166 return bus_stop_list;
167 }
std::pair< TrackPos, TrackPos > routeTrackPos(const lanelet::ConstArea &area) const override
Returns a pair of TrackPos, computed in 2d, of the provided area relative to the current route....

References route_, routeTrackPos(), and semantic_map_.

Here is the call graph for this function:

◆ getEntryExitOfSignalAlongRoute()

boost::optional< std::pair< lanelet::ConstLanelet, lanelet::ConstLanelet > > carma_wm::CARMAWorldModel::getEntryExitOfSignalAlongRoute ( const lanelet::CarmaTrafficSignalPtr &  traffic_signal) const
overridevirtual

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.

Implements carma_wm::WorldModel.

Definition at line 1268 of file CARMAWorldModel.cpp.

1269 {
1270 if (!traffic_signal)
1271 {
1272 throw std::invalid_argument("Empty traffic signal pointer has been passed!");
1273 }
1274
1275 std::pair<lanelet::ConstLanelet, lanelet::ConstLanelet> entry_exit;
1276 bool found_entry = false;
1277 bool found_exit = false;
1278 auto entry_lanelets = traffic_signal->getControlStartLanelets();
1279 auto exit_lanelets = traffic_signal->getControlEndLanelets();
1280
1281 // get entry and exit lane along route for the nearest given signal
1282 for (const auto& ll: route_->shortestPath())
1283 {
1284 if (!found_entry)
1285 {
1286 for (const auto& entry: entry_lanelets)
1287 {
1288 if (ll.id() == entry.id())
1289 {
1290 entry_exit.first = entry;
1291 found_entry = true;
1292 break;
1293 }
1294 }
1295 }
1296
1297 if (!found_exit)
1298 {
1299 for (const auto& exit: exit_lanelets)
1300 {
1301 if (ll.id() == exit.id())
1302 {
1303 entry_exit.second = exit;
1304 found_exit = true;
1305 break;
1306 }
1307 }
1308 }
1309
1310 if (found_entry && found_exit)
1311 return entry_exit;
1312 }
1313
1314 // was not able to find entry and exit for this signal along route
1315 return boost::none;
1316 }

References route_.

◆ getFirstLaneletOnShortestPath()

std::optional< lanelet::ConstLanelet > carma_wm::CARMAWorldModel::getFirstLaneletOnShortestPath ( const std::vector< lanelet::ConstLanelet > &  lanelets_to_filter) const
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

Implements carma_wm::WorldModel.

Definition at line 1566 of file CARMAWorldModel.cpp.

1567 {
1568 if (!route_ || lanelets_to_filter.empty())
1569 {
1570 return std::nullopt;
1571 }
1572
1573 // pick a lanelet on the shortest path
1574 for (const auto& llt : lanelets_to_filter)
1575 {
1576 auto shortest_path = route_->shortestPath();
1577 if (std::find(shortest_path.begin(), shortest_path.end(), llt) != shortest_path.end())
1578 {
1579 return llt;
1580 }
1581 }
1582
1583 return std::nullopt;
1584 }

References route_.

◆ getInLaneObjects()

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

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

Implements carma_wm::WorldModel.

Definition at line 856 of file CARMAWorldModel.cpp.

858 {
859 // Get all lanelets on current lane section
860 std::vector<lanelet::ConstLanelet> lane = getLane(lanelet, section);
861
862 // Check if any roadway object is registered
863 if (roadway_objects_.size() == 0)
864 {
865 return std::vector<carma_perception_msgs::msg::RoadwayObstacle>{};
866 }
867
868 // Initialize useful variables
869 std::vector<carma_perception_msgs::msg::RoadwayObstacle> lane_objects, roadway_objects_copy = roadway_objects_;
870
871 /*
872 * Get all in lane objects
873 * For each lane, we check if each object is on it by matching lanelet_id
874 * Complexity N*K, where N: num of lanelets, K: num of objects
875 */
876 int curr_idx;
877 std::queue<int> obj_idxs_queue;
878
879 // Create an index queue for roadway objects to quickly pop the idx if associated
880 // lanelet is found. This is to reduce number of objects to check as we check new lanelets
881 for (size_t i = 0; i < roadway_objects_copy.size(); i++)
882 {
883 obj_idxs_queue.push((int)i);
884 }
885
886 // check each lanelets
887 for (auto llt : lane)
888 {
889 int checked_queue_items = 0, to_check = obj_idxs_queue.size();
890 // check each objects
891 while (checked_queue_items < to_check)
892 {
893 curr_idx = obj_idxs_queue.front();
894 obj_idxs_queue.pop();
895 checked_queue_items++;
896
897 // Check if the object is in the lanelet
898 auto curr_obj = roadway_objects_copy[curr_idx];
899 if (curr_obj.lanelet_id == llt.id())
900 {
901 // found intersecting lanelet for this object
902 lane_objects.push_back(curr_obj);
903 }
904 // handle a case where an object might be lane-changing, so check adjacent ids
905 // a bit faster than checking intersection solely as && is left-to-right evaluation
906 else if (((map_routing_graph_->left(llt) && curr_obj.lanelet_id == map_routing_graph_->left(llt).get().id()) ||
907 (map_routing_graph_->right(llt) && curr_obj.lanelet_id == map_routing_graph_->right(llt).get().id())) &&
908 boost::geometry::intersects(
909 llt.polygon2d().basicPolygon(),
910 geometry::objectToMapPolygon(curr_obj.object.pose.pose, curr_obj.object.size)))
911 {
912 // found intersecting lanelet for this object
913 lane_objects.push_back(curr_obj);
914 }
915 else
916 {
917 // did not find suitable lanelet, so it will be processed again for next lanelet
918 obj_idxs_queue.push(curr_idx);
919 }
920 }
921 }
922
923 return lane_objects;
924 }
LaneletRoutingGraphPtr map_routing_graph_
std::vector< lanelet::ConstLanelet > getLane(const lanelet::ConstLanelet &lanelet, const LaneSection &section=LANE_AHEAD) const override
Gets the specified lane section achievable without lane change, sorted from the start,...

References getLane(), process_bag::i, map_routing_graph_, carma_wm::geometry::objectToMapPolygon(), and roadway_objects_.

Referenced by distToNearestObjInLane(), and getNearestObjInLane().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getIntersectingLanelet()

lanelet::Optional< lanelet::Lanelet > carma_wm::CARMAWorldModel::getIntersectingLanelet ( const carma_perception_msgs::msg::ExternalObject &  object) const
overridevirtual

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.

Implements carma_wm::WorldModel.

Definition at line 927 of file CARMAWorldModel.cpp.

928 {
929 // Check if the map is loaded yet
930 if (!semantic_map_ || semantic_map_->laneletLayer.size() == 0)
931 {
932 throw std::invalid_argument("Map is not set or does not contain lanelets");
933 }
934
935 lanelet::BasicPoint2d object_center(object.pose.pose.position.x, object.pose.pose.position.y);
936 lanelet::BasicPolygon2d object_polygon = geometry::objectToMapPolygon(object.pose.pose, object.size);
937
938 auto nearestLanelet = semantic_map_->laneletLayer.nearest(
939 object_center, 1)[0]; // Since the map contains lanelets there should always be at least 1 element
940
941 // Check if the object is inside or intersecting this lanelet
942 // If no intersection then the object can be considered off the road and does not need to processed
943 if (!boost::geometry::intersects(nearestLanelet.polygon2d().basicPolygon(), object_polygon))
944 {
945 return boost::none;
946 }
947 return nearestLanelet;
948 }

References carma_wm::geometry::objectToMapPolygon(), and semantic_map_.

Referenced by toRoadwayObstacle().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getIntersectionsAlongRoute()

std::vector< std::shared_ptr< lanelet::AllWayStop > > carma_wm::CARMAWorldModel::getIntersectionsAlongRoute ( const lanelet::BasicPoint2d &  loc) const
overridevirtual

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

Implements carma_wm::WorldModel.

Definition at line 1318 of file CARMAWorldModel.cpp.

1319 {
1320 // Check if the map is loaded yet
1321 if (!semantic_map_ || semantic_map_->laneletLayer.empty())
1322 {
1323 RCLCPP_ERROR_STREAM(rclcpp::get_logger("carma_wm"), "Map is not set or does not contain lanelets");
1324 return {};
1325 }
1326 // Check if the route was loaded yet
1327 if (!route_)
1328 {
1329 RCLCPP_ERROR_STREAM(rclcpp::get_logger("carma_wm"), "Route has not yet been loaded");
1330 return {};
1331 }
1332 std::vector<std::shared_ptr<lanelet::AllWayStop>> intersection_list;
1333 auto curr_downtrack = routeTrackPos(loc).downtrack;
1334 // shortpath is already sorted by distance
1335 for(const auto& ll : route_->shortestPath())
1336 {
1337 auto intersections = semantic_map_->laneletLayer.get(ll.id()).regulatoryElementsAs<lanelet::AllWayStop>();
1338 if (intersections.empty())
1339 {
1340 continue;
1341 }
1342 for (auto intersection : intersections)
1343 {
1344 double intersection_downtrack = routeTrackPos(intersection->stopLines().front().front().basicPoint2d()).downtrack;
1345 if (intersection_downtrack < curr_downtrack)
1346 {
1347 continue;
1348 }
1349 intersection_list.push_back(intersection);
1350 }
1351 }
1352 return intersection_list;
1353 }

References route_, routeTrackPos(), and semantic_map_.

Here is the call graph for this function:

◆ getLane()

std::vector< lanelet::ConstLanelet > carma_wm::CARMAWorldModel::getLane ( const lanelet::ConstLanelet &  lanelet,
const LaneSection section = LANE_AHEAD 
) const
overridevirtual

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

Implements carma_wm::WorldModel.

Definition at line 1116 of file CARMAWorldModel.cpp.

1118 {
1119 // Check if the map is loaded yet
1120 if (!semantic_map_ || semantic_map_->laneletLayer.size() == 0)
1121 {
1122 throw std::invalid_argument("Map is not set or does not contain lanelets");
1123 }
1124
1125 // Check if the lanelet is in map
1126 if (semantic_map_->laneletLayer.find(lanelet.id()) == semantic_map_->laneletLayer.end())
1127 {
1128 throw std::invalid_argument("Lanelet is not on the map");
1129 }
1130
1131 // Check if the lane section input is correct
1132 if (section != LANE_FULL && section != LANE_BEHIND && section != LANE_AHEAD)
1133 {
1134 throw std::invalid_argument("Undefined lane section is requested");
1135 }
1136
1137 std::vector<lanelet::ConstLanelet> following_lane = {lanelet};
1138 std::stack<lanelet::ConstLanelet> prev_lane_helper;
1139 std::vector<lanelet::ConstLanelet> prev_lane;
1140 std::vector<lanelet::ConstLanelet> connecting_lanelet = map_routing_graph_->following(lanelet, false);
1141
1142 // if only interested in following lanelets, as it is the most case
1143 while (connecting_lanelet.size() != 0)
1144 {
1145 following_lane.push_back(connecting_lanelet[0]);
1146 connecting_lanelet = map_routing_graph_->following(connecting_lanelet[0], false);
1147 }
1148 if (section == LANE_AHEAD)
1149 return following_lane;
1150
1151 // if interested in lanelets behind
1152 connecting_lanelet = map_routing_graph_->previous(lanelet, false);
1153 while (connecting_lanelet.size() != 0)
1154 {
1155 prev_lane_helper.push(connecting_lanelet[0]);
1156 connecting_lanelet = map_routing_graph_->previous(connecting_lanelet[0], false);
1157 }
1158
1159 // gather all lanelets with correct start order
1160 while (prev_lane_helper.size() != 0)
1161 {
1162 prev_lane.push_back(prev_lane_helper.top());
1163 prev_lane_helper.pop();
1164 }
1165
1166 // if only interested in lane behind
1167 if (section == LANE_BEHIND)
1168 {
1169 prev_lane.push_back(lanelet);
1170 return prev_lane;
1171 }
1172
1173 // if interested in full lane
1174 prev_lane.insert(prev_lane.end(), following_lane.begin(), following_lane.end());
1175 return prev_lane;
1176 }

References carma_wm::LANE_AHEAD, carma_wm::LANE_BEHIND, carma_wm::LANE_FULL, map_routing_graph_, and semantic_map_.

Referenced by getInLaneObjects(), and getNearestObjInLane().

Here is the caller graph for this function:

◆ getLaneletsBetween()

std::vector< lanelet::ConstLanelet > carma_wm::CARMAWorldModel::getLaneletsBetween ( double  start,
double  end,
bool  shortest_path_only = false,
bool  bounds_inclusive = true 
) const
overridevirtual

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

Implements carma_wm::WorldModel.

Definition at line 305 of file CARMAWorldModel.cpp.

307 {
308 // Check if the route was loaded yet
309 if (!route_)
310 {
311 throw std::invalid_argument("Route has not yet been loaded");
312 }
313 if (start > end)
314 {
315 throw std::invalid_argument("Start distance is greater than end distance");
316 }
317
318 std::vector<lanelet::ConstLanelet> output;
319 std::priority_queue<LaneletDowntrackPair, std::vector<LaneletDowntrackPair>, std::greater<LaneletDowntrackPair>>
320 prioritized_lanelets;
321
322 auto lanelet_map = route_->laneletMap();
323 for (lanelet::ConstLanelet lanelet : lanelet_map->laneletLayer)
324 {
325 if (shortest_path_only && !shortest_path_view_->laneletLayer.exists(lanelet.id()))
326 {
327 continue; // Continue if we are only evaluating the shortest path and this lanelet is not part of it
328 }
329 lanelet::ConstLineString2d centerline = lanelet::utils::to2D(lanelet.centerline());
330
331 auto front = centerline.front();
332 auto back = centerline.back();
333 TrackPos min = routeTrackPos(front);
334 TrackPos max = routeTrackPos(back);
335
336 if (!bounds_inclusive) // reduce bounds slightly to avoid including exact bounds
337 {
338 if (std::max(min.downtrack, start + 0.00001) > std::min(max.downtrack, end - 0.00001)
339 || (start == end && (min.downtrack >= start || max.downtrack <= end)))
340 { // Check for 1d intersection
341 // No intersection so continue
342 continue;
343 }
344 }
345 else
346 {
347 if (std::max(min.downtrack, start) > std::min(max.downtrack, end)
348 || (start == end && (min.downtrack > start || max.downtrack < end)))
349 { // Check for 1d intersection
350 // No intersection so continue
351 continue;
352 }
353 }
354 // Intersection has occurred so add lanelet to list
355 LaneletDowntrackPair pair(lanelet, min.downtrack);
356 prioritized_lanelets.push(pair);
357 }
358
359 output.reserve(prioritized_lanelets.size());
360 while (!prioritized_lanelets.empty())
361 {
362 auto pair = prioritized_lanelets.top();
363 prioritized_lanelets.pop();
364 output.push_back(pair.lanelet_);
365 }
366
367 if (!shortest_path_only)
368 {
369 return output;
370 }
371
372 //Sort lanelets according to shortest path if using shortest path
373 std::vector<lanelet::ConstLanelet> sorted_output;
374 for (auto llt : route_->shortestPath())
375 {
376 for (size_t i = 0; i < output.size(); i++)
377 {
378 if (llt.id() == output[i].id())
379 {
380 sorted_output.push_back(llt);
381 break;
382 }
383 }
384 }
385
386 return sorted_output;
387 }

References carma_wm::TrackPos::downtrack, process_bag::i, route_, routeTrackPos(), and shortest_path_view_.

Here is the call graph for this function:

◆ getLaneletsFromPoint() [1/2]

std::vector< lanelet::Lanelet > carma_wm::CARMAWorldModel::getLaneletsFromPoint ( const lanelet::BasicPoint2d &  point,
const unsigned int  n 
)

(non-const version) 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

Definition at line 1198 of file CARMAWorldModel.cpp.

1199 {
1201 }
std::vector< lanelet::ConstLanelet > getLaneletsFromPoint(const lanelet::LaneletMapConstPtr &semantic_map, const lanelet::BasicPoint2d &point, const unsigned int n=10)
carma_wm::query namespace contains implementations for query functions (input and output read or writ...

References carma_wm::query::getLaneletsFromPoint(), process_traj_logs::point, and semantic_map_.

Here is the call graph for this function:

◆ getLaneletsFromPoint() [2/2]

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

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

Implements carma_wm::WorldModel.

Definition at line 1203 of file CARMAWorldModel.cpp.

1204 {
1206 }
lanelet::LaneletMapConstPtr getMap() const override
Get a pointer to the current map. If the underlying map has changed the pointer will also need to be ...

References carma_wm::query::getLaneletsFromPoint(), getMap(), and process_traj_logs::point.

Here is the call graph for this function:

◆ getMap()

lanelet::LaneletMapConstPtr carma_wm::CARMAWorldModel::getMap ( ) const
overridevirtual

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

Implements carma_wm::WorldModel.

Definition at line 547 of file CARMAWorldModel.cpp.

548 {
549 return std::static_pointer_cast<lanelet::LaneletMap const>(semantic_map_); // Cast pointer to const variant
550 }

References semantic_map_.

Referenced by getLaneletsFromPoint(), and nonConnectedAdjacentLeft().

Here is the caller graph for this function:

◆ getMapRoutingGraph()

LaneletRoutingGraphConstPtr carma_wm::CARMAWorldModel::getMapRoutingGraph ( ) const
overridevirtual

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

Implements carma_wm::WorldModel.

Definition at line 756 of file CARMAWorldModel.cpp.

757 {
758 return std::static_pointer_cast<const lanelet::routing::RoutingGraph>(map_routing_graph_); // Cast pointer to const
759 // variant
760 }

References map_routing_graph_.

◆ getMapVersion()

size_t carma_wm::CARMAWorldModel::getMapVersion ( ) const
overridevirtual

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

Implements carma_wm::WorldModel.

Definition at line 606 of file CARMAWorldModel.cpp.

607 {
608 return map_version_;
609 }

References map_version_.

◆ getMutableMap()

lanelet::LaneletMapPtr carma_wm::CARMAWorldModel::getMutableMap ( ) const

Get a mutable version of the current map.

NOTE: the user must make sure to setMap() after any edit to the map and to set a valid route

Definition at line 611 of file CARMAWorldModel.cpp.

612 {
613 return semantic_map_;
614 }

References semantic_map_.

◆ getNearestObjInLane()

lanelet::Optional< std::tuple< TrackPos, carma_perception_msgs::msg::RoadwayObstacle > > carma_wm::CARMAWorldModel::getNearestObjInLane ( const lanelet::BasicPoint2d &  object_center,
const LaneSection section = LANE_AHEAD 
) const

This function is called by distanceToObjectBehindInLane or distanceToObjectAheadInLane. Gets Downtrack distance to AND copy of the closest object 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
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 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. Return empty if there is no objects on current lane or the road

Definition at line 992 of file CARMAWorldModel.cpp.

993 {
994 // Check if the map is loaded yet
995 if (!semantic_map_ || semantic_map_->laneletLayer.size() == 0)
996 {
997 throw std::invalid_argument("Map is not set or does not contain lanelets");
998 }
999
1000 // return empty if there is no object nearby
1001 if (roadway_objects_.size() == 0)
1002 return boost::none;
1003
1004 // Get the lanelet of this point
1005 auto curr_lanelet = semantic_map_->laneletLayer.nearest(object_center, 1)[0];
1006
1007 // Check if this point at least is actually within this lanelet; otherwise, it wouldn't be "in-lane"
1008 if (!boost::geometry::within(object_center, curr_lanelet.polygon2d().basicPolygon()))
1009 throw std::invalid_argument("Given point is not within any lanelet");
1010
1011 // Get objects that are in the lane
1012 std::vector<carma_perception_msgs::msg::RoadwayObstacle> lane_objects = getInLaneObjects(curr_lanelet, section);
1013
1014 // return empty if there is no object in the lane
1015 if (lane_objects.size() == 0)
1016 return boost::none;
1017
1018 // Get the lane that is including this lanelet
1019 std::vector<lanelet::ConstLanelet> lane_section = getLane(curr_lanelet, section);
1020
1021 std::vector<double> object_downtracks, object_crosstracks;
1022 std::vector<int> object_idxs;
1023 std::queue<int> obj_idxs_queue;
1024 double base_downtrack = 0;
1025 double input_obj_downtrack = 0;
1026 int curr_idx = 0;
1027
1028 // Create an index queue for in lane objects to quickly pop the idx if associated
1029 // lanelet is found. This is to reduce number of objects to check as we check new lanelets
1030 for (size_t i = 0; i < lane_objects.size(); i++)
1031 {
1032 obj_idxs_queue.push((int)i);
1033 }
1034
1035 // For each lanelet, check if each object is inside it. if so, calculate downtrack
1036 for (auto llt : lane_section)
1037 {
1038 int checked_queue_items = 0, to_check = obj_idxs_queue.size();
1039
1040 // check each remaining objects
1041 while (checked_queue_items < to_check)
1042 {
1043 curr_idx = obj_idxs_queue.front();
1044 obj_idxs_queue.pop();
1045 checked_queue_items++;
1046
1047 // if the object is on it, store its total downtrack distance
1048 if (lane_objects[curr_idx].lanelet_id == llt.id())
1049 {
1050 object_downtracks.push_back(base_downtrack + lane_objects[curr_idx].down_track);
1051 object_crosstracks.push_back(lane_objects[curr_idx].cross_track);
1052 object_idxs.push_back(curr_idx);
1053 }
1054 // if it's not on it, try adjacent lanelets because the object could be lane changing
1055 else if ((map_routing_graph_->left(llt) &&
1056 lane_objects[curr_idx].lanelet_id == map_routing_graph_->left(llt).get().id()) ||
1057 (map_routing_graph_->right(llt) &&
1058 lane_objects[curr_idx].lanelet_id == map_routing_graph_->right(llt).get().id()))
1059 {
1060 // no need to check intersection as the objects are guaranteed to be intersecting this lane
1061 lanelet::BasicPoint2d obj_center(lane_objects[curr_idx].object.pose.pose.position.x,
1062 lane_objects[curr_idx].object.pose.pose.position.y);
1063 TrackPos new_tp = geometry::trackPos(llt, obj_center);
1064 object_downtracks.push_back(base_downtrack + new_tp.downtrack);
1065 object_crosstracks.push_back(lane_objects[curr_idx].cross_track);
1066 object_idxs.push_back(curr_idx);
1067 }
1068 else
1069 {
1070 // the object is not in the lanelet if above conditions do not meet
1071 obj_idxs_queue.push(curr_idx);
1072 }
1073 }
1074 // try to update object_center's downtrack
1075 if (curr_lanelet.id() == llt.id())
1076 input_obj_downtrack = base_downtrack + geometry::trackPos(llt, object_center).downtrack;
1077
1078 // this lanelet's entire centerline as downtrack
1079 base_downtrack +=
1080 geometry::trackPos(llt.centerline().back().basicPoint2d(), llt.centerline().front().basicPoint2d(),
1081 llt.centerline().back().basicPoint2d())
1082 .downtrack;
1083 }
1084
1085 // compare with input's downtrack and return the min_dist
1086 size_t min_idx = 0;
1087 double min_dist = INFINITY;
1088 for (size_t idx = 0; idx < object_downtracks.size(); idx++)
1089 {
1090 if (min_dist > std::fabs(object_downtracks[idx] - input_obj_downtrack))
1091 {
1092 min_dist = std::fabs(object_downtracks[idx] - input_obj_downtrack);
1093 min_idx = idx;
1094 }
1095 }
1096
1097 // if before the parallel line with the start of the llt that crosses given object_center, neg downtrack.
1098 // if left to the parallel line with the centerline of the llt that crosses given object_center, pos crosstrack
1099 return std::tuple<TrackPos, carma_perception_msgs::msg::RoadwayObstacle>(
1100 TrackPos(object_downtracks[min_idx] - input_obj_downtrack,
1101 object_crosstracks[min_idx] - geometry::trackPos(curr_lanelet, object_center).crosstrack),
1102 lane_objects[object_idxs[min_idx]]);
1103 }
TrackPos trackPos(const lanelet::ConstLanelet &lanelet, const lanelet::BasicPoint2d &point)
Returns the TrackPos, computed in 2d, of the provided point relative to the centerline of the provide...
Definition: Geometry.cpp:120

References carma_wm::TrackPos::downtrack, getInLaneObjects(), getLane(), process_bag::i, map_routing_graph_, roadway_objects_, semantic_map_, and carma_wm::geometry::trackPos().

Referenced by nearestObjectAheadInLane(), and nearestObjectBehindInLane().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getRoadwayObjects()

std::vector< carma_perception_msgs::msg::RoadwayObstacle > carma_wm::CARMAWorldModel::getRoadwayObjects ( ) const
overridevirtual

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.

Implements carma_wm::WorldModel.

Definition at line 851 of file CARMAWorldModel.cpp.

852 {
853 return roadway_objects_;
854 }

References roadway_objects_.

◆ getRoute()

LaneletRouteConstPtr carma_wm::CARMAWorldModel::getRoute ( ) const
overridevirtual

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

Implements carma_wm::WorldModel.

Definition at line 552 of file CARMAWorldModel.cpp.

553 {
554 return std::static_pointer_cast<const lanelet::routing::Route>(route_); // Cast pointer to const variant
555 }

References route_.

◆ getRouteEndTrackPos()

TrackPos carma_wm::CARMAWorldModel::getRouteEndTrackPos ( ) const
overridevirtual

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

Returns
Trackpos

Implements carma_wm::WorldModel.

Definition at line 557 of file CARMAWorldModel.cpp.

558 {
559 TrackPos p(route_length_, 0);
560 return p;
561 }

References route_length_.

Referenced by pointFromRouteTrackPos(), and sampleRoutePoints().

Here is the caller graph for this function:

◆ getRouteName()

std::string carma_wm::CARMAWorldModel::getRouteName ( ) const
overridevirtual

Get the current route name.

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

Implements carma_wm::WorldModel.

Definition at line 657 of file CARMAWorldModel.cpp.

658 {
659 return route_name_;
660 }

References route_name_.

◆ getSignalizedIntersectionsAlongRoute()

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

Implements carma_wm::WorldModel.

Definition at line 1355 of file CARMAWorldModel.cpp.

1356 {
1357 // Check if the map is loaded yet
1358 if (!semantic_map_ || semantic_map_->laneletLayer.empty())
1359 {
1360 RCLCPP_ERROR_STREAM(rclcpp::get_logger("carma_wm"), "Map is not set or does not contain lanelets");
1361 return {};
1362 }
1363 // Check if the route was loaded yet
1364 if (!route_)
1365 {
1366 RCLCPP_ERROR_STREAM(rclcpp::get_logger("carma_wm"), "Route has not yet been loaded");
1367 return {};
1368 }
1369 std::vector<lanelet::SignalizedIntersectionPtr> intersection_list;
1370 auto curr_downtrack = routeTrackPos(loc).downtrack;
1371 // shortpath is already sorted by distance
1372 for (const auto &ll : route_->shortestPath())
1373 {
1374 auto intersections = semantic_map_->laneletLayer.get(ll.id()).regulatoryElementsAs<lanelet::SignalizedIntersection>();
1375 if (intersections.empty())
1376 {
1377 continue;
1378 }
1379 for (auto intersection : intersections)
1380 {
1381 double intersection_downtrack = routeTrackPos(ll.centerline().back().basicPoint2d()).downtrack;
1382 if (intersection_downtrack < curr_downtrack)
1383 {
1384 continue;
1385 }
1386 intersection_list.push_back(intersection);
1387 }
1388 }
1389 return intersection_list;
1390 }

References route_, routeTrackPos(), and semantic_map_.

Here is the call graph for this function:

◆ getSignalsAlongRoute()

std::vector< lanelet::CarmaTrafficSignalPtr > carma_wm::CARMAWorldModel::getSignalsAlongRoute ( const lanelet::BasicPoint2d &  loc) const
overridevirtual

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

Implements carma_wm::WorldModel.

Definition at line 1218 of file CARMAWorldModel.cpp.

1219 {
1220 // Check if the map is loaded yet
1221 if (!semantic_map_ || semantic_map_->laneletLayer.empty())
1222 {
1223 RCLCPP_ERROR_STREAM(rclcpp::get_logger("carma_wm"), "Map is not set or does not contain lanelets");
1224 return {};
1225 }
1226 // Check if the route was loaded yet
1227 if (!route_)
1228 {
1229 RCLCPP_ERROR_STREAM(rclcpp::get_logger("carma_wm"), "Route has not yet been loaded");
1230 return {};
1231 }
1232 std::vector<lanelet::CarmaTrafficSignalPtr> light_list;
1233 auto curr_downtrack = routeTrackPos(loc).downtrack;
1234 // shortpath is already sorted by distance
1235
1236 for (const auto &ll : route_->shortestPath())
1237 {
1238 auto lights = semantic_map_->laneletLayer.get(ll.id()).regulatoryElementsAs<lanelet::CarmaTrafficSignal>();
1239 if (lights.empty())
1240 {
1241 continue;
1242 }
1243
1244 for (auto light : lights)
1245 {
1246 auto stop_line = light->getStopLine(ll);
1247 if (!stop_line)
1248 {
1249 RCLCPP_ERROR_STREAM(rclcpp::get_logger("carma_wm"), "No stop line");
1250 continue;
1251 }
1252 else
1253 {
1254 double light_downtrack = routeTrackPos(stop_line.get().front().basicPoint2d()).downtrack;
1255 double distance_remaining_to_traffic_light = light_downtrack - curr_downtrack;
1256
1257 if (distance_remaining_to_traffic_light < 0)
1258 {
1259 continue;
1260 }
1261 light_list.push_back(light);
1262 }
1263 }
1264 }
1265 return light_list;
1266 }

References route_, routeTrackPos(), and semantic_map_.

Here is the call graph for this function:

◆ getTrafficRules() [1/2]

lanelet::Optional< TrafficRulesConstPtr > carma_wm::CARMAWorldModel::getTrafficRules ( ) const
overridevirtual

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

Implements carma_wm::WorldModel.

Definition at line 787 of file CARMAWorldModel.cpp.

788 {
789
791 }

References getTrafficRules(), and participant_type_.

Referenced by computeDowntrackReferenceLine(), getTrafficRules(), and setMap().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getTrafficRules() [2/2]

lanelet::Optional< TrafficRulesConstPtr > carma_wm::CARMAWorldModel::getTrafficRules ( const std::string &  participant) const
overridevirtual

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.

Implements carma_wm::WorldModel.

Definition at line 762 of file CARMAWorldModel.cpp.

763 {
764 lanelet::Optional<TrafficRulesConstPtr> optional_ptr;
765 // Create carma traffic rules object
766 try
767 {
768 lanelet::traffic_rules::TrafficRulesUPtr traffic_rules = lanelet::traffic_rules::TrafficRulesFactory::create(
769 lanelet::traffic_rules::CarmaUSTrafficRules::Location, participant);
770
771 auto carma_traffic_rules = std::make_shared<lanelet::traffic_rules::CarmaUSTrafficRules>();
772
773 carma_traffic_rules = std::static_pointer_cast<lanelet::traffic_rules::CarmaUSTrafficRules>(
774 lanelet::traffic_rules::TrafficRulesPtr(std::move(traffic_rules)));
775 carma_traffic_rules->setConfigSpeedLimit(config_speed_limit_);
776
777 optional_ptr = std::static_pointer_cast<const lanelet::traffic_rules::CarmaUSTrafficRules>(carma_traffic_rules);
778 }
779 catch (const lanelet::InvalidInputError& e)
780 {
781 return optional_ptr;
782 }
783
784 return optional_ptr;
785 }

References config_speed_limit_.

◆ getTrafficSignal()

lanelet::CarmaTrafficSignalPtr carma_wm::CARMAWorldModel::getTrafficSignal ( const lanelet::Id &  id) const

helper for getting traffic signal with given lanelet::Id

Definition at line 1392 of file CARMAWorldModel.cpp.

1393 {
1394 auto general_regem = semantic_map_->regulatoryElementLayer.get(id);
1395
1396 auto lanelets_general = semantic_map_->laneletLayer.findUsages(general_regem);
1397 if (lanelets_general.empty())
1398 {
1399 RCLCPP_WARN_STREAM(rclcpp::get_logger("carma_wm"), "There was an error querying lanelet for traffic light with id: " << id);
1400 }
1401
1402 auto curr_light_list = lanelets_general[0].regulatoryElementsAs<lanelet::CarmaTrafficSignal>();
1403
1404 if (curr_light_list.empty())
1405 {
1406 RCLCPP_WARN_STREAM(rclcpp::get_logger("carma_wm"), "There was an error querying traffic light with id: " << id);
1407 return nullptr;
1408 }
1409
1410 lanelet::CarmaTrafficSignalPtr curr_light;
1411
1412 for (auto signal : lanelets_general[0].regulatoryElementsAs<lanelet::CarmaTrafficSignal>())
1413 {
1414 if (signal->id() == id)
1415 {
1416 curr_light = signal;
1417 break;
1418 }
1419 }
1420
1421 if (!curr_light)
1422 {
1423 RCLCPP_WARN_STREAM(rclcpp::get_logger("carma_wm"), "Was not able to find traffic signal with id: " << id << ", ignoring...");
1424 return nullptr;
1425 }
1426
1427 return curr_light;
1428 }

References semantic_map_.

Referenced by processSpatFromMsg().

Here is the caller graph for this function:

◆ getTrafficSignalId()

lanelet::Id carma_wm::CARMAWorldModel::getTrafficSignalId ( uint16_t  intersection_id,
uint8_t  signal_id 
)

helper for traffic signal Id

Definition at line 84 of file CARMAWorldModel.cpp.

85 {
86 lanelet::Id inter_id = lanelet::InvalId;
87 lanelet::Id signal_id = lanelet::InvalId;
88
89 if (sim_.intersection_id_to_regem_id_.find(intersection_id) != sim_.intersection_id_to_regem_id_.end())
90 {
91 inter_id = sim_.intersection_id_to_regem_id_[intersection_id];
92 }
93
94 if (inter_id != lanelet::InvalId && sim_.signal_group_to_traffic_light_id_.find(signal_group_id) != sim_.signal_group_to_traffic_light_id_.end())
95 {
96 signal_id = sim_.signal_group_to_traffic_light_id_[signal_group_id];
97 }
98
99 return signal_id;
100 }
carma_wm::SignalizedIntersectionManager sim_
std::unordered_map< uint16_t, lanelet::Id > intersection_id_to_regem_id_
std::unordered_map< uint8_t, lanelet::Id > signal_group_to_traffic_light_id_

References carma_wm::SignalizedIntersectionManager::intersection_id_to_regem_id_, carma_wm::SignalizedIntersectionManager::signal_group_to_traffic_light_id_, and sim_.

Referenced by processSpatFromMsg().

Here is the caller graph for this function:

◆ getVehicleParticipationType()

std::string carma_wm::CARMAWorldModel::getVehicleParticipationType ( )

Get vehicle participation type.

Definition at line 1193 of file CARMAWorldModel.cpp.

1194 {
1195 return participant_type_;
1196 }

References participant_type_.

◆ min_end_time_converter_minute_of_year()

boost::posix_time::ptime carma_wm::CARMAWorldModel::min_end_time_converter_minute_of_year ( boost::posix_time::ptime  min_end_time,
bool  moy_exists,
uint32_t  moy = 0,
bool  is_simulation = true,
bool  is_spat_wall_time = false 
)

update minimum end time to account for minute of the year

Parameters
min_end_timeminimum end time of the spat movement event list
moy_existstells weather minute of the year exist or not
moyvalue of the minute of the year
is_spat_wall_timeBoolean to indicate if the incoming spat is based on wall clock. Defaults to true.

Definition at line 1430 of file CARMAWorldModel.cpp.

1431 {
1432 double simulation_time_difference_in_seconds = 0.0;
1433 double wall_time_offset_in_seconds = 0.0;
1434 // NOTE: In simulation, ROS1 clock (often coming from CARLA) can have a large time ahead.
1435 // the timing calculated here is in Simulation time, which is behind. Therefore, the world model adds the offset to make it meaningful to carma-platform:
1436 // https://github.com/usdot-fhwa-stol/carma-platform/issues/2217
1437 if (is_simulation && ros1_clock_ && simulation_clock_)
1438 {
1439 simulation_time_difference_in_seconds = ros1_clock_.value().seconds() - simulation_clock_.value().seconds();
1440 }
1441 else if (is_simulation && ros1_clock_ && is_spat_wall_time)
1442 {
1443 // NOTE: If carma-platform is running in simulation with clock synced to sim time but the incoming spat information is based on wall clock
1444 // the spat signal phase time must be offset to sim time.
1445 wall_time_offset_in_seconds = (std::chrono::duration<double>(std::chrono::system_clock::now().time_since_epoch()).count()) - ros1_clock_.value().seconds();
1446 }
1447
1448 min_end_time += lanelet::time::durationFromSec(simulation_time_difference_in_seconds);
1449 min_end_time -= lanelet::time::durationFromSec(wall_time_offset_in_seconds);
1450
1451 if (moy_exists) //account for minute of the year
1452 {
1453 auto inception_boost(boost::posix_time::time_from_string("1970-01-01 00:00:00.000")); // inception of epoch
1454 auto duration_since_inception(lanelet::time::durationFromSec(std::chrono::duration<double>(std::chrono::system_clock::now().time_since_epoch()).count()));
1455 auto curr_time_boost = inception_boost + duration_since_inception;
1456
1457 int curr_year = curr_time_boost.date().year();
1458
1459 // Force the current year to start of epoch if it is simulation
1460 if (is_simulation && !is_spat_wall_time)
1461 curr_year = 1970;
1462
1463 auto curr_year_start_boost(boost::posix_time::time_from_string(std::to_string(curr_year)+ "-01-01 00:00:00.000"));
1464
1465 auto curr_minute_stamp_boost = curr_year_start_boost + boost::posix_time::minutes((int)moy);
1466
1467 int hours_of_day = curr_minute_stamp_boost.time_of_day().hours();
1468 int curr_month = curr_minute_stamp_boost.date().month();
1469 int curr_day = curr_minute_stamp_boost.date().day();
1470
1471 auto curr_day_boost(boost::posix_time::time_from_string(std::to_string(curr_year) + "/" + std::to_string(curr_month) + "/" + std::to_string(curr_day) +" 00:00:00.000")); // GMT is the standard
1472 auto curr_hour_boost = curr_day_boost + boost::posix_time::hours(hours_of_day);
1473
1474 min_end_time += lanelet::time::durationFromSec(lanelet::time::toSec(curr_hour_boost));
1475 return min_end_time;
1476 }
1477 else
1478 {
1479 return min_end_time; // return unchanged
1480 }
1481 }
std::optional< rclcpp::Time > ros1_clock_
std::optional< rclcpp::Time > simulation_clock_
auto to_string(const UtmZone &zone) -> std::string
Definition: utm_zone.cpp:21

References ros1_clock_, simulation_clock_, and carma_cooperative_perception::to_string().

Referenced by processSpatFromMsg().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ nearestObjectAheadInLane()

lanelet::Optional< std::tuple< TrackPos, carma_perception_msgs::msg::RoadwayObstacle > > carma_wm::CARMAWorldModel::nearestObjectAheadInLane ( const lanelet::BasicPoint2d &  object_center) const
overridevirtual

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

Implements carma_wm::WorldModel.

Definition at line 1106 of file CARMAWorldModel.cpp.

1107 {
1108 return getNearestObjInLane(object_center, LANE_AHEAD);
1109 }
lanelet::Optional< std::tuple< TrackPos, carma_perception_msgs::msg::RoadwayObstacle > > getNearestObjInLane(const lanelet::BasicPoint2d &object_center, const LaneSection &section=LANE_AHEAD) const
This function is called by distanceToObjectBehindInLane or distanceToObjectAheadInLane....

References getNearestObjInLane(), and carma_wm::LANE_AHEAD.

Here is the call graph for this function:

◆ nearestObjectBehindInLane()

lanelet::Optional< std::tuple< TrackPos, carma_perception_msgs::msg::RoadwayObstacle > > carma_wm::CARMAWorldModel::nearestObjectBehindInLane ( const lanelet::BasicPoint2d &  object_center) const
overridevirtual

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

Implements carma_wm::WorldModel.

Definition at line 1112 of file CARMAWorldModel.cpp.

1113 {
1114 return getNearestObjInLane(object_center, LANE_BEHIND);
1115 }

References getNearestObjInLane(), and carma_wm::LANE_BEHIND.

Here is the call graph for this function:

◆ nonConnectedAdjacentLeft() [1/2]

std::vector< lanelet::Lanelet > carma_wm::CARMAWorldModel::nonConnectedAdjacentLeft ( const lanelet::BasicPoint2d &  input_point,
const unsigned int  n = 10 
)

(non-const version) 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
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

Definition at line 1208 of file CARMAWorldModel.cpp.

1209 {
1211 }

References carma_wm::query::getLaneletsFromPoint(), and semantic_map_.

Here is the call graph for this function:

◆ nonConnectedAdjacentLeft() [2/2]

std::vector< lanelet::ConstLanelet > carma_wm::CARMAWorldModel::nonConnectedAdjacentLeft ( const lanelet::BasicPoint2d &  input_point,
const unsigned int  n = 10 
) const
overridevirtual

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

Implements carma_wm::WorldModel.

Definition at line 1213 of file CARMAWorldModel.cpp.

1214 {
1215 return carma_wm::query::getLaneletsFromPoint(getMap(), input_point, n);
1216 }

References carma_wm::query::getLaneletsFromPoint(), and getMap().

Here is the call graph for this function:

◆ pointFromRouteTrackPos()

boost::optional< lanelet::BasicPoint2d > carma_wm::CARMAWorldModel::pointFromRouteTrackPos ( const TrackPos route_pos) const
overridevirtual

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

Implements carma_wm::WorldModel.

Definition at line 430 of file CARMAWorldModel.cpp.

431 {
432 double downtrack = route_pos.downtrack;
433 double crosstrack = route_pos.crosstrack;
434
435 if (!route_)
436 {
437 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm"), "Route has not yet been loaded");
438 return boost::none;
439 }
440
441 if (downtrack < 0 || downtrack > getRouteEndTrackPos().downtrack)
442 {
443 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm"), "Tried to convert a downtrack of: " << downtrack
444 << " to map point, but it did not fit in route bounds of "
445 << getRouteEndTrackPos().downtrack);
446 return boost::none;
447 }
448
449 // Use fast lookup to identify the points before and after the provided downtrack on the route
450 auto indices = shortest_path_distance_map_.getElementIndexByDistance(downtrack, true); // Get the linestring matching the provided downtrack
451 size_t ls_i = std::get<0>(indices);
452 size_t pt_i = std::get<1>(indices);
453
454 auto linestring = shortest_path_centerlines_[ls_i];
455
456 if (pt_i >= linestring.size())
457 {
458 throw std::invalid_argument("Impossible index: pt: " + std::to_string(pt_i) + " linestring: " + std::to_string(ls_i));
459 }
460
461 double ls_downtrack = shortest_path_distance_map_.distanceToElement(ls_i);
462
463 double relative_downtrack = downtrack - ls_downtrack;
464
465 size_t centerline_size = linestring.size();
466
467 size_t prior_idx = std::min(pt_i, centerline_size - 1);
468
469 size_t next_idx = std::min(pt_i + 1, centerline_size - 1);
470
471 // This if block handles the edge case where the downtrack distance has landed exactly on an existing point
472 if (prior_idx == next_idx)
473 { // If both indexes are the same we are on the point
474
475 if (crosstrack == 0)
476 { // Crosstrack not provided so we can return the point directly
477 auto prior_point = linestring[prior_idx];
478
479 return lanelet::BasicPoint2d(prior_point.x(), prior_point.y());
480 }
481
482 lanelet::BasicPoint2d prior_point, next_point;
483 double x, y;
484 if (prior_idx < centerline_size - 1)
485 { // If this is not the end point compute the crosstrack based on the next point
486 prior_point = linestring[prior_idx].basicPoint2d();
487 next_point = linestring[prior_idx + 1].basicPoint2d(); // No need to check bounds as this class will reject routes with fewer than 2 points in a centerline
488 x = prior_point.x();
489 y = prior_point.y();
490 }
491 else
492 { // If this is the end point compute the crosstrack based on previous point
493 prior_point = linestring[prior_idx - 1].basicPoint2d();
494 next_point = linestring[prior_idx].basicPoint2d();
495 x = next_point.x();
496 y = next_point.y();
497 }
498
499 // Compute the crosstrack
500 double sigma = geometry::point_to_point_yaw(prior_point, next_point); // Angle between route segment and x-axis
501 double theta = sigma + M_PI_2; // M_PI_2 is 90 deg. Theta is the angle to the vector from the route projected point
502 // to the target point
503 double delta_x = cos(theta) * -crosstrack;
504 double delta_y = sin(theta) * -crosstrack;
505
506 return lanelet::BasicPoint2d(x + delta_x, y + delta_y);
507 }
508
509 double prior_downtrack = shortest_path_distance_map_.distanceToPointAlongElement(ls_i, prior_idx);
510 double next_downtrack = shortest_path_distance_map_.distanceToPointAlongElement(ls_i, next_idx);
511
512 double prior_to_next_dist = next_downtrack - prior_downtrack;
513 double prior_to_target_dist = relative_downtrack - prior_downtrack;
514 double interpolation_percentage = 0;
515
516 if (prior_to_next_dist < 0.000001)
517 {
518 interpolation_percentage = 0;
519 }
520 else
521 {
522 interpolation_percentage = prior_to_target_dist / prior_to_next_dist; // Use the percentage progress between both points to compute the downtrack point
523 }
524
525 auto prior_point = linestring[prior_idx].basicPoint2d();
526 auto next_point = linestring[next_idx].basicPoint2d();
527 auto delta_vec = next_point - prior_point;
528
529 double x = prior_point.x() + interpolation_percentage * delta_vec.x();
530 double y = prior_point.y() + interpolation_percentage * delta_vec.y();
531
532 if (crosstrack != 0) // If the crosstrack is not set no need to do the costly computation.
533 {
534 double sigma = geometry::point_to_point_yaw(prior_point, next_point); // Angle between route segment and x-axis
535 double theta = sigma + M_PI_2; // M_PI_2 is 90 deg. Theta is the angle to the vector from the route projected point
536 // to the target point
537 double delta_x = cos(theta) * -crosstrack;
538 double delta_y = sin(theta) * -crosstrack;
539
540 x += delta_x; // Adjust x and y of target point to account for crosstrack
541 y += delta_y;
542 }
543
544 return lanelet::BasicPoint2d(x, y);
545 }
TrackPos getRouteEndTrackPos() const override
Get trackpos of the end of route point relative to the route.
std::pair< size_t, size_t > getElementIndexByDistance(double distance, bool get_point=true) const
Returns index of the linestring which the provided distance is within. NOTE: Unlike the rest of this ...
double distanceToPointAlongElement(size_t index, size_t point_index) const
Get the along-line distance to the point on the provided linestring.
double distanceToElement(size_t index) const
Get the distance to the start of the linestring at the specified index.
double point_to_point_yaw(const lanelet::BasicPoint2d &cur_point, const lanelet::BasicPoint2d &next_point)
Computes the 2d orientation of the vector from the provided start point to end point.
Definition: Geometry.cpp:588

References carma_wm::TrackPos::crosstrack, carma_wm::IndexedDistanceMap::distanceToElement(), carma_wm::IndexedDistanceMap::distanceToPointAlongElement(), carma_wm::TrackPos::downtrack, carma_wm::IndexedDistanceMap::getElementIndexByDistance(), getRouteEndTrackPos(), carma_wm::geometry::point_to_point_yaw(), route_, shortest_path_centerlines_, shortest_path_distance_map_, carma_cooperative_perception::to_string(), process_traj_logs::x, and process_traj_logs::y.

Referenced by sampleRoutePoints().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ processSpatFromMsg()

void carma_wm::CARMAWorldModel::processSpatFromMsg ( const carma_v2x_msgs::msg::SPAT &  spat_msg,
bool  use_sim_time = false,
bool  is_spat_wall_time = true 
)

processSpatFromMsg update map's traffic light states with SPAT msg

Parameters
spat_msgMsg to update with
use_sim_timeBoolean to indicate if it is currently simulation or not
is_spat_wall_timeBoolean to indicate if the incoming spat is based on wall clock. Defaults to true.

Definition at line 1483 of file CARMAWorldModel.cpp.

1484 {
1485 if (!semantic_map_)
1486 {
1487 RCLCPP_INFO_STREAM(rclcpp::get_logger("carma_wm"), "Map is not set yet.");
1488 return;
1489 }
1490
1491 if (spat_msg.intersection_state_list.empty())
1492 {
1493 RCLCPP_WARN_STREAM(rclcpp::get_logger("carma_wm"), "No intersection_state_list in the newly received SPAT msg. Returning...");
1494 return;
1495 }
1496
1497 for (const auto& curr_intersection : spat_msg.intersection_state_list)
1498 {
1499
1500 for (const auto& current_movement_state : curr_intersection.movement_list)
1501 {
1502 lanelet::Id curr_light_id = getTrafficSignalId(curr_intersection.id.id, current_movement_state.signal_group);
1503
1504 if (curr_light_id == lanelet::InvalId)
1505 {
1506 continue;
1507 }
1508
1509 lanelet::CarmaTrafficSignalPtr curr_light = getTrafficSignal(curr_light_id);
1510
1511 if (curr_light == nullptr)
1512 {
1513 continue;
1514 }
1515
1516 // reset states if the intersection's geometry changed
1517 if (curr_light->revision_ != curr_intersection.revision)
1518 {
1519 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm"), "Received a new intersection geometry. intersection_id: " << (int)curr_intersection.id.id << ", and signal_group_id: " << (int)current_movement_state.signal_group);
1520 sim_.traffic_signal_start_times_[curr_intersection.id.id][current_movement_state.signal_group].clear();
1521 sim_.traffic_signal_states_[curr_intersection.id.id][current_movement_state.signal_group].clear();
1522 }
1523
1524 // all maneuver types in same signal group is currently expected to share signal timing, so only 0th index is used when setting states
1525 if (current_movement_state.movement_event_list.empty())
1526 {
1527 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm"), "Movement_event_list is empty . intersection_id: " << (int)curr_intersection.id.id << ", and signal_group_id: " << (int)current_movement_state.signal_group);
1528 continue;
1529 }
1530 else
1531 {
1532 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm"), "Movement_event_list size: " << current_movement_state.movement_event_list.size() << " . intersection_id: " << (int)curr_intersection.id.id << ", and signal_group_id: " << (int)current_movement_state.signal_group);
1533 }
1534
1535 curr_light->revision_ = curr_intersection.revision; // valid SPAT msg
1536
1537 sim_.traffic_signal_states_[curr_intersection.id.id][current_movement_state.signal_group]={};
1538 sim_.traffic_signal_start_times_[curr_intersection.id.id][current_movement_state.signal_group]={};
1539
1540 for(auto current_movement_event:current_movement_state.movement_event_list)
1541 {
1542 // raw min_end_time in seconds measured from the most recent full hour
1543 boost::posix_time::ptime min_end_time_dynamic = lanelet::time::timeFromSec(current_movement_event.timing.min_end_time);
1544 boost::posix_time::ptime start_time_dynamic = lanelet::time::timeFromSec(current_movement_event.timing.start_time);
1545
1546 min_end_time_dynamic=min_end_time_converter_minute_of_year(min_end_time_dynamic,curr_intersection.moy_exists,curr_intersection.moy, use_sim_time, is_spat_wall_time); // Accounting minute of the year
1547 start_time_dynamic=min_end_time_converter_minute_of_year(start_time_dynamic,curr_intersection.moy_exists,curr_intersection.moy, use_sim_time, is_spat_wall_time); // Accounting minute of the year
1548
1549 auto received_state_dynamic = static_cast<lanelet::CarmaTrafficSignalState>(current_movement_event.event_state.movement_phase_state);
1550
1551 sim_.traffic_signal_states_[curr_intersection.id.id][current_movement_state.signal_group].push_back(std::make_pair(min_end_time_dynamic, received_state_dynamic));
1552 sim_.traffic_signal_start_times_[curr_intersection.id.id][current_movement_state.signal_group].push_back(
1553 start_time_dynamic);
1554
1555 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm"), "intersection id: " << (int)curr_intersection.id.id << ", signal: " << (int)current_movement_state.signal_group
1556 << ", start_time: " << std::to_string(lanelet::time::toSec(start_time_dynamic))
1557 << ", end_time: " << std::to_string(lanelet::time::toSec(min_end_time_dynamic))
1558 << ", state: " << received_state_dynamic);
1559 }
1560 curr_light->recorded_time_stamps = sim_.traffic_signal_states_[curr_intersection.id.id][current_movement_state.signal_group];
1561 curr_light->recorded_start_time_stamps = sim_.traffic_signal_start_times_[curr_intersection.id.id][current_movement_state.signal_group];
1562 }
1563 }
1564 }
lanelet::Id getTrafficSignalId(uint16_t intersection_id, uint8_t signal_id)
helper for traffic signal Id
boost::posix_time::ptime min_end_time_converter_minute_of_year(boost::posix_time::ptime min_end_time, bool moy_exists, uint32_t moy=0, bool is_simulation=true, bool is_spat_wall_time=false)
update minimum end time to account for minute of the year
lanelet::CarmaTrafficSignalPtr getTrafficSignal(const lanelet::Id &id) const
helper for getting traffic signal with given lanelet::Id
std::unordered_map< uint16_t, std::unordered_map< uint8_t, std::vector< boost::posix_time::ptime > > > traffic_signal_start_times_
std::unordered_map< uint16_t, std::unordered_map< uint8_t, std::vector< std::pair< boost::posix_time::ptime, lanelet::CarmaTrafficSignalState > > > > traffic_signal_states_

References getTrafficSignal(), getTrafficSignalId(), min_end_time_converter_minute_of_year(), semantic_map_, sim_, carma_cooperative_perception::to_string(), carma_wm::SignalizedIntersectionManager::traffic_signal_start_times_, and carma_wm::SignalizedIntersectionManager::traffic_signal_states_.

Here is the call graph for this function:

◆ routeTrackPos() [1/3]

TrackPos carma_wm::CARMAWorldModel::routeTrackPos ( const lanelet::BasicPoint2d &  point) const
overridevirtual

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

Implements carma_wm::WorldModel.

Definition at line 169 of file CARMAWorldModel.cpp.

170 {
171 // Check if the route was loaded yet
172 if (!route_)
173 {
174 throw std::invalid_argument("Route has not yet been loaded");
175 }
176
177 // Find the nearest continuos shortest path centerline segment using fast map nearest search
178 lanelet::Points3d near_points =
179 shortest_path_filtered_centerline_view_->pointLayer.nearest(point, 1); // Find the nearest points
180
181 // Match point with linestring using fast map lookup
182 auto lineString_1 =
183 lanelet::utils::to2D(shortest_path_filtered_centerline_view_->lineStringLayer.findUsages(near_points[0])
184 .front()); // Only need the first index due to nature of route centerline
185
186 if (lineString_1.size() == 0)
187 {
188 throw std::invalid_argument("Invalid route loaded. Shortest path does not have proper references");
189 }
190
191 // New approach
192 // 1. Find nearest point
193 // 2. Find linestring associated with nearest point
194 // 3. If the nearest point is the first point on the linestring then we need to check the downtrack value
195 // 4. -- If donwtrack is negative then iterate over route segments to find preceeding segment
196 // 5. -- If downtrack is positive then we are on the correct segment
197 // 6. If the nearest point is the last point on the linestring then we need to check downtrack value
198 // 7. -- If downtrack is less then seg length then we are on the correct segment
199 // 8. -- If downtrack is greater then seg length then iterate over route segments to find succeeding segment
200 // 9. With correct segment identified compute segment downtrack distance
201 // 10. Accumulate previos segment distances if needed.
202
203 // Find best route segment
204 lanelet::Id bestRouteSegId;
205 TrackPos tp(0, 0);
206 // Check for end cases
207
208 auto indexes = shortest_path_distance_map_.getIndexFromId(near_points[0].id());
209 size_t ls_i = indexes.first;
210 size_t p_i = indexes.second;
211
212 if (near_points[0].id() == lineString_1.front().id())
213 { // Nearest point is at the start of a line string
214 // Get start point of cur segment and add 1
215 auto next_point = lineString_1[1];
216 TrackPos tp_next = geometry::trackPos(point, lineString_1.front().basicPoint(), next_point.basicPoint());
217
218 if (tp_next.downtrack >= 0 || ls_i == 0)
219 {
220 bestRouteSegId = lineString_1.id();
221 tp = tp_next;
222 // If downtrack is positive then we are on the correct segment
223 }
224 else
225 {
226 // If downtrack is negative then iterate over route segments to find preceeding segment
227 const size_t prev_ls_i = ls_i - 1;
228
229 auto prev_centerline = lanelet::utils::to2D(shortest_path_centerlines_[prev_ls_i]); // Get prev centerline
230 tp = geometry::trackPos(point, prev_centerline[prev_centerline.size() - 2].basicPoint(),
231 prev_centerline[prev_centerline.size() - 1].basicPoint());
232 tp.downtrack += shortest_path_distance_map_.distanceToPointAlongElement(prev_ls_i, prev_centerline.size() - 2);
233 bestRouteSegId = prev_centerline.id();
234 }
235 }
236 else if (near_points[0].id() == lineString_1.back().id())
237 { // Nearest point is the end of a line string
238
239 // Get end point of cur segment and subtract 1
240 auto prev_prev_point = lineString_1[lineString_1.size() - 2];
241 auto prev_point = lineString_1[lineString_1.size() - 1];
242
243 TrackPos tp_prev = geometry::trackPos(point, prev_prev_point.basicPoint(), prev_point.basicPoint());
244
245 double last_seg_length =
246 shortest_path_distance_map_.distanceBetween(ls_i, lineString_1.size() - 2, lineString_1.size() - 1);
247
248 if (tp_prev.downtrack < last_seg_length || ls_i == shortest_path_centerlines_.size() - 1)
249 {
250 // If downtrack is less then seg length then we are on the correct segment
251 bestRouteSegId = lineString_1.id();
252 tp = tp_prev;
253 tp.downtrack += shortest_path_distance_map_.distanceToPointAlongElement(ls_i, lineString_1.size() - 2);
254 }
255 else
256 {
257 // If downtrack is greater then seg length then we need to find the succeeding segment
258 auto next_centerline = lanelet::utils::to2D(shortest_path_centerlines_[ls_i + 1]); // Get prev centerline
259 tp = geometry::trackPos(point, next_centerline[0].basicPoint(), next_centerline[1].basicPoint());
260 bestRouteSegId = next_centerline.id();
261 }
262 }
263 else
264 { // The nearest point is in the middle of a line string
265 // Graph the two bounding points on the line string and call matchSegment using a 3 element segment
266 // There is a guarantee from the earlier if statements that near_points[0] will always be located at an index within
267 // the exclusive range (0,lineString_1.size() - 1) so no need for range checks
268
269 lanelet::BasicLineString2d subSegment = lanelet::BasicLineString2d(
270 { lineString_1[p_i - 1].basicPoint(), lineString_1[p_i].basicPoint(), lineString_1[p_i + 1].basicPoint() });
271
272 tp = std::get<0>(geometry::matchSegment(point, subSegment)); // Get track pos along centerline
273
274 tp.downtrack += shortest_path_distance_map_.distanceToPointAlongElement(ls_i, p_i - 1);
275
276 bestRouteSegId = lineString_1.id();
277 }
278
279 // Accumulate distance
280 auto bestRouteSegIndex = shortest_path_distance_map_.getIndexFromId(bestRouteSegId);
281 tp.downtrack += shortest_path_distance_map_.distanceToElement(bestRouteSegIndex.first);
282
283 return tp;
284 }
std::pair< size_t, size_t > getIndexFromId(const lanelet::Id &id) const
Returns the indexes of the element identified by the provided Id NOTE: It is up to the user to know i...
double distanceBetween(size_t index, size_t p1_index, size_t p2_index) const
Get the distance between two points on the same linestring.
std::tuple< TrackPos, lanelet::BasicSegment2d > matchSegment(const lanelet::BasicPoint2d &p, const lanelet::BasicLineString2d &line_string)
Get the TrackPos of the provided point along the linestring and the segment of the line string which ...
Definition: Geometry.cpp:187

References carma_wm::IndexedDistanceMap::distanceBetween(), carma_wm::IndexedDistanceMap::distanceToElement(), carma_wm::IndexedDistanceMap::distanceToPointAlongElement(), carma_wm::TrackPos::downtrack, carma_wm::IndexedDistanceMap::getIndexFromId(), carma_wm::geometry::matchSegment(), process_traj_logs::point, route_, shortest_path_centerlines_, shortest_path_distance_map_, shortest_path_filtered_centerline_view_, and carma_wm::geometry::trackPos().

Here is the call graph for this function:

◆ routeTrackPos() [2/3]

std::pair< TrackPos, TrackPos > carma_wm::CARMAWorldModel::routeTrackPos ( const lanelet::ConstArea &  area) const
overridevirtual

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

Implements carma_wm::WorldModel.

Definition at line 40 of file CARMAWorldModel.cpp.

41 {
42 // Check if the route was loaded yet
43 if (!route_)
44 {
45 throw std::invalid_argument("Route has not yet been loaded");
46 }
47
48 lanelet::ConstLineStrings3d outer_bound = area.outerBound();
49
50 if (outer_bound.empty())
51 {
52 throw std::invalid_argument("Provided area outer bound is invalid as it contains no points");
53 }
54
55 TrackPos minPos(0, 0);
56 TrackPos maxPos(0, 0);
57 bool first = true;
58 for (lanelet::ConstLineString3d sub_bound3d : outer_bound)
59 {
60 auto sub_bound = lanelet::utils::to2D(sub_bound3d);
61 for (lanelet::ConstPoint2d point : sub_bound)
62 {
63 TrackPos tp = routeTrackPos(point);
64 if (first)
65 {
66 minPos = maxPos = tp;
67 first = false;
68 }
69 else if (tp.downtrack < minPos.downtrack)
70 {
71 minPos.downtrack = tp.downtrack;
72 minPos.crosstrack = tp.crosstrack;
73 }
74 else if (tp.downtrack > maxPos.downtrack)
75 {
76 maxPos.downtrack = tp.downtrack;
77 maxPos.crosstrack = tp.crosstrack;
78 }
79 }
80 }
81 return std::make_pair(minPos, maxPos);
82 }

References carma_wm::TrackPos::crosstrack, carma_wm::TrackPos::downtrack, process_traj_logs::point, route_, and routeTrackPos().

Referenced by getBusStopsAlongRoute(), getIntersectionsAlongRoute(), getLaneletsBetween(), getSignalizedIntersectionsAlongRoute(), getSignalsAlongRoute(), routeTrackPos(), setRoute(), and setRouteEndPoint().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ routeTrackPos() [3/3]

TrackPos carma_wm::CARMAWorldModel::routeTrackPos ( const lanelet::ConstLanelet &  lanelet) const
overridevirtual

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

Implements carma_wm::WorldModel.

Definition at line 102 of file CARMAWorldModel.cpp.

103 {
104 // Check if the route was loaded yet
105 if (!route_)
106 {
107 throw std::invalid_argument("Route has not yet been loaded");
108 }
109
110 lanelet::ConstLineString2d centerline = lanelet::utils::to2D(lanelet.centerline());
111 if (centerline.empty())
112 {
113 throw std::invalid_argument("Provided lanelet has invalid centerline containing no points");
114 }
115 auto front = centerline.front();
116 return routeTrackPos(front);
117 }

References route_, and routeTrackPos().

Here is the call graph for this function:

◆ sampleRoutePoints()

std::vector< lanelet::BasicPoint2d > carma_wm::CARMAWorldModel::sampleRoutePoints ( double  start_downtrack,
double  end_downtrack,
double  step_size 
) const
overridevirtual

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.

Implements carma_wm::WorldModel.

Definition at line 389 of file CARMAWorldModel.cpp.

391 {
392 std::vector<lanelet::BasicPoint2d> output;
393 if (!route_)
394 {
395 RCLCPP_WARN_STREAM(rclcpp::get_logger("carma_wm"), "Route has not yet been loaded");
396 return output;
397 }
398
399 double route_end = getRouteEndTrackPos().downtrack;
400
401 if (start_downtrack < 0 || start_downtrack > route_end || end_downtrack < 0 || end_downtrack > route_end ||
402 start_downtrack > end_downtrack)
403 {
404 RCLCPP_WARN_STREAM(rclcpp::get_logger("carma_wm"), "Invalid input downtracks");
405 return output;
406 }
407
408 TrackPos route_pos(start_downtrack, 0);
409
410 if (end_downtrack == start_downtrack)
411 {
412 output.emplace_back(*(pointFromRouteTrackPos(route_pos))); // If a single point was provided return that point
413 return output;
414 }
415
416 output.reserve(2 + (end_downtrack - start_downtrack) / step_size);
417 double downtrack = start_downtrack;
418 while (downtrack < end_downtrack)
419 {
420 route_pos.downtrack = downtrack;
421 output.emplace_back(*(pointFromRouteTrackPos(route_pos)));
422 downtrack += step_size;
423 }
424
425 route_pos.downtrack = end_downtrack;
426 output.emplace_back(*(pointFromRouteTrackPos(route_pos)));
427 return output;
428 }
boost::optional< lanelet::BasicPoint2d > pointFromRouteTrackPos(const TrackPos &route_pos) const override
Converts a route track position into a map frame cartesian point.

References carma_wm::TrackPos::downtrack, getRouteEndTrackPos(), pointFromRouteTrackPos(), and route_.

Here is the call graph for this function:

◆ setConfigSpeedLimit()

void carma_wm::CARMAWorldModel::setConfigSpeedLimit ( double  config_lim)
Parameters
config_limthe configurable speed limit value populated from WMListener using the config_speed_limit parameter in VehicleConfigParams.yaml

Definition at line 1183 of file CARMAWorldModel.cpp.

1184 {
1185 config_speed_limit_ = config_lim;
1186 }

References config_speed_limit_.

◆ setMap()

void carma_wm::CARMAWorldModel::setMap ( lanelet::LaneletMapPtr  map,
size_t  map_version = 0,
bool  recompute_routing_graph = true 
)

Set the current map.

Parameters
mapA shared pointer to the map which will share ownership to this object
map_versionOptional field to set the map version. While this is technically optional its uses is highly advised to manage synchronization.
recompute_routing_graphOptional field which if true will result in the routing graph being recomputed. NOTE: If this map is the first map set the graph will always be recomputed

Definition at line 563 of file CARMAWorldModel.cpp.

564 {
565 // If this is the first time the map has been set, then recompute the routing graph
566 if (!semantic_map_)
567 {
568
569 RCLCPP_INFO_STREAM(rclcpp::get_logger("carma_wm"), "First time map is set in carma_wm. Routing graph will be recomputed reguardless of method inputs.");
570
571 recompute_routing_graph = true;
572 }
573
574 semantic_map_ = map;
575 map_version_ = map_version;
576
577 // If the routing graph should be updated then recompute it
578 if (recompute_routing_graph)
579 {
580
581 RCLCPP_INFO_STREAM(rclcpp::get_logger("carma_wm"), "Building routing graph");
582
584
585 if (!tr)
586 {
587 throw std::invalid_argument("Could not construct traffic rules for participant");
588 }
589
590 TrafficRulesConstPtr traffic_rules = *tr;
591
592 lanelet::routing::RoutingGraphUPtr map_graph = lanelet::routing::RoutingGraph::build(*semantic_map_, *traffic_rules);
593 map_routing_graph_ = std::move(map_graph);
594
595 RCLCPP_INFO_STREAM(rclcpp::get_logger("carma_wm"), "Done building routing graph");
596 }
597 }

References getTrafficRules(), map_routing_graph_, map_version_, participant_type_, and semantic_map_.

Here is the call graph for this function:

◆ setRoadwayObjects()

void carma_wm::CARMAWorldModel::setRoadwayObjects ( const std::vector< carma_perception_msgs::msg::RoadwayObstacle > &  rw_objs)

Update internal records of roadway objects. These objects MUST be guaranteed to be on the road.

These are detected by the sensor fusion node and are passed as objects compatible with lanelet

Definition at line 846 of file CARMAWorldModel.cpp.

847 {
848 roadway_objects_ = rw_objs;
849 }

References roadway_objects_.

◆ setRos1Clock()

void carma_wm::CARMAWorldModel::setRos1Clock ( const rclcpp::Time &  time_now)

Set current Ros1 clock (only used in simulation runs)

Definition at line 616 of file CARMAWorldModel.cpp.

617 {
618 ros1_clock_ = time_now;
619 }

References ros1_clock_.

◆ setRoute()

void carma_wm::CARMAWorldModel::setRoute ( LaneletRoutePtr  route)

Set the current route. This route must match the current map for this class to function properly.

Parameters
routeA shared pointer to the route which will share ownership to this object

Definition at line 626 of file CARMAWorldModel.cpp.

627 {
628 route_ = route;
629 lanelet::ConstLanelets path_lanelets(route_->shortestPath().begin(), route_->shortestPath().end());
630 shortest_path_view_ = lanelet::utils::createConstSubmap(path_lanelets, {});
632 // NOTE: Setting the route_length_ field here will likely result in the final lanelets final point being used. Call setRouteEndPoint to use the destination point value
633 route_length_ = routeTrackPos(route_->getEndPoint().basicPoint2d()).downtrack; // Cache the route length with
634 // consideration for endpoint
635 }
void computeDowntrackReferenceLine()
Helper function to compute the geometry of the route downtrack/crosstrack reference line This functio...

References computeDowntrackReferenceLine(), route_, route_length_, routeTrackPos(), and shortest_path_view_.

Here is the call graph for this function:

◆ setRouteEndPoint()

void carma_wm::CARMAWorldModel::setRouteEndPoint ( const lanelet::BasicPoint3d &  end_point)

Set endpoint of the route.

Definition at line 637 of file CARMAWorldModel.cpp.

638 {
639 if (!route_)
640 {
641 throw std::invalid_argument("Route endpoint set before route was available.");
642 }
643
644 lanelet::ConstPoint3d const_end_point{ lanelet::utils::getId(), end_point.x(), end_point.y(), end_point.z() };
645
646 route_->setEndPoint(const_end_point);
647
648 route_length_ = routeTrackPos(route_->getEndPoint().basicPoint2d()).downtrack; // Cache the route length with
649 // consideration for endpoint
650 }

References route_, route_length_, and routeTrackPos().

Here is the call graph for this function:

◆ setRouteName()

void carma_wm::CARMAWorldModel::setRouteName ( const std::string &  route_name)

Set the name of the route.

Definition at line 652 of file CARMAWorldModel.cpp.

653 {
654 route_name_ = route_name;
655 }

References route_name_.

◆ setRoutingGraph()

void carma_wm::CARMAWorldModel::setRoutingGraph ( LaneletRoutingGraphPtr  graph)

Set the routing graph for the participant type. This function may serve as an optimization to recomputing the routing graph when it is already available.

NOTE: The set graph will be overwritten if setMap(recompute_routing_graph=true) is called. It will not, be overwritten if the map is set with recompute_routing_graph=false

Parameters
graphThe graph to set. NOTE: This graph must be for the participant type specified getVehicleParticipationType(). There is no way to validate this from the object so the user must ensure consistency.

Definition at line 599 of file CARMAWorldModel.cpp.

599 {
600
601 RCLCPP_INFO_STREAM(rclcpp::get_logger("carma_wm"), "Setting the routing graph with user or listener provided graph");
602
603 map_routing_graph_ = graph;
604 }

References map_routing_graph_.

◆ setSimulationClock()

void carma_wm::CARMAWorldModel::setSimulationClock ( const rclcpp::Time &  time_now)

Set simulation clock clock (only used in simulation runs)

Definition at line 621 of file CARMAWorldModel.cpp.

622 {
623 simulation_clock_ = time_now;
624 }

References simulation_clock_.

◆ setTrafficLightIds()

void carma_wm::CARMAWorldModel::setTrafficLightIds ( uint32_t  id,
lanelet::Id  lanelet_id 
)

Sets the id mapping between intersection/signal group and lanelet::Id for traffic lights in the map.

Parameters
idintersection_id (16bit) and signal_group_id (8bit) concatenated in that order and saved in 32bit
lanelet_idlanelet_id

Definition at line 1178 of file CARMAWorldModel.cpp.

1179 {
1180 traffic_light_ids_[id] = lanelet_id;
1181 }
std::unordered_map< uint32_t, lanelet::Id > traffic_light_ids_

References traffic_light_ids_.

◆ setVehicleParticipationType()

void carma_wm::CARMAWorldModel::setVehicleParticipationType ( const std::string &  participant)

Set vehicle participation type.

Definition at line 1188 of file CARMAWorldModel.cpp.

1189 {
1190 participant_type_ = participant;
1191 }

References participant_type_.

◆ toRoadwayObstacle()

lanelet::Optional< carma_perception_msgs::msg::RoadwayObstacle > carma_wm::CARMAWorldModel::toRoadwayObstacle ( const carma_perception_msgs::msg::ExternalObject &  object) const
overridevirtual

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.

Implements carma_wm::WorldModel.

Definition at line 794 of file CARMAWorldModel.cpp.

795 {
796 if (!semantic_map_ || semantic_map_->laneletLayer.size() == 0)
797 {
798 throw std::invalid_argument("Map is not set or does not contain lanelets");
799 }
800
801 lanelet::BasicPoint2d object_center(object.pose.pose.position.x, object.pose.pose.position.y);
802
803 auto nearestLaneletBoost = getIntersectingLanelet(object);
804
805 if (!nearestLaneletBoost)
806 return boost::none;
807
808 lanelet::Lanelet nearestLanelet = nearestLaneletBoost.get();
809
810 carma_perception_msgs::msg::RoadwayObstacle obs;
811 obs.object = object;
812 obs.connected_vehicle_type.type =
813 carma_perception_msgs::msg::ConnectedVehicleType::NOT_CONNECTED; // TODO No clear way to determine automation state at this time
814 obs.lanelet_id = nearestLanelet.id();
815
816 carma_wm::TrackPos obj_track_pos = geometry::trackPos(nearestLanelet, object_center);
817 obs.down_track = obj_track_pos.downtrack;
818 obs.cross_track = obj_track_pos.crosstrack;
819
820 for (auto prediction : object.predictions)
821 {
822 // Compute prediction polygon
823 lanelet::BasicPolygon2d prediction_polygon =
824 geometry::objectToMapPolygon(prediction.predicted_position, object.size);
825 lanelet::BasicPoint2d prediction_center(prediction.predicted_position.position.x,
826 prediction.predicted_position.position.y);
827
828 auto predNearestLanelet = semantic_map_->laneletLayer.nearest(prediction_center, 1)[0];
829
830 carma_wm::TrackPos pred_track_pos = geometry::trackPos(predNearestLanelet, prediction_center);
831
832 obs.predicted_lanelet_ids.emplace_back(predNearestLanelet.id());
833 obs.predicted_cross_tracks.emplace_back(pred_track_pos.crosstrack);
834 obs.predicted_down_tracks.emplace_back(pred_track_pos.downtrack);
835
836 // Since the predictions are having their lanelet ids matched based on the nearest nounding box search rather than
837 // checking for intersection The id confidence will be set to 90% of the position confidence
838 obs.predicted_lanelet_id_confidences.emplace_back(0.9 * prediction.predicted_position_confidence);
839 obs.predicted_cross_track_confidences.emplace_back(0.9 * prediction.predicted_position_confidence);
840 obs.predicted_down_track_confidences.emplace_back(0.9 * prediction.predicted_position_confidence);
841 }
842
843 return obs;
844 }
lanelet::Optional< lanelet::Lanelet > getIntersectingLanelet(const carma_perception_msgs::msg::ExternalObject &object) const override
Gets the a lanelet the object is currently on determined by its position on the semantic map....
Position in a track based coordinate system where the axis are downtrack and crosstrack....
Definition: TrackPos.hpp:35

References carma_wm::TrackPos::crosstrack, carma_wm::TrackPos::downtrack, getIntersectingLanelet(), carma_wm::geometry::objectToMapPolygon(), semantic_map_, and carma_wm::geometry::trackPos().

Here is the call graph for this function:

Member Data Documentation

◆ config_speed_limit_

double carma_wm::CARMAWorldModel::config_speed_limit_
private

Definition at line 278 of file CARMAWorldModel.hpp.

Referenced by getTrafficRules(), and setConfigSpeedLimit().

◆ GREEN_LIGHT_DURATION

constexpr double carma_wm::CARMAWorldModel::GREEN_LIGHT_DURATION = 20.0
staticconstexprprivate

Definition at line 325 of file CARMAWorldModel.hpp.

◆ map_routing_graph_

LaneletRoutingGraphPtr carma_wm::CARMAWorldModel::map_routing_graph_
private

◆ map_version_

size_t carma_wm::CARMAWorldModel::map_version_ = 0
private

Definition at line 316 of file CARMAWorldModel.hpp.

Referenced by getMapVersion(), and setMap().

◆ participant_type_

std::string carma_wm::CARMAWorldModel::participant_type_ = lanelet::Participants::Vehicle
private

◆ RED_LIGHT_DURATION

constexpr double carma_wm::CARMAWorldModel::RED_LIGHT_DURATION = 20.0
staticconstexprprivate

Definition at line 323 of file CARMAWorldModel.hpp.

◆ roadway_objects_

std::vector<carma_perception_msgs::msg::RoadwayObstacle> carma_wm::CARMAWorldModel::roadway_objects_
private

◆ ros1_clock_

std::optional<rclcpp::Time> carma_wm::CARMAWorldModel::ros1_clock_ = std::nullopt
private

Definition at line 300 of file CARMAWorldModel.hpp.

Referenced by min_end_time_converter_minute_of_year(), and setRos1Clock().

◆ route_

◆ route_length_

double carma_wm::CARMAWorldModel::route_length_ = 0
private

Definition at line 306 of file CARMAWorldModel.hpp.

Referenced by getRouteEndTrackPos(), setRoute(), and setRouteEndPoint().

◆ route_name_

std::string carma_wm::CARMAWorldModel::route_name_
private

Definition at line 318 of file CARMAWorldModel.hpp.

Referenced by getRouteName(), and setRouteName().

◆ semantic_map_

◆ shortest_path_centerlines_

std::vector<lanelet::LineString3d> carma_wm::CARMAWorldModel::shortest_path_centerlines_
private

◆ shortest_path_distance_map_

IndexedDistanceMap carma_wm::CARMAWorldModel::shortest_path_distance_map_
private

◆ shortest_path_filtered_centerline_view_

lanelet::LaneletMapUPtr carma_wm::CARMAWorldModel::shortest_path_filtered_centerline_view_
private

Definition at line 312 of file CARMAWorldModel.hpp.

Referenced by computeDowntrackReferenceLine(), and routeTrackPos().

◆ shortest_path_view_

lanelet::LaneletSubmapConstUPtr carma_wm::CARMAWorldModel::shortest_path_view_
private

◆ sim_

carma_wm::SignalizedIntersectionManager carma_wm::CARMAWorldModel::sim_

Definition at line 274 of file CARMAWorldModel.hpp.

Referenced by getTrafficSignalId(), and processSpatFromMsg().

◆ simulation_clock_

std::optional<rclcpp::Time> carma_wm::CARMAWorldModel::simulation_clock_ = std::nullopt
private

◆ traffic_light_ids_

std::unordered_map<uint32_t, lanelet::Id> carma_wm::CARMAWorldModel::traffic_light_ids_

Definition at line 272 of file CARMAWorldModel.hpp.

Referenced by setTrafficLightIds().

◆ YELLOW_LIGHT_DURATION

constexpr double carma_wm::CARMAWorldModel::YELLOW_LIGHT_DURATION = 3.0
staticconstexprprivate

Definition at line 324 of file CARMAWorldModel.hpp.


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