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 Namespace Reference

Namespaces

namespace  collision_detection
 
namespace  geometry
 geometry namespace contains utility geometry functions which do not require the map or route provided by an active world model
 
namespace  query
 
namespace  test
 
namespace  utils
 

Classes

class  CARMAWorldModel
 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...
 
class  IndexedDistanceMap
 O(1) distance lookup structure for quickly accessing route distance information. NOTE: This structure is used internally in the world model and is not intended for use by WorldModel users. More...
 
struct  LANE_DIRECTION
 
class  LaneletDowntrackPair
 
class  SignalizedIntersectionManager
 This class manages and keeps track of all signalized intersections in the map. All of the SPAT and MAP standard's lane ids to lanelet id mapping is recorded here. NOTE: This class functions do not update the map given. More...
 
class  TrackPos
 Position in a track based coordinate system where the axis are downtrack and crosstrack. Positive crosstrack is to the left of the reference line. More...
 
class  TrafficControl
 
class  WMListener
 Class which provies automated subscription and threading support for the world model. More...
 
class  WMListenerWorker
 Backend logic class for WMListener. More...
 
class  WorldModel
 An interface which provides read access to the semantic map and route. This class is not thread safe. All units of distance are in meters. More...
 

Typedefs

using LaneletRoutePtr = std::shared_ptr< lanelet::routing::Route >
 
using LaneletRouteConstPtr = std::shared_ptr< const lanelet::routing::Route >
 
using LaneletRouteUPtr = std::unique_ptr< lanelet::routing::Route >
 
using LaneletRouteUConstPtr = std::unique_ptr< const lanelet::routing::Route >
 
using LaneletRoutingGraphPtr = std::shared_ptr< lanelet::routing::RoutingGraph >
 
using LaneletRoutingGraphConstPtr = std::shared_ptr< const lanelet::routing::RoutingGraph >
 
using LaneletRoutingGraphUPtr = std::unique_ptr< lanelet::routing::RoutingGraph >
 
using LaneletRoutingGraphConstUPtr = std::unique_ptr< const lanelet::routing::RoutingGraph >
 
using TrafficRulesConstPtr = std::shared_ptr< const lanelet::traffic_rules::TrafficRules >
 
using TrafficRulesUConstPtr = std::unique_ptr< const lanelet::traffic_rules::TrafficRules >
 
using WorldModelConstPtr = std::shared_ptr< const WorldModel >
 

Enumerations

enum  LaneSection { LANE_AHEAD , LANE_BEHIND , LANE_FULL }
 
enum class  GeofenceType {
  INVALID , DIGITAL_SPEED_LIMIT , PASSING_CONTROL_LINE , REGION_ACCESS_RULE ,
  DIGITAL_MINIMUM_GAP , DIRECTION_OF_TRAVEL , STOP_RULE , CARMA_TRAFFIC_LIGHT ,
  SIGNALIZED_INTERSECTION
}
 

Functions

void toBinMsg (std::shared_ptr< carma_wm::TrafficControl > gf_ptr, autoware_lanelet2_msgs::msg::MapBin *msg)
 
void fromBinMsg (const autoware_lanelet2_msgs::msg::MapBin &msg, std::shared_ptr< carma_wm::TrafficControl > gf_ptr, lanelet::LaneletMapPtr lanelet_map=nullptr)
 
GeofenceType resolveGeofenceType (const std::string &rule_name)
 
void logSignalizedIntersectionManager (const carma_wm::SignalizedIntersectionManager &sim)
 

Detailed Description

This is a test library made for guidance unit tests. In general, it includes the following :

  • Helper functions to create the world from scratch or extend the world in getGuidanceTestMap()
  • addObstacle at a specified Cartesian or Trackpos point relative to specified lanelet Id
  • set route by giving series of lanelet Id in the map (setRouteById)
  • set speed of entire road (setSpeedLimit)
  • getGuidanceTestMap gives a simple one way, 3 lane map (25mph speed limit) with one static prebaked obstacle and 4 lanelets in a lane (if 2 stripes make up one lanelet):

    |1203|1213|1223| | _ _ _ _ _| |1202| Ob |1222| | _ _ _ _ _| |1201|1211|1221| num = lanelet id hardcoded for easier testing | _ _ _ _ _| | = lane lines |1200|1210|1220| - - - = Lanelet boundary | | O = Default Obstacle


    START_LINE

  • NOTE: please look at the README for an example of how to use them

Typedef Documentation

◆ LaneletRouteConstPtr

using carma_wm::LaneletRouteConstPtr = typedef std::shared_ptr<const lanelet::routing::Route>

Definition at line 46 of file WorldModel.hpp.

◆ LaneletRoutePtr

using carma_wm::LaneletRoutePtr = typedef std::shared_ptr<lanelet::routing::Route>

Definition at line 45 of file WorldModel.hpp.

◆ LaneletRouteUConstPtr

using carma_wm::LaneletRouteUConstPtr = typedef std::unique_ptr<const lanelet::routing::Route>

Definition at line 48 of file WorldModel.hpp.

◆ LaneletRouteUPtr

using carma_wm::LaneletRouteUPtr = typedef std::unique_ptr<lanelet::routing::Route>

Definition at line 47 of file WorldModel.hpp.

◆ LaneletRoutingGraphConstPtr

Definition at line 51 of file WorldModel.hpp.

◆ LaneletRoutingGraphConstUPtr

Definition at line 53 of file WorldModel.hpp.

◆ LaneletRoutingGraphPtr

Definition at line 50 of file WorldModel.hpp.

◆ LaneletRoutingGraphUPtr

Definition at line 52 of file WorldModel.hpp.

◆ TrafficRulesConstPtr

using carma_wm::TrafficRulesConstPtr = typedef std::shared_ptr<const lanelet::traffic_rules::TrafficRules>

Definition at line 55 of file WorldModel.hpp.

◆ TrafficRulesUConstPtr

using carma_wm::TrafficRulesUConstPtr = typedef std::unique_ptr<const lanelet::traffic_rules::TrafficRules>

Definition at line 56 of file WorldModel.hpp.

◆ WorldModelConstPtr

using carma_wm::WorldModelConstPtr = typedef std::shared_ptr<const WorldModel>

Definition at line 452 of file WorldModel.hpp.

Enumeration Type Documentation

◆ GeofenceType

enum class carma_wm::GeofenceType
strong
Enumerator
INVALID 
DIGITAL_SPEED_LIMIT 
PASSING_CONTROL_LINE 
REGION_ACCESS_RULE 
DIGITAL_MINIMUM_GAP 
DIRECTION_OF_TRAVEL 
STOP_RULE 
CARMA_TRAFFIC_LIGHT 
SIGNALIZED_INTERSECTION 

Definition at line 28 of file WMListenerWorker.cpp.

◆ LaneSection

Enumerator
LANE_AHEAD 
LANE_BEHIND 
LANE_FULL 

Definition at line 59 of file WorldModel.hpp.

60{
64};

Function Documentation

◆ fromBinMsg()

void carma_wm::fromBinMsg ( const autoware_lanelet2_msgs::msg::MapBin &  msg,
std::shared_ptr< carma_wm::TrafficControl gf_ptr,
lanelet::LaneletMapPtr  lanelet_map = nullptr 
)

[Converts Geofence binary ROS message to carma_wm::TrafficControl object. Similar implementation to lanelet2_extension::utility::message_conversion::fromBinMsg]

Parameters
msg[ROS message for geofence]
gf_ptr[Ptr to converted Geofence object]
lanelet_map[Ptr to lanelet map to match incoming objects' memory address with that of existing objects' with same lanelet id] NOTE: When converting the geofence object, the converter only fills its relevant map update fields (update_list, remove_list) as the ROS msg doesn't hold any other data field in the object. NOTE: While main map update function needs to use lanelet_map, other utility use cases such as unit test or map update logger does not currently use lanelet_map and can use nullptr as input

Definition at line 40 of file TrafficControl.cpp.

41{
42 if (!gf_ptr)
43 {
44 RCLCPP_ERROR_STREAM(rclcpp::get_logger("carma_wm::TrafficControl"), __FUNCTION__ << ": gf_ptr is null pointer!");
45 return;
46 }
47
48 std::string data_str;
49 data_str.assign(msg.data.begin(), msg.data.end());
50
51 std::stringstream ss;
52 ss << data_str;
53 boost::archive::binary_iarchive oa(ss);
54
55 oa >> *gf_ptr;
56
57 if (!lanelet_map)
58 return;
59
60 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::TrafficControl"), "Lanelet Map is provided to match memory addresses of received binary map update");
61
62 lanelet::utils::OverwriteParameterVisitor memory_visitor(lanelet_map);
63 // It is sufficient to check single regem as carma_wm_ctrl sends only one type of regem in each list
64 if (!gf_ptr->update_list_.empty())
65 gf_ptr->update_list_.front().second->applyVisitor(memory_visitor);
66 if (!gf_ptr->remove_list_.empty())
67 gf_ptr->remove_list_.front().second->applyVisitor(memory_visitor);
68
69 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::TrafficControl"), "Done resolving memory addresses of received regulatory elements!");
70}

Referenced by carma_wm_ctrl::WMBroadcaster::baseMapCallback(), carma_wm::WMListenerWorker::mapCallback(), carma_wm::WMListenerWorker::mapUpdateCallback(), and MapUpdateLogger::mapUpdateCallback().

Here is the caller graph for this function:

◆ logSignalizedIntersectionManager()

void carma_wm::logSignalizedIntersectionManager ( const carma_wm::SignalizedIntersectionManager sim)

Definition at line 120 of file WMListenerWorker.cpp.

121{
122 for (auto const &[intersection_id, regulatory_element_id] : sim.intersection_id_to_regem_id_)
123 {
124 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::WMListenerWorker"),
125 "inter id: " << intersection_id << ", regem id: " << regulatory_element_id);
126 }
127 for (auto const &[signal_id, entry_llt_ids] : sim.signal_group_to_entry_lanelet_ids_)
128 {
129 for (const auto & entry_llt_id : entry_llt_ids)
130 {
131 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::WMListenerWorker"), "signal id: " << (int)signal_id << ", entry llt id: " << entry_llt_id);
132 }
133 }
134 for (auto const &[signal_id, exit_llt_ids] : sim.signal_group_to_exit_lanelet_ids_)
135 {
136 for (const auto & exit_llt_id : exit_llt_ids)
137 {
138 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::WMListenerWorker"), "signal id: " << (int)signal_id << ", exit llt id: " << exit_llt_id);
139 }
140 }
141 for (auto const &[signal_id, regem_id] : sim.signal_group_to_traffic_light_id_)
142 {
143 RCLCPP_DEBUG_STREAM(rclcpp::get_logger("carma_wm::WMListenerWorker"), "signal id: " << (int)signal_id << ", regem id: " << regem_id);
144 }
145}
std::unordered_map< uint8_t, std::unordered_set< lanelet::Id > > signal_group_to_entry_lanelet_ids_
std::unordered_map< uint16_t, lanelet::Id > intersection_id_to_regem_id_
std::unordered_map< uint8_t, std::unordered_set< lanelet::Id > > signal_group_to_exit_lanelet_ids_
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_entry_lanelet_ids_, carma_wm::SignalizedIntersectionManager::signal_group_to_exit_lanelet_ids_, and carma_wm::SignalizedIntersectionManager::signal_group_to_traffic_light_id_.

Referenced by carma_wm::WMListenerWorker::mapUpdateCallback().

Here is the caller graph for this function:

◆ resolveGeofenceType()

GeofenceType carma_wm::resolveGeofenceType ( const std::string &  rule_name)

Definition at line 31 of file WMListenerWorker.cpp.

32{
33 if (rule_name.compare(lanelet::PassingControlLine::RuleName) == 0) return GeofenceType::PASSING_CONTROL_LINE;
34 if (rule_name.compare(lanelet::DigitalSpeedLimit::RuleName) == 0) return GeofenceType::DIGITAL_SPEED_LIMIT;
35 if (rule_name.compare(lanelet::RegionAccessRule::RuleName) == 0) return GeofenceType::REGION_ACCESS_RULE;
36 if (rule_name.compare(lanelet::DigitalMinimumGap::RuleName) == 0) return GeofenceType::DIGITAL_MINIMUM_GAP;
37 if (rule_name.compare(lanelet::DirectionOfTravel::RuleName) == 0) return GeofenceType::DIRECTION_OF_TRAVEL;
38 if (rule_name.compare(lanelet::StopRule::RuleName) == 0) return GeofenceType::STOP_RULE;
39 if (rule_name.compare(lanelet::CarmaTrafficSignal::RuleName) == 0) return GeofenceType::CARMA_TRAFFIC_LIGHT;
40 if (rule_name.compare(lanelet::SignalizedIntersection::RuleName) == 0) return GeofenceType::SIGNALIZED_INTERSECTION;
41
42 return GeofenceType::INVALID;
43}

References CARMA_TRAFFIC_LIGHT, DIGITAL_MINIMUM_GAP, DIGITAL_SPEED_LIMIT, DIRECTION_OF_TRAVEL, INVALID, PASSING_CONTROL_LINE, REGION_ACCESS_RULE, SIGNALIZED_INTERSECTION, and STOP_RULE.

Referenced by carma_wm::WMListenerWorker::newRegemUpdateHelper().

Here is the caller graph for this function:

◆ toBinMsg()

void carma_wm::toBinMsg ( std::shared_ptr< carma_wm::TrafficControl gf_ptr,
autoware_lanelet2_msgs::msg::MapBin *  msg 
)

[Converts carma_wm::TrafficControl object to ROS message. Similar implementation to lanelet2_extension::utility::message_conversion::toBinMsg]

Parameters
gf_ptr[Ptr to Geofence data]
msg[converted ROS message. Only "data" field is filled] NOTE: When converting the geofence object, the converter fills its relevant map update fields (update_list, remove_list) to be read once received at the user

Definition at line 24 of file TrafficControl.cpp.

25{
26 if (msg == nullptr)
27 {
28 RCLCPP_ERROR_STREAM(rclcpp::get_logger("carma_wm::TrafficControl"), __FUNCTION__ << ": msg is null pointer!");
29 return;
30 }
31 std::stringstream ss;
32 boost::archive::binary_oarchive oa(ss);
33 oa << *gf_ptr;
34 std::string data_str(ss.str());
35
36 msg->data.clear();
37 msg->data.assign(data_str.begin(), data_str.end());
38}

Referenced by carma_wm_ctrl::WMBroadcaster::addGeofence(), carma_wm_ctrl::WMBroadcaster::baseMapCallback(), and carma_wm_ctrl::WMBroadcaster::removeGeofence().

Here is the caller graph for this function: