82 auto elevation = std::make_unique<RoadInfoElevation>(s, a, b, c, d);
88 const std::string name,
95 const std::string orientation,
98 const std::vector<road::element::CrosswalkPoint> points) {
100 auto cross = std::make_unique<RoadInfoCrosswalk>(s, name, t, zOffset, hdg, pitch, roll, std::move(orientation), width, length, std::move(points));
108 const std::string restriction) {
128 const double outer) {
136 const std::string surface,
137 const double friction,
138 const double roughness) {
147 const std::string value) {
155 const double forward,
158 const double right) {
177 const int road_mark_id,
179 const std::string type,
180 const std::string weight,
181 const std::string color,
182 const std::string material,
184 std::string lane_change,
186 const std::string type_name,
187 const double type_width) {
193 if (lane_change ==
"increase") {
194 lc = RoadInfoMarkRecord::LaneChange::Increase;
195 }
else if (lane_change ==
"decrease") {
196 lc = RoadInfoMarkRecord::LaneChange::Decrease;
197 }
else if (lane_change ==
"none") {
198 lc = RoadInfoMarkRecord::LaneChange::None;
200 lc = RoadInfoMarkRecord::LaneChange::Both;
204 material, width, lc, height, type_name, type_width));
209 const int road_mark_id,
212 const double tOffset,
214 const std::string rule,
215 const double width) {
218 for (; !it.IsAtEnd(); ++it) {
219 if (it->GetRoadMarkId() == road_mark_id) {
220 it->GetLines().emplace_back(std::make_unique<RoadInfoMarkTypeLine>(s, road_mark_id, length, space,
221 tOffset, rule, width));
232 const std::string ) {
243 const std::string name,
244 const std::string dynamic,
245 const std::string orientation,
246 const double zOffset,
247 const std::string country,
248 const std::string type,
249 const std::string subtype,
251 const std::string unit,
254 const std::string text,
255 const double hOffset,
291 signal->_using_inertial_position =
true;
304 const double zOffset,
305 const double hOffset,
309 signal->_road_id = road_id;
312 signal->_zOffset = zOffset;
313 signal->_hOffset = hOffset;
314 signal->_pitch = pitch;
315 signal->_roll = roll;
321 const double s_position,
322 const double t_position,
323 const std::string signal_reference_orientation) {
325 const double epsilon = 0.00001;
330 signal_id, road->
GetId(), fixed_s, t_position, signal_reference_orientation));
334 return road_info_signal;
346 const std::string dependency_id,
347 const std::string dependency_type) {
355 const std::string name,
369 road->_length = length;
370 road->_junction_id = junction_id;
371 (junction_id != -1) ? road->_is_junction =
true : road->_is_junction =
false;
372 road->_successor = successor;
373 road->_predecessor = predecessor;
390 const int32_t lane_id,
391 const uint32_t lane_type,
392 const bool lane_level,
393 const int32_t predecessor,
394 const int32_t successor) {
398 auto *lane = &((section->
_lanes.emplace(lane_id,
Lane()).first)->second);
402 lane->_lane_section = section;
403 lane->_level = lane_level;
405 lane->_successor = successor;
406 lane->_predecessor = predecessor;
417 const double length) {
419 const geom::Location location(
static_cast<float>(x),
static_cast<float>(y), 0.0f);
420 auto line_geometry = std::make_unique<GeometryLine>(
427 std::move(line_geometry))));
435 const std::string ) {
458 const double curvature) {
460 const geom::Location location(
static_cast<float>(x),
static_cast<float>(y), 0.0f);
461 auto arc_geometry = std::make_unique<GeometryArc>(
469 std::move(arc_geometry))));
479 const double curvStart,
480 const double curvEnd) {
483 const geom::Location location(
static_cast<float>(x),
static_cast<float>(y), 0.0f);
484 auto spiral_geometry = std::make_unique<GeometrySpiral>(
493 std::move(spiral_geometry))));
509 const geom::Location location(
static_cast<float>(x),
static_cast<float>(y), 0.0f);
510 auto poly3_geometry = std::make_unique<GeometryPoly3>(
520 std::move(poly3_geometry))));
538 const std::string p_range) {
541 if(p_range ==
"arcLength"){
547 const geom::Location location(
static_cast<float>(x),
static_cast<float>(y), 0.0f);
548 auto parampoly3_geometry = std::make_unique<GeometryParamPoly3>(
563 std::move(parampoly3_geometry))));
572 const ConId connection_id,
573 const RoadId incoming_road,
574 const RoadId connecting_road) {
582 const ConId connection_id,
591 std::set<road::ContId>&& controllers) {
626 return section->
GetLane(lane_id);
635 std::vector<Lane *> result;
665 if ((lane_id > 0 && s > 0) ||
668 if (next != 0 || (lane_id == 0 && next == 0)) {
676 }
else if (!next_is_junction) {
678 if (next != 0 || (lane_id == 0 && next == 0)) {
687 auto next_road_as_junction =
static_cast<JuncId>(next_road);
689 for (
auto opt : options) {
701 std::vector<std::pair<RoadId, LaneId>> result;
705 if (junction ==
nullptr) {
712 if (con.second.incoming_road == road_id) {
716 result.push_back(std::make_pair(con.second.connecting_road, 0));
719 for (
auto link : con.second.lane_links) {
721 if (link.from == lane_id) {
723 result.push_back(std::make_pair(con.second.connecting_road, link.to));
737 for (
auto §ion : road.second._lane_sections) {
738 for (
auto &lane : section.second._lanes) {
741 lane.second._next_lanes =
GetLaneNext(road.first, section.second._id, lane.first);
744 for (
auto next_lane : lane.second._next_lanes) {
747 next_lane->_prev_lanes.push_back(&lane.second);
756 for (
auto §ion : road.second._lane_sections) {
757 for (
auto &lane : section.second._lanes) {
760 for (
auto next_lane : lane.second._next_lanes) {
763 if (next_lane->GetRoad() != &road.second) {
764 if (std::find(road.second._nexts.begin(), road.second._nexts.end(),
765 next_lane->GetRoad()) == road.second._nexts.end()) {
766 road.second._nexts.push_back(next_lane->GetRoad());
772 for (
auto prev_lane : lane.second._prev_lanes) {
775 if (prev_lane->GetRoad() != &road.second) {
776 if (std::find(road.second._prevs.begin(), road.second._prevs.end(),
777 prev_lane->GetRoad()) == road.second._prevs.end()) {
778 road.second._prevs.push_back(prev_lane->GetRoad());
792 point.
location.
z +=
static_cast<float>(signal->_zOffset);
802 signal_reference->_signal =
807 auto& signal = signal_pair.second;
808 if (signal->_using_inertial_position) {
813 transform.location = transform.location +
816 signal->_transform = transform;
826 for(
const auto& controller : junction.second._controllers) {
829 if( it->second !=
nullptr ){
830 it->second->_junctions.insert(junction.first);
831 for(
const auto & signal : it->second->_signals) {
833 if( signal_it->second !=
nullptr ){
834 signal_it->second->_controllers.insert(controller);
845 auto* junction = map.
GetJunction(junctionpair.first);
847 const int number_intervals = 10;
849 float minx = std::numeric_limits<float>::max();
850 float miny = std::numeric_limits<float>::max();
851 float minz = std::numeric_limits<float>::max();
852 float maxx = -std::numeric_limits<float>::max();
853 float maxy = -std::numeric_limits<float>::max();
854 float maxz = -std::numeric_limits<float>::max();
857 if (position.x < minx) {
860 if (position.y < miny) {
863 if (position.z < minz) {
867 if (position.x > maxx) {
870 if (position.y > maxy) {
873 if (position.z > maxz) {
878 for (
auto &waypoint_p : waypoints) {
879 auto &waypoint_start = waypoint_p.first;
880 auto &waypoint_end = waypoint_p.second;
881 double interval = (waypoint_end.s - waypoint_start.s) /
static_cast<double>(number_intervals);
882 auto next_wp = waypoint_end;
885 get_min_max(location);
887 next_wp = waypoint_start;
890 get_min_max(location);
892 for (
int i = 0; i < number_intervals; ++i) {
893 if (interval < std::numeric_limits<double>::epsilon())
895 auto next = map.
GetNext(next_wp, interval);
897 next_wp = next.back();
901 get_min_max(location);
912 const ContId controller_id,
913 const std::string controller_name,
914 const uint32_t controller_sequence,
915 const std::set<road::SignId>&& signals) {
921 std::make_unique<Controller>(controller_id, controller_name, controller_sequence)));
927 controller_pair.first->second->_signals = std::move(signals);
931 for(
auto signal: signals) {
932 auto it = signals_map.find(signal);
933 if(it != signals_map.end()) {
934 it->second->_controllers.insert(signal);
941 auto& junction = junctionpair.second;
948 if (signal_reference->_validities.size() == 0) {
949 Road* road =
GetRoad(signal_reference->GetRoadId());
951 switch (signal_reference->GetOrientation()) {
955 for (
const auto* lane : lanes) {
956 auto lane_id = lane->GetId();
957 if(lane_id > max_lane) {
961 if(min_lane <= max_lane) {
969 for (
const auto* lane : lanes) {
970 auto lane_id = lane->GetId();
971 if(lane_id < min_lane) {
975 if(min_lane <= max_lane) {
984 for (
const auto* lane : lanes) {
985 auto lane_id = lane->GetId();
986 if(lane_id > max_lane) {
990 if(min_lane <= max_lane) {
997 for (
const auto* lane : lanes) {
998 auto lane_id = lane->GetId();
999 if(lane_id < min_lane) {
1003 if(min_lane <= max_lane) {
1014 std::vector<element::RoadInfoSignal*> elements_to_remove;
1016 bool should_remove =
true;
1017 for (
auto & lane_validity : signal_reference->_validities) {
1018 if ( (lane_validity._from_lane != 0) ||
1019 (lane_validity._to_lane != 0)) {
1020 should_remove =
false;
1024 if (signal_reference->_validities.size() == 0) {
1025 should_remove =
false;
1027 if (should_remove) {
1028 elements_to_remove.push_back(signal_reference);
1031 for (
auto* element : elements_to_remove) {
1032 auto road_id = element->GetRoadId();
1034 road_info.erase(std::remove_if(road_info.begin(), road_info.end(),
1035 [=] (
auto& info_ptr) {
1036 return (info_ptr.get() == element);
1037 }), road_info.end());
1046 auto& signal = signal_pair.second;
1047 auto signal_position = signal->GetTransform().location;
1048 auto signal_rotation = signal->GetTransform().rotation;
1049 auto closest_waypoint_to_signal =
1054 signal->GetName().find(
"Stencil_STOP") != std::string::npos ||
1055 signal->GetName().find(
"STATIC") != std::string::npos ||
1056 signal->_using_inertial_position) {
1059 if(closest_waypoint_to_signal) {
1060 auto road_transform = map.
ComputeTransform(closest_waypoint_to_signal.get());
1061 auto distance_to_road = (road_transform.location -signal_position).Length();
1062 double lane_width = map.
GetLaneWidth(closest_waypoint_to_signal.get());
1063 int displacement_direction = 1;
1067 while(distance_to_road < (lane_width * 0.7) && iter < MaxIter && displacement_direction != 0) {
1070 signal->GetSignalId(),
1071 "overlaps a driving lane. Moving out of the road...");
1074 auto right_waypoint = map.
GetRight(closest_waypoint_to_signal.get());
1077 auto left_waypoint = map.
GetLeft(closest_waypoint_to_signal.get());
1081 displacement_direction = 1;
1083 displacement_direction = -1;
1085 displacement_direction = 0;
1088 geom::Vector3D displacement = 1.f*(road_transform.GetRightVector()) *
1089 static_cast<float>(abs(lane_width))*0.2f;
1090 signal_position += (displacement * displacement_direction);
1091 signal_rotation = road_transform.rotation;
1092 closest_waypoint_to_signal =
1097 signal_position).Length();
1098 lane_width = map.
GetLaneWidth(closest_waypoint_to_signal.get());
1101 if(iter == MaxIter) {
1102 log_debug(
"Failed to find suitable place for signal.");
1105 signal->_transform.location = signal_position;
1106 signal->_transform.rotation = signal_rotation;
#define DEBUG_ASSERT(predicate)
#define RELEASE_ASSERT(pred)
static void ToLower(WritableRangeT &str)
static T Clamp(T a, T min=T(0), T max=T(1))
static constexpr T ToDegrees(T rad)
Connection * GetConnection(ConId id)
std::set< ContId > _controllers
std::unordered_map< ConId, Connection > & GetConnections()
std::unordered_map< ConId, Connection > _connections
LaneSection & Emplace(SectionId id, double s)
LaneSection & GetById(SectionId id)
double GetDistance() const
Lane * GetLane(const LaneId id)
std::map< LaneId, Lane > _lanes
LaneType
Can be used as flags
LaneId GetPredecessor() const
LaneId GetSuccessor() const
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 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 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 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.
std::unordered_map< RoadId, Road > _roads
Road & GetRoad(const RoadId id)
std::unordered_map< ContId, std::unique_ptr< Controller > > _controllers
std::unordered_map< JuncId, Junction > _junctions
bool ContainsRoad(RoadId id) const
std::unordered_map< JuncId, Junction > & GetJunctions()
Junction * GetJunction(JuncId id)
std::unordered_map< SignId, std::unique_ptr< Signal > > _signals
Lane::LaneType GetLaneType(Waypoint waypoint) const
double GetLaneWidth(Waypoint waypoint) const
boost::optional< element::Waypoint > GetClosestWaypointOnRoad(const geom::Location &location, int32_t lane_type=static_cast< int32_t >(Lane::LaneType::Driving)) const
========================================================================
boost::optional< Waypoint > GetRight(Waypoint waypoint) const
Return a waypoint at the lane of waypoint's right lane.
boost::optional< Waypoint > GetLeft(Waypoint waypoint) const
Return a waypoint at the lane of waypoint's left lane.
std::vector< Waypoint > GetNext(Waypoint waypoint, double distance) const
Return the list of waypoints at distance such that a vehicle at waypoint could drive to.
Junction * GetJunction(JuncId id)
geom::Transform ComputeTransform(Waypoint waypoint) const
std::vector< std::pair< Waypoint, Waypoint > > GetJunctionWaypoints(JuncId id, Lane::LaneType lane_type) const
Generate waypoints of the junction
std::unordered_map< road::RoadId, std::unordered_set< road::RoadId > > ComputeJunctionConflicts(JuncId id) const
RoadId GetPredecessor() const
Lane * GetPrevLane(const double s, const LaneId lane_id)
LaneSectionMap _lane_sections
RoadId GetSuccessor() const
LaneSection * GetStartSection(LaneId id)
Get the start section (from road coordinates s) given a lane id
Lane * GetNextLane(const double s, const LaneId lane_id)
Lane & GetLaneByDistance(double s, LaneId lane_id)
std::vector< Lane * > GetLanesByDistance(double s)
Get all lanes from all lane sections in a specific s
element::DirectedPoint GetDirectedPointInNoLaneOffset(const double s) const
Returns a directed point on the center of the road (lane 0), with the corresponding laneOffset and el...
LaneSection * GetEndSection(LaneId id)
Get the end section (from road coordinates s) given a lane id
static bool IsTrafficLight(const std::string &type)
LaneChange
Can be used as flags
std::vector< LaneValidity > _validities
This file contains definitions of common data structures used in traffic manager.
static void log_debug(Args &&... args)
void AddLaneLink(LaneId from, LaneId to)
void ApplyLateralOffset(float lateral_offset)