13#include <boost/optional.hpp>
23 boost::optional<Map>
Build();
28 const std::string name,
42 const uint32_t lane_type,
43 const bool lane_level,
63 const double curvature);
72 const double curvStart,
73 const double curvEnd);
102 const std::string p_range);
115 const std::string name,
118 const double zOffset,
122 const std::string orientation,
125 const std::vector<road::element::CrosswalkPoint> points);
159 const std::string name,
160 const std::string dynamic,
161 const std::string orientation,
162 const double zOffset,
163 const std::string country,
164 const std::string type,
165 const std::string subtype,
167 const std::string unit,
170 const std::string text,
171 const double hOffset,
189 const double zOffset,
190 const double hOffset,
197 const double s_position,
198 const double t_position,
199 const std::string signal_reference_orientation);
208 const std::string dependency_id,
209 const std::string dependency_type);
214 const std::string name);
218 const ConId connection_id,
219 const RoadId incoming_road,
220 const RoadId connecting_road);
224 const ConId connection_id,
230 std::set<ContId>&& controllers);
246 const bool lane_level,
254 const std::string restriction);
273 const std::string surface,
274 const double friction,
275 const double roughness);
288 const std::string value);
293 const double forward,
308 const int road_mark_id,
310 const std::string type,
311 const std::string weight,
312 const std::string color,
313 const std::string material,
315 const std::string lane_change,
317 const std::string type_name,
318 const double type_width);
322 const int road_mark_id,
325 const double tOffset,
327 const std::string rule,
333 const std::string type,
335 const std::string unit);
341 const std::string unit);
353 const ContId controller_id,
354 const std::string controller_name,
355 const uint32_t controller_sequence,
356 const std::set<road::SignId>&& signals
413 std::unordered_map<Road *, std::vector<std::unique_ptr<element::RoadInfo>>>
416 std::unordered_map<Lane *, std::vector<std::unique_ptr<element::RoadInfo>>>
419 std::unordered_map<SignId, std::unique_ptr<Signal>>
LaneType
Can be used as flags
std::unordered_map< SignId, std::unique_ptr< Signal > > _temp_signal_container
void AddRoadGeometryArc(carla::road::Road *road, const double s, const double x, const double y, const double hdg, const double length, const double curvature)
void CreateController(const ContId controller_id, const std::string controller_name, const uint32_t controller_sequence, const std::set< road::SignId > &&signals)
carla::road::Lane * AddRoadSectionLane(carla::road::LaneSection *section, const LaneId lane_id, const uint32_t lane_type, const bool lane_level, const LaneId predecessor, const LaneId successor)
void AddSignalPositionRoad(const SignId signal_id, const RoadId road_id, const double s, const double t, const double zOffset, const double hOffset, const double pitch, const double roll)
void AddSignalPositionInertial(const SignId signal_id, const double x, const double y, const double z, const double hdg, const double pitch, const double roll)
void CreateRoadSpeed(Road *road, const double s, const std::string type, const double max, const std::string unit)
carla::road::Road * AddRoad(const RoadId road_id, const std::string name, const double length, const JuncId junction_id, const RoadId predecessor, const RoadId successor)
void CreateSectionOffset(Road *road, const double s, const double a, const double b, const double c, const double d)
void AddJunctionController(const JuncId junction_id, std::set< ContId > &&controllers)
carla::road::LaneSection * AddRoadSection(carla::road::Road *road, const SectionId id, const double s)
void CreateLaneAccess(Lane *lane, const double s, const std::string restriction)
void AddRoadObjectCrosswalk(Road *road, const std::string name, const double s, const double t, const double zOffset, const double hdg, const double pitch, const double roll, const std::string orientation, const double width, const double length, const std::vector< road::element::CrosswalkPoint > points)
void CreateLaneHeight(Lane *lane, const double s, const double inner, const double outer)
geom::Transform ComputeSignalTransform(std::unique_ptr< Signal > &signal, MapData &data)
Lane * GetLane(const RoadId road_id, const LaneId lane_id, const double s)
void CreateLaneBorder(Lane *lane, const double s, const double a, const double b, const double c, const double d)
void ComputeJunctionRoadConflicts(Map &map)
Compute the conflicts of the roads (intersecting roads)
void AddValidityToSignalReference(element::RoadInfoSignal *signal_reference, const LaneId from_lane, const LaneId to_lane)
void CreateLaneRule(Lane *lane, const double s, const std::string value)
void SetGeoReference(const geom::GeoLocation &geo_reference)
void SolveControllerAndJuntionReferences()
Solve the references between Controllers and Juntions
void AddRoadElevationProfile(Road *road, const double s, const double a, const double b, const double c, const double d)
boost::optional< Map > Build()
void AddJunction(const JuncId id, const std::string name)
void CreateLaneSpeed(Lane *lane, const double s, const double max, const std::string unit)
std::unordered_map< Road *, std::vector< std::unique_ptr< element::RoadInfo > > > _temp_road_info_container
Map to temporary store all the road and lane infos until the map is built, so they can be added all t...
void AddLaneLink(const JuncId junction_id, const ConId connection_id, const LaneId from, const LaneId to)
void AddDependencyToSignal(const SignId signal_id, const std::string dependency_id, const std::string dependency_type)
void AddRoadGeometryParamPoly3(carla::road::Road *road, const double s, const double x, const double y, const double hdg, const double length, const double aU, const double bU, const double cU, const double dU, const double aV, const double bV, const double cV, const double dV, const std::string p_range)
std::vector< std::pair< RoadId, LaneId > > GetJunctionLanes(JuncId junction_id, RoadId road_id, LaneId lane_id)
void RemoveZeroLaneValiditySignalReferences()
Removes signal references with lane validity equal to [0,0] as they have no effect on any road
void CreateRoadMarkTypeLine(Lane *lane, const int road_mark_id, const double length, const double space, const double tOffset, const double s, const std::string rule, const double width)
void AddRoadSection(const RoadId road_id, const SectionId section_index, const double s, const double a, const double b, const double c, const double d)
void CreateJunctionBoundingBoxes(Map &map)
Create the bounding boxes of each junction
element::RoadInfoSignal * AddSignalReference(Road *road, const SignId signal_id, const double s_position, const double t_position, const std::string signal_reference_orientation)
std::unordered_map< Lane *, std::vector< std::unique_ptr< element::RoadInfo > > > _temp_lane_info_container
std::vector< element::RoadInfoSignal * > _temp_signal_reference_container
void AddRoadGeometryPoly3(carla::road::Road *road, const double s, const double x, const double y, const double hdg, const double length, const double a, const double b, const double c, const double d)
void GenerateDefaultValiditiesForSignalReferences()
Generates a default validity field for signal references with missing validity record in OpenDRIVE
void AddConnection(const JuncId junction_id, const ConId connection_id, const RoadId incoming_road, const RoadId connecting_road)
element::RoadInfoSignal * AddSignal(Road *road, const SignId signal_id, const double s, const double t, const std::string name, const std::string dynamic, const std::string orientation, const double zOffset, const std::string country, const std::string type, const std::string subtype, const double value, const std::string unit, const double height, const double width, const std::string text, const double hOffset, const double pitch, const double roll)
void CreateRoadMark(Lane *lane, const int road_mark_id, const double s, const std::string type, const std::string weight, const std::string color, const std::string material, const double width, const std::string lane_change, const double height, const std::string type_name, const double type_width)
std::vector< Lane * > GetLaneNext(RoadId road_id, SectionId section_id, LaneId lane_id)
Return a list of pointers to all lanes from a lane (using road and junction info).
void CreateLaneWidth(Lane *lane, const double s, const double a, const double b, const double c, const double d)
void SolveSignalReferencesAndTransforms()
Solves the signal references in the road
void CreateLaneVisibility(Lane *lane, const double s, const double forward, const double back, const double left, const double right)
void CreatePointersBetweenRoadSegments()
Create the pointers between RoadSegments based on the ids.
Road * GetRoad(const RoadId road_id)
void SetRoadLaneLink(const RoadId road_id, const SectionId section_index, const LaneId lane_id, const Lane::LaneType lane_type, const bool lane_level, const LaneId predecessor, const LaneId successor)
void CreateLaneMaterial(Lane *lane, const double s, const std::string surface, const double friction, const double roughness)
void CheckSignalsOnRoads(Map &map)
Checks signals overlapping driving lanes and emits a warning
void AddRoadGeometrySpiral(carla::road::Road *road, const double s, const double x, const double y, const double hdg, const double length, const double curvStart, const double curvEnd)
void AddRoadGeometryLine(carla::road::Road *road, const double s, const double x, const double y, const double hdg, const double length)
Lane * GetEdgeLanePointer(RoadId road_id, bool from_start, LaneId lane_id)
Return the pointer to a lane object.
geom::GeoLocation _geo_reference
This file contains definitions of common data structures used in traffic manager.