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));
208 const int road_mark_id,
211 const double tOffset,
213 const std::string rule,
214 const double width) {
217 for (; !it.IsAtEnd(); ++it) {
218 if (it->GetRoadMarkId() == road_mark_id) {
219 it->GetLines().emplace_back(std::make_unique<RoadInfoMarkTypeLine>(s, road_mark_id, length, space,
220 tOffset, rule, width));
230 const std::string ) {
240 const std::string name,
241 const std::string dynamic,
242 const std::string orientation,
243 const double zOffset,
244 const std::string country,
245 const std::string type,
246 const std::string subtype,
248 const std::string unit,
251 const std::string text,
252 const double hOffset,
288 signal->_using_inertial_position =
true;
301 const double zOffset,
302 const double hOffset,
306 signal->_road_id = road_id;
309 signal->_zOffset = zOffset;
310 signal->_hOffset = hOffset;
311 signal->_pitch = pitch;
312 signal->_roll = roll;
318 const double s_position,
319 const double t_position,
320 const std::string signal_reference_orientation) {
322 const double epsilon = 0.00001;
328 signal_id, road->
GetId(), fixed_s, t_position, signal_reference_orientation));
334 return road_info_signal;
347 const std::string dependency_id,
348 const std::string dependency_type) {
357 const std::string name,
391 const int32_t lane_id,
392 const uint32_t lane_type,
393 const bool lane_level,
394 const int32_t predecessor,
395 const int32_t successor) {
399 auto *lane = &((section->
_lanes.emplace(lane_id,
Lane()).first)->second);
404 lane->
_level = lane_level;
418 const double length) {
420 const geom::Location location(
static_cast<float>(x),
static_cast<float>(y), 0.0f);
422 auto line_geometry = std::make_unique<GeometryLine>(
438 const std::string ) {
465 const double curvature) {
469 const geom::Location location(
static_cast<float>(x),
static_cast<float>(y), 0.0f);
471 auto arc_geometry = std::make_unique<GeometryArc>(
480 std::move(arc_geometry))));
491 const double curvStart,
492 const double curvEnd) {
496 const geom::Location location(
static_cast<float>(x),
static_cast<float>(y), 0.0f);
498 auto spiral_geometry = std::make_unique<GeometrySpiral>(
508 std::move(spiral_geometry))));
525const geom::Location location(
static_cast<float>(x),
static_cast<float>(y), 0.0f);
526auto poly3_geometry = std::make_unique<GeometryPoly3>(
536 std::move(poly3_geometry))));
553 const std::string p_range) {
556 if(p_range ==
"arcLength"){
562 const geom::Location location(
static_cast<float>(x),
static_cast<float>(y), 0.0f);
563 auto parampoly3_geometry = std::make_unique<GeometryParamPoly3>(
578 std::move(parampoly3_geometry))));
586 const ConId connection_id,
587 const RoadId incoming_road,
588 const RoadId connecting_road) {
596 const ConId connection_id,
605 std::set<road::ContId>&& controllers) {
643 return section->
GetLane(lane_id);
651 std::vector<Lane *> result;
682 if ((lane_id > 0 && s > 0) ||
685 if (next != 0 || (lane_id == 0 && next == 0)) {
693 }
else if (!next_is_junction) {
695 if (next != 0 || (lane_id == 0 && next == 0)) {
703 auto next_road_as_junction =
static_cast<JuncId>(next_road);
705 for (
auto opt : options) {
717 std::vector<std::pair<RoadId, LaneId>> result;
721if (junction ==
nullptr) {
726for (
auto con : junction->_connections) {
728 if (con.second.incoming_road == road_id) {
731 result.push_back(std::make_pair(con.second.connecting_road, 0));
734 for (
auto link : con.second.lane_links) {
736 if (link.from == lane_id) {
738 result.push_back(std::make_pair(con.second.connecting_road, link.to));
752 for (
auto §ion : road.second._lane_sections) {
753 for (
auto &lane : section.second._lanes) {
759 for (
auto next_lane : lane.second._next_lanes) {
762 next_lane->_prev_lanes.push_back(&lane.second);
771 for (
auto §ion : road.second._lane_sections) {
772 for (
auto &lane : section.second._lanes) {
775 for (
auto next_lane : lane.second._next_lanes) {
778 if (next_lane->GetRoad() != &road.second) {
779 if (std::find(road.second.
_nexts.begin(), road.second.
_nexts.end(),
780 next_lane->GetRoad()) == road.second.
_nexts.end()) {
781 road.second.
_nexts.push_back(next_lane->GetRoad());
787 for (
auto prev_lane : lane.second._prev_lanes) {
790 if (prev_lane->GetRoad() != &road.second) {
791 if (std::find(road.second.
_prevs.begin(), road.second.
_prevs.end(),
792 prev_lane->GetRoad()) == road.second.
_prevs.end()) {
793 road.second.
_prevs.push_back(prev_lane->GetRoad());
807 point.
location.
z +=
static_cast<float>(signal->_zOffset);
825 auto& signal = signal_pair.second;
826 if (signal->_using_inertial_position) {
834 transform.location = transform.location +
838 signal->_transform = transform;
850 for(
const auto& junction :
_map_data._junctions) {
852 for(
const auto& controller : junction.second._controllers) {
856 if( it->second !=
nullptr ){
858 it->second->_junctions.insert(junction.first);
860 for(
const auto & signal : it->second->_signals) {
863 if( signal_it->second !=
nullptr ){
865 signal_it->second->_controllers.insert(controller);
876 for (
auto &junctionpair : map._data.GetJunctions()) {
877 auto* junction = map.GetJunction(junctionpair.first);
879 const int number_intervals = 10;
882 float minx = std::numeric_limits<float>::max();
883 float miny = std::numeric_limits<float>::max();
884 float minz = std::numeric_limits<float>::max();
885 float maxx = -std::numeric_limits<float>::max();
886 float maxy = -std::numeric_limits<float>::max();
887 float maxz = -std::numeric_limits<float>::max();
892 if (position.x < minx) {
895 if (position.y < miny) {
898 if (position.z < minz) {
903 if (position.x > maxx) {
906 if (position.y > maxy) {
909 if (position.z > maxz) {
915 for (
auto &waypoint_p : waypoints) {
916 auto &waypoint_start = waypoint_p.first;
917 auto &waypoint_end = waypoint_p.second;
918 double interval = (waypoint_end.s - waypoint_start.s) /
static_cast<double>(number_intervals);
919 auto next_wp = waypoint_end;
920 auto location = map.ComputeTransform(next_wp).location;
923 get_min_max(location);
925 next_wp = waypoint_start;
926 location = map.ComputeTransform(next_wp).location;
929 get_min_max(location);
932 for (
int i = 0; i < number_intervals; ++i) {
933 if (interval < std::numeric_limits<double>::epsilon())
935 auto next = map.GetNext(next_wp, interval);
937 next_wp = next.back();
940 location = map.ComputeTransform(next_wp).location;
941 get_min_max(location);
954 const ContId controller_id,
955 const std::string controller_name,
956 const uint32_t controller_sequence,
957 const std::set<road::SignId>&& signals) {
963 std::make_unique<Controller>(controller_id, controller_name, controller_sequence)));
969 controller_pair.first->second->_signals = std::move(signals);
973 for(
auto signal: signals) {
974 auto it = signals_map.find(signal);
975 if(it != signals_map.end()) {
976 it->second->_controllers.insert(controller_id);
983 for (
auto &junctionpair : map._data.GetJunctions()) {
984 auto& junction = junctionpair.second;
1001 for (
const auto* lane : lanes) {
1002 auto lane_id = lane->
GetId();
1003 if(lane_id > max_lane) {
1007 if(min_lane <= max_lane) {
1015 for (
const auto* lane : lanes) {
1016 auto lane_id = lane->
GetId();
1017 if(lane_id < min_lane) {
1021 if(min_lane <= max_lane) {
1030 for (
const auto* lane : lanes) {
1031 auto lane_id = lane->
GetId();
1032 if(lane_id > max_lane) {
1036 if(min_lane <= max_lane) {
1044for (
const auto* lane : lanes) {
1045 auto lane_id = lane->
GetId();
1046 if(lane_id < min_lane) {
1051if(min_lane <= max_lane) {
1060 std::vector<element::RoadInfoSignal*> elements_to_remove;
1062 bool should_remove =
true;
1063 for (
auto & lane_validity : signal_reference->_validities) {
1064 if ( (lane_validity._from_lane != 0) ||
1065 (lane_validity._to_lane != 0)) {
1066 should_remove =
false;
1071 should_remove =
false;
1074 if (should_remove) {
1075 elements_to_remove.push_back(signal_reference);
1079 for (
auto* element : elements_to_remove) {
1080 auto road_id = element->GetRoadId();
1082 road_info.erase(std::remove_if(road_info.begin(), road_info.end(),
1083 [=] (
auto& info_ptr) {
1084 return (info_ptr.get() == element);
1085 }), road_info.end());
1093 for (
auto& signal_pair : map._data._signals) {
1094 auto& signal = signal_pair.second;
1095 auto signal_position = signal->GetTransform().location;
1096 auto signal_rotation = signal->GetTransform().rotation;
1097 auto closest_waypoint_to_signal =
1098 map.GetClosestWaypointOnRoad(signal_position,
1103 signal->GetName().find(
"Stencil_STOP") != std::string::npos ||
1104 signal->GetName().find(
"STATIC") != std::string::npos ||
1105 signal->_using_inertial_position) {
1109 if(closest_waypoint_to_signal) {
1110 auto road_transform = map.ComputeTransform(closest_waypoint_to_signal.get());
1111 auto distance_to_road = (road_transform.location - signal_position).Length();
1112 double lane_width = map.GetLaneWidth(closest_waypoint_to_signal.get());
1113 int displacement_direction = 1;
1118 while(distance_to_road < (lane_width * 0.7) && iter < MaxIter && displacement_direction != 0) {
1121 signal->GetSignalId(),
1122 "overlaps a driving lane. Moving out of the road...");
1125 auto right_waypoint = map.GetRight(closest_waypoint_to_signal.get());
1126auto right_lane_type = (right_waypoint) ?
1127 map.GetLaneType(right_waypoint.get()) :
1130auto left_waypoint = map.GetLeft(closest_waypoint_to_signal.get());
1131auto left_lane_type = (left_waypoint) ?
1132 map.GetLaneType(left_waypoint.get()) :
1136 displacement_direction = 1;
1138 displacement_direction = -1;
1140 displacement_direction = 0;
1143geom::Vector3D displacement = 1.f*(road_transform.GetRightVector()) *
1144 static_cast<float>(abs(lane_width)) * 0.2f;
1146signal_position += (displacement * displacement_direction);
1147signal_rotation = road_transform.rotation;
1148closest_waypoint_to_signal =
1149 map.GetClosestWaypointOnRoad(signal_position,
1153 (map.ComputeTransform(closest_waypoint_to_signal.get()).location -
1154 signal_position).Length();
1155lane_width = map.GetLaneWidth(closest_waypoint_to_signal.get());
1159if(iter == MaxIter) {
1160 log_debug(
"Failed to find suitable place for signal.");
1163 signal->_transform.location = signal_position;
1164 signal->_transform.rotation = signal_rotation;
#define DEBUG_ASSERT(predicate)
#define RELEASE_ASSERT(pred)
地图类的前向声明,用于在LaneInvasionSensor类中可能的引用。
static void ToLower(WritableRangeT &str)
static T Clamp(T a, T min=T(0), T max=T(1))
static constexpr T ToDegrees(T rad)
carla::geom::BoundingBox _bounding_box
std::unordered_map< RoadId, std::unordered_set< RoadId > > _road_conflicts
Connection * GetConnection(ConId id)
std::set< ContId > _controllers
std::unordered_map< ConId, Connection > & GetConnections()
LaneSection & Emplace(SectionId id, double s)
LaneSection & GetById(SectionId id)
double GetDistance() const
Lane * GetLane(const LaneId id)
std::map< LaneId, Lane > _lanes
std::vector< Lane * > _next_lanes
LaneId GetPredecessor() const
LaneId GetSuccessor() const
LaneSection * _lane_section
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 // 用于临时存储所有道路和车道信息,直到地图构建完成,因此可以一...
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] // 移除车道有效性等于[0,0]的信号引用 as they have no ef...
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...
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
bool ContainsRoad(RoadId id) const
std::unordered_map< JuncId, Junction > & GetJunctions()
Junction * GetJunction(JuncId id)
std::unordered_map< SignId, std::unique_ptr< Signal > > _signals
RoadId GetPredecessor() const
Lane * GetPrevLane(const double s, const LaneId lane_id)
LaneSectionMap _lane_sections
RoadId GetSuccessor() const
std::vector< Road * > _nexts
std::vector< Road * > _prevs
LaneSection * GetStartSection(LaneId id)
获取给定车道 ID 的起始车道段
Lane * GetNextLane(const double s, const LaneId lane_id)
Lane & GetLaneByDistance(double s, LaneId lane_id)
std::vector< Lane * > GetLanesByDistance(double s)
在特定的 s 值获取所有车道
element::DirectedPoint GetDirectedPointInNoLaneOffset(const double s) const
返回指定距离的中心点(车道 0)的导向点,不考虑车道偏移
LaneSection * GetEndSection(LaneId id)
获取给定车道 ID 的结束车道段
static bool IsTrafficLight(const std::string &type)
std::vector< LaneValidity > _validities
SignalOrientation GetOrientation() const
static void log_debug(Args &&... args)
void AddLaneLink(LaneId from, LaneId to)
void ApplyLateralOffset(float lateral_offset)