/****************************************************************************/1// Eclipse SUMO, Simulation of Urban MObility; see https://eclipse.dev/sumo2// Copyright (C) 2001-2025 German Aerospace Center (DLR) and others.3// This program and the accompanying materials are made available under the4// terms of the Eclipse Public License 2.0 which is available at5// https://www.eclipse.org/legal/epl-2.0/6// This Source Code may also be made available under the following Secondary7// Licenses when the conditions for such availability set forth in the Eclipse8// Public License 2.0 are satisfied: GNU General Public License, version 29// or later which is available at10// https://www.gnu.org/licenses/old-licenses/gpl-2.0-standalone.html11// SPDX-License-Identifier: EPL-2.0 OR GPL-2.0-or-later12/****************************************************************************/13/// @file NBNode.h14/// @author Daniel Krajzewicz15/// @author Jakob Erdmann16/// @author Yun-Pang Floetteroed17/// @author Michael Behrisch18/// @date Tue, 20 Nov 200119///20// The representation of a single node21/****************************************************************************/22#pragma once23#include <config.h>2425#include <vector>26#include <deque>27#include <utility>28#include <string>29#include <set>30#include <memory>31#include <utils/common/StdDefs.h>32#include <utils/common/Named.h>33#include <utils/geom/Bresenham.h>34#include <utils/geom/GeomHelper.h>35#include <utils/common/VectorHelper.h>36#include <utils/geom/Position.h>37#include <utils/geom/PositionVector.h>38#include <utils/xml/SUMOXMLDefinitions.h>39#include "NBEdge.h"40#include "NBConnection.h"41#include "NBConnectionDefs.h"42#include "NBContHelper.h"434445// ===========================================================================46// class declarations47// ===========================================================================48class NBRequest;49class NBDistrict;50class OptionsCont;51class NBTrafficLightDefinition;52class NBTypeCont;53class NBTrafficLightLogicCont;54class NBDistrictCont;55class OutputDevice;565758// ===========================================================================59// class definitions60// ===========================================================================61/**62* @class NBNode63* @brief Represents a single node (junction) during network building64*/65class NBNode : public Named, public Parameterised {66friend class NBNodeCont;67friend class GNEJunction; // < used for visualization (netedit)68friend class NBNodesEdgesSorter; // < sorts the edges69friend class NBNodeTypeComputer; // < computes type70friend class NBEdgePriorityComputer; // < computes priorities of edges per intersection7172public:73/**74* @class ApproachingDivider75* @brief Computes lane-2-lane connections76*77* Being a bresenham-callback, this class computes which lanes78* are approached by the current lane (first callback parameter).79* The second callback parameter is the destination lane that is the80* middle of the computed lanes.81* The lanes are spreaded from this middle position both to left and right82* but may also be transposed in full when there is not enough space.83*/84class ApproachingDivider : public Bresenham::BresenhamCallBack {85public:86/**@brief Constructor87* @param[in] approaching The list of the edges that approach the outgoing edge88* @param[in] currentOutgoing The outgoing edge89*/90ApproachingDivider(const EdgeVector& approaching, NBEdge* currentOutgoing);9192/// @brief Destructor93~ApproachingDivider();9495/// @ get number of available lanes96int numAvailableLanes() const {97return (int)myAvailableLanes.size();98}99100/// @brief the bresenham-callback101void execute(const int src, const int dest);102103/// @brief the method that spreads the wished number of lanes from the lane given by the bresenham-call to both left and right104std::deque<int>* spread(int numLanes, int dest) const;105106private:107/// @brief The list of edges that approach the current edge108const EdgeVector& myApproaching;109110/// @brief The approached current edge111NBEdge* myCurrentOutgoing;112113/// @brief The available lanes to which connections shall be built114std::vector<int> myAvailableLanes;115116/// directions from each incoming edge to the outgoing edge117std::vector<LinkDirection> myDirections;118119/// @brief number of straight connections to the outgoing edge120int myNumStraight;121122/// @brief whether the outgoing edge is exclusively used by bikes123bool myIsBikeEdge;124125private:126/// @brief Invalidated assignment operator.127ApproachingDivider& operator=(const ApproachingDivider&) = delete;128129};130131/** @class Crossing132* @brief A definition of a pedestrian crossing133*/134class Crossing final : public Parameterised {135public:136/// @brief constructor137Crossing(const NBNode* _node, const EdgeVector& _edges, double _width, bool _priority, int _customTLIndex, int _customTLIndex2, const PositionVector& _customShape);138/// @brief The parent node of this crossing139const NBNode* node;140/// @brief The edges being crossed141EdgeVector edges;142/// @brief The crossing's shape143PositionVector shape;144/// @brief The outline shape for this crossing145PositionVector outlineShape;146/// @brief This crossing's width147double customWidth;148/// @brief This crossing's width149double width;150/// @brief the (edge)-id of this crossing151std::string id;152/// @brief the lane-id of the previous walkingArea153std::string prevWalkingArea;154/// @brief the lane-id of the next walkingArea155std::string nextWalkingArea;156/// @brief whether the pedestrians have priority157bool priority;158/// @brief optional customShape for this crossing159PositionVector customShape;160/// @brief the traffic light index of this crossing (if controlled)161int tlLinkIndex;162int tlLinkIndex2;163/// @brief the custom traffic light index of this crossing (if controlled)164int customTLIndex;165int customTLIndex2;166/// @brief The id of the traffic light that controls this connection167std::string tlID;168/// @brief whether this crossing is valid (and can be written to the net.xml). This is needed for netedit because validity can only be checked during junction computation169bool valid;170};171172173/** @struct WalkingArea174* @brief A definition of a pedestrian walking area175*/176struct WalkingArea {177/// @brief constructor178WalkingArea(const std::string& _id, double _width) :179id(_id),180width(_width) {181}182/// @brief the (edge)-id of this walkingArea183std::string id;184/// @brief This lane's width185double width;186/// @brief This lane's width187double length = INVALID_DOUBLE;188/// @brief The polygonal shape189PositionVector shape;190/// @brief the lane-id of the next crossing(s)191std::vector<std::string> nextCrossings;192/// @brief the lane-id of the previous crossing(s)193std::vector<std::string> prevCrossings;194/// @brief the lane-id of the next sidewalk lane or ""195std::vector<std::string> nextSidewalks;196/// @brief the lane-id of the previous sidewalk lane or ""197std::vector<std::string> prevSidewalks;198/// @brief whether this walkingArea has a custom shape199bool hasCustomShape = false;200/// @brief minimum number of edges crossed by nextCrossings201int minNextCrossingEdges = std::numeric_limits<int>::max();202/// @brief minimum number of edges crossed by incoming crossings203int minPrevCrossingEdges = std::numeric_limits<int>::max();204/// @brief reference edges that uniquely identify this walkingarea205std::set<const NBEdge*, ComparatorIdLess> refEdges;206};207208struct WalkingAreaCustomShape {209std::set<const NBEdge*, ComparatorIdLess> edges;210PositionVector shape;211double width;212};213214/// @brief edge directions (for pedestrian related stuff)215static const int FORWARD;216static const int BACKWARD;217218/// @brief unspecified lane width219static const double UNSPECIFIED_RADIUS;220221/// @brief flags for controlling shape generation222static const int AVOID_WIDE_RIGHT_TURN;223static const int AVOID_WIDE_LEFT_TURN;224static const int FOUR_CONTROL_POINTS;225static const int AVOID_INTERSECTING_LEFT_TURNS;226static const int SCURVE_IGNORE;227static const int INDIRECT_LEFT;228229public:230/**@brief Constructor231* @param[in] id The id of the node232* @param[in] position The position of the node233* @param[in] type The type of the node234*/235NBNode(const std::string& id, const Position& position, SumoXMLNodeType type);236237/**@brief Constructor238* @param[in] id The id of the node239* @param[in] position The position of the node240* @param[in] district The district this district node represents, 0 means no district node241*/242NBNode(const std::string& id, const Position& position, NBDistrict* district = 0);243244/// @brief Destructor245~NBNode();246247/**@brief Resets initial values248* @param[in] position The position of the node249* @param[in] type The type of the node250* @param[in] updateEdgeGeometries Whether the geometires of all251* connected edges shall be updated252*/253void reinit(const Position& position, SumoXMLNodeType type,254bool updateEdgeGeometries = false);255256/// @name Atomar getter methods257/// @{258/// @brief Returns the position of this node259inline const Position& getPosition() const {260return myPosition;261}262263/// @brief Returns a position that is guaranteed to lie within the node shape264Position getCenter() const;265266/// @brief Returns this node's incoming edges (The edges which yield in this node)267inline const EdgeVector& getIncomingEdges() const {268return myIncomingEdges;269}270271/// @brief Returns this node's outgoing edges (The edges which start at this node)272inline const EdgeVector& getOutgoingEdges() const {273return myOutgoingEdges;274}275276/// @brief Returns all edges which participate in this node (Edges that start or end at this node)277inline const EdgeVector& getEdges() const {278return myAllEdges;279}280281/**@brief Returns the type of this node282* @see SumoXMLNodeType283*/284inline SumoXMLNodeType getType() const {285return myType;286}287288/// @brief Returns the turning radius of this node289inline double getRadius() const {290return myRadius;291}292293/// @brief Returns the keepClear flag294inline bool getKeepClear() const {295return myKeepClear;296}297298/// @brief Returns hint on how to compute right of way299inline RightOfWay getRightOfWay() const {300return myRightOfWay;301}302303/// @brief Returns fringe type304inline FringeType getFringeType() const {305return myFringeType;306}307308/// @brief Returns intersection name309inline const std::string& getName() const {310return myName;311}312/// @}313314/// @name Methods for dealing with assigned traffic lights315/// @{316/**@brief Adds a traffic light to the list of traffic lights that control this node317* @param[in] tld The traffic light that controls this node318*/319void addTrafficLight(NBTrafficLightDefinition* tlDef);320321/// @brief Removes the given traffic light from this node322void removeTrafficLight(NBTrafficLightDefinition* tlDef);323324/// @brief Removes all references to traffic lights that control this tls325void removeTrafficLights(bool setAsPriority = false);326327/**@brief Returns whether this node is controlled by any tls328* @return Whether a traffic light was assigned to this node329*/330bool isTLControlled() const {331return myTrafficLights.size() != 0;332}333334335/// @brief whether this node was marked as having a signal in the (OSM) input336bool hadSignal() const;337338/// @brief Returns the traffic lights that were assigned to this node (The set of tls that control this node)339const std::set<NBTrafficLightDefinition*>& getControllingTLS() const {340return myTrafficLights;341}342343/// @brief causes the traffic light to be computed anew344void invalidateTLS(NBTrafficLightLogicCont& tlCont, bool addedConnections, bool removedConnections);345346/// @brief patches loaded signal plans by modifying lane indices above threshold by the given offset347void shiftTLConnectionLaneIndex(NBEdge* edge, int offset, int threshold = -1);348/// @}349350351/// @name Prunning the input352/// @{353354/**@brief Removes edges which are both incoming and outgoing into this node355*356* If given, the connections to other edges participating in this node are updated357*358* @param[in, opt. changed] dc The districts container to update359* @param[in, opt. changed] ec The edge container to remove the edges from360* @param[in, opt. changed] tc The traffic lights container to update361* @return The number of removed edges362*/363int removeSelfLoops(NBDistrictCont& dc, NBEdgeCont& ec, NBTrafficLightLogicCont& tc);364/// @}365366367/// @name Applying offset368/// @{369/**@brief Applies an offset to the node370* @param[in] xoff The x-offset to apply371* @param[in] yoff The y-offset to apply372*/373void reshiftPosition(double xoff, double yoff);374375/// @brief ensure consistency between input and output geometries376void roundGeometry();377378/// @brief mirror coordinates along the x-axis379void mirrorX();380/// @}381382/// @brief adds an incoming edge383void addIncomingEdge(NBEdge* edge);384385/// @brief adds an outgoing edge386void addOutgoingEdge(NBEdge* edge);387388/// @brief computes the connections of lanes to edges389void computeLanes2Lanes();390391/// @brief computes the node's type, logic and traffic light392void computeLogic(const NBEdgeCont& ec);393394/// @brief compute right-of-way logic for all lane-to-lane connections395void computeLogic2(bool checkLaneFoes);396397/// @brief compute keepClear status for all connections398void computeKeepClear();399400/// @brief writes the XML-representation of the logic as a bitset-logic XML representation401bool writeLogic(OutputDevice& into) const;402403/// @brief get the 'foes' string (conflict bit set) of the right-of-way logic404const std::string getFoes(int linkIndex) const;405406/// @brief get the 'response' string (right-of-way bit set) of the right-of-way logic407const std::string getResponse(int linkIndex) const;408409/// @brief whether there are conflicting streams of traffic at this node410bool hasConflict() const;411412/// @brief whether the given edge has a conflicting stream of traffic at this node413bool hasConflict(const NBEdge* e) const;414415/// @brief Returns something like the most unused direction Should only be used to add source or sink nodes416Position getEmptyDir() const;417418/**@brief Returns whether the given edge ends at this node419* @param[in] e The edge420* @return Whether the given edge is one of this node's incoming edges421*/422bool hasIncoming(const NBEdge* const e) const;423424/**@brief Returns whether the given edge starts at this node425* @param[in] e The edge426* @return Whether the given edge is one of this node's outgoing edges427*/428bool hasOutgoing(const NBEdge* const e) const;429430/// @brief returns the opposite incoming edge of certain edge431NBEdge* getOppositeIncoming(NBEdge* e) const;432433/// @brief invalidate incoming connections434void invalidateIncomingConnections(bool reallowSetting = false);435436/// @brief invalidate outgoing connections437void invalidateOutgoingConnections(bool reallowSetting = false);438439/// @brief remove duble edges440void removeDoubleEdges();441442/// @brief get connection to certain node443NBEdge* getConnectionTo(NBNode* n) const;444445/// @brief add shorted link FOES446void addSortedLinkFoes(const NBConnection& mayDrive, const NBConnection& mustStop);447448/// @brief get possibly splitted incoming edge449NBEdge* getPossiblySplittedIncoming(const std::string& edgeid);450451/// @brief get possibly splitted outgoing edge452NBEdge* getPossiblySplittedOutgoing(const std::string& edgeid);453454/// @brief Removes edge from this node and optionally removes connections as well455void removeEdge(NBEdge* edge, bool removeFromConnections = true);456457/**@brief Computes whether the given connection is a left mover across the junction458*459* It is assumed, that it is a left-mover if the clockwise angle is lower460* than the counter-clockwise angle.461*462* @param[in] from The incoming edge (the begin of the connection)463* @param[in] from The outgoing edge (the end of the connection)464* @return Whether the described connection is a left-mover465*/466bool isLeftMover(const NBEdge* const from, const NBEdge* const to) const;467468/**@brief Returns the information whether the described flow must let any other flow pass469* @param[in] from The connection's start edge470* @param[in] to The connection's end edge471* @param[in] fromLane The lane the connection start at472* @param[in] toLane The lane the connection ends at473* @param[in] includePedCrossings Whether braking due to a pedestrian crossing counts474* @return Whether the described connection must brake (has higher priorised foes)475*/476bool mustBrake(const NBEdge* const from, const NBEdge* const to, int fromLane, int toLane, bool includePedCrossings) const;477478/**@brief Returns the information whether the described flow must brake for the given crossing479* @param[in] from The connection's start edge480* @param[in] to The connection's end edge481* @param[in] crossing The pedestrian crossing to check482* @return Whether the described connection must brake (has higher priorised foes)483*/484bool mustBrakeForCrossing(const NBEdge* const from, const NBEdge* const to, const Crossing& crossing) const;485486/// @brief whether a connection to the given edge must brake for a crossing when leaving the intersection487bool brakeForCrossingOnExit(const NBEdge* to, LinkDirection dir, bool indirect) const;488489/// @brief return whether the given laneToLane connection is a right turn which must yield to a bicycle crossings490static bool rightTurnConflict(const NBEdge* from, const NBEdge* to, int fromLane,491const NBEdge* prohibitorFrom, const NBEdge* prohibitorTo, int prohibitorFromLane);492493/// @brief whether one of multple connections from the same edge targeting the same lane must yield494bool mergeConflictYields(const NBEdge* from, int fromLane, int fromLaneFoe, NBEdge* to, int toLane) const;495496/// @brief whether multiple connections from the same edge target the same lane497bool mergeConflict(const NBEdge* from, const NBEdge::Connection& con,498const NBEdge* prohibitorFrom, const NBEdge::Connection& prohibitorCon, bool foes) const;499500/// @brief whether the foe connections is oncoming on the same lane501bool bidiConflict(const NBEdge* from, const NBEdge::Connection& con,502const NBEdge* prohibitorFrom, const NBEdge::Connection& prohibitorCon, bool foes) const;503504bool zipperConflict(const NBEdge* incoming, const NBEdge* outgoing, int fromLane, int toLane) const;505506/// @brief return whether the given laneToLane connection originate from the same edge and are in conflict due to turning across each other507bool turnFoes(const NBEdge* from, const NBEdge* to, int fromLane,508const NBEdge* from2, const NBEdge* to2, int fromLane2,509bool lefthand = false) const;510511/**@brief Returns the information whether "prohibited" flow must let "prohibitor" flow pass512* @param[in] possProhibitedFrom The maybe prohibited connection's begin513* @param[in] possProhibitedTo The maybe prohibited connection's end514* @param[in] possProhibitorFrom The maybe prohibiting connection's begin515* @param[in] possProhibitorTo The maybe prohibiting connection's end516* @param[in] regardNonSignalisedLowerPriority Whether the right of way rules without traffic lights shall be regarded517* @return Whether the second flow prohibits the first one518*/519bool forbids(const NBEdge* const possProhibitorFrom, const NBEdge* const possProhibitorTo,520const NBEdge* const possProhibitedFrom, const NBEdge* const possProhibitedTo,521bool regardNonSignalisedLowerPriority) const;522523/**@brief Returns the information whether the given flows cross524* @param[in] from1 The starting edge of the first stream525* @param[in] to1 The ending edge of the first stream526* @param[in] from2 The starting edge of the second stream527* @param[in] to2 The ending edge of the second stream528* @return Whether both stream are foes (cross)529*/530bool foes(const NBEdge* const from1, const NBEdge* const to1,531const NBEdge* const from2, const NBEdge* const to2) const;532533/**@brief Returns the representation of the described stream's direction534* @param[in] incoming The edge the stream starts at535* @param[in] outgoing The edge the stream ends at536* @param[in] leftHand Whether a lefthand network is being built. Should only be set at writing time537* @return The direction of the stream538*/539LinkDirection getDirection(const NBEdge* const incoming, const NBEdge* const outgoing, bool leftHand = false) const;540541/// @brief get link state542LinkState getLinkState(const NBEdge* incoming, const NBEdge* outgoing,543int fromLane, int toLane, bool mayDefinitelyPass, const std::string& tlID) const;544545/**@brief Compute the junction shape for this node546* @param[in] mismatchThreshold The threshold for warning about shapes which are away from myPosition547*/548void computeNodeShape(double mismatchThreshold);549550/// @brief update geometry of node and surrounding edges551void updateSurroundingGeometry();552553/// @brief retrieve the junction shape554const PositionVector& getShape() const;555556/// @brief set the junction shape557void setCustomShape(const PositionVector& shape);558559/// @brief reset node shape560void resetShape() {561myPoly.clear();562}563564/// @brief set the turning radius565void setRadius(double radius) {566myRadius = radius;567}568569/// @brief set the keepClear flag570void setKeepClear(bool keepClear) {571myKeepClear = keepClear;572}573574/// @brief set method for computing right-of-way575void setRightOfWay(RightOfWay rightOfWay) {576myRightOfWay = rightOfWay;577}578579/// @brief set method for computing right-of-way580void setFringeType(FringeType fringeType) {581myFringeType = fringeType;582}583584/// @brief set intersection name585void setName(const std::string& name) {586myName = name;587}588589/// @brief return whether the shape was set by the user590bool hasCustomShape() const {591return myHaveCustomPoly;592}593594/// @brief check if node is removable595bool checkIsRemovable() const;596597/// @brief check if node is removable and return reason if not598bool checkIsRemovableReporting(std::string& reason) const;599600/// @brief get edges to join601std::vector<std::pair<NBEdge*, NBEdge*> > getEdgesToJoin() const;602603/// @chech if node is near district604bool isNearDistrict() const;605606/// @brief check if node is a district607bool isDistrict() const;608609/// @brief whether an internal junction should be built at from and respect other610bool needsCont(const NBEdge* fromE, const NBEdge* otherFromE,611const NBEdge::Connection& c, const NBEdge::Connection& otherC, bool checkOnlyTLS = false) const;612613/// @brief whether the connection must yield if the foe remains on the intersection after its phase ends614bool tlsStrandedConflict(const NBEdge* from, const NBEdge::Connection& c,615const NBEdge* foeFrom, const NBEdge::Connection& foe) const;616617618/**@brief Compute the shape for an internal lane619* @param[in] fromE The starting edge620* @param[in] con The connection for this internal lane621* @param[in] numPoints The number of geometry points for the internal lane622* @param[in] recordError The node itself if the displacement error during shape computation shall be recorded623* @return The shape of the internal lane624*/625PositionVector computeInternalLaneShape(const NBEdge* fromE, const NBEdge::Connection& con, int numPoints, NBNode* recordError = 0, int shapeFlag = 0) const;626627/**@brief Compute a smooth curve between the given geometries628* @param[in] begShape The geometry at the start629* @param[in] endShape The geometry at the end630* @param[in] numPoints The number of geometry points for the internal lane631* @param[in] isTurnaround Whether this shall be the shape for a turnaround632* @param[in] extrapolateBeg Extrapolation distance at the beginning633* @param[in] extrapolateEnd Extrapolation distance at the end634* @param[in] recordError The node itself if the displacement error during shape computation shall be recorded635* @return The shape of the internal lane636*/637PositionVector computeSmoothShape(const PositionVector& begShape, const PositionVector& endShape, int numPoints,638bool isTurnaround, double extrapolateBeg, double extrapolateEnd,639NBNode* recordError = 0, int shapeFlag = 0) const;640/// @brief get bezier control points641static PositionVector bezierControlPoints(const PositionVector& begShape, const PositionVector& endShape,642bool isTurnaround, double extrapolateBeg, double extrapolateEnd,643bool& ok, NBNode* recordError = 0, double straightThresh = DEG2RAD(5),644int shapeFlag = 0);645646/// @brief compute shape of indirect left turn647PositionVector indirectLeftShape(const PositionVector& begShape, const PositionVector& endShape, int numPoints) const;648649/// @brief compute the displacement error during s-curve computation650double getDisplacementError() const {651return myDisplacementError;652}653654/// @brief Replaces occurrences of the first edge within the list of incoming by the second Connections are remapped, too655void replaceIncoming(NBEdge* which, NBEdge* by, int laneOff);656657/// @brief Replaces occurrences of every edge from the given list within the list of incoming by the second Connections are remapped, too658void replaceIncoming(const EdgeVector& which, NBEdge* by);659660/// @brief Replaces occurrences of the first edge within the list of outgoing by the second Connections are remapped, too661void replaceOutgoing(NBEdge* which, NBEdge* by, int laneOff);662663/// @brief Replaces occurrences of every edge from the given list within the list of outgoing by the second Connections are remapped, too664void replaceOutgoing(const EdgeVector& which, NBEdge* by);665666/// @brief guess pedestrian crossings and return how many were guessed667int guessCrossings();668669/* @brief check whether a crossing should be build for the candiate edges and build 0 to n crossings670* @param[in] candidates The candidate vector of edges to be crossed671* @param[in] checkOnly Whether only checking (of user supplied) crossings shall be performed672* @return The number of crossings built673* */674int checkCrossing(EdgeVector candidates, bool checkOnly = false);675676/// @brief return true if there already exist a crossing with the same edges as the input677bool checkCrossingDuplicated(EdgeVector edges);678679/// @brief build internal lanes, pedestrian crossings and walking areas680double buildInnerEdges();681682/**@brief build pedestrian crossings683* @return The next index for creating internal lanes684**/685int buildCrossings();686687/**@brief build pedestrian walking areas and set connections from/to walkingAreas688* @param[in] cornerDetail The detail level when generating the inner curve689*/690void buildWalkingAreas(int cornerDetail, double joinMinDist);691692/// @brief build crossing outlines after walkingareas are finished693void buildCrossingOutlines();694695/// @brief build crossings, and walkingareas. Also removes invalid loaded crossings if wished696void buildCrossingsAndWalkingAreas();697698/// @brief return all edges that lie clockwise between the given edges699EdgeVector edgesBetween(const NBEdge* e1, const NBEdge* e2) const;700701/// @brief return true if the given edges are connected by a crossing702bool crossingBetween(const NBEdge* e1, const NBEdge* e2) const;703704/// @brief return true if the given pedestrian paths are connected at another junction within dist705bool alreadyConnectedPaths(const NBEdge* e1, const NBEdge* e2, double dist) const;706707/// @brief return true if the given sidewalks are separated by a fringe road708bool crossesFringe(const NBEdge* e1, const NBEdge* e2) const;709710/// @brief get prohibitions (BLocked connections)711const NBConnectionProhibits& getProhibitions() {712return myBlockedConnections;713}714715/// @brief whether this is structurally similar to a geometry node716bool geometryLike() const;717static bool geometryLike(const EdgeVector& incoming, const EdgeVector& outgoing);718719/// @brief update the type of this node as a roundabout720void setRoundabout();721722/// @brief return whether this node is part of a roundabout723bool isRoundabout() const;724725/// @brief add a pedestrian crossing to this node726NBNode::Crossing* addCrossing(EdgeVector edges, double width, bool priority, int tlIndex = -1, int tlIndex2 = -1,727const PositionVector& customShape = PositionVector::EMPTY, bool fromSumoNet = false, const Parameterised* params = nullptr);728729/// @brief add custom shape for walkingArea730void addWalkingAreaShape(EdgeVector edges, const PositionVector& shape, double width);731732/// @brief remove a pedestrian crossing from this node (identified by its edges)733void removeCrossing(const EdgeVector& edges);734735/// @brief discard all current (and optionally future) crossings736void discardAllCrossings(bool rejectAll);737738/// @brief discard previously built walkingareas (required for repeated computation by netedit)739void discardWalkingareas();740741/// @brief get num of crossings from sumo net742int numCrossingsFromSumoNet() const {743return myCrossingsLoadedFromSumoNet;744}745746/// @brief return this junctions pedestrian crossings747std::vector<Crossing*> getCrossings() const;748inline const std::vector<std::unique_ptr<Crossing> >& getCrossingsIncludingInvalid() const {749return myCrossings;750}751752/// @brief return this junctions pedestrian walking areas753inline const std::vector<WalkingArea>& getWalkingAreas() const {754return myWalkingAreas;755}756757const std::vector<WalkingAreaCustomShape>& getWalkingAreaCustomShapes() const {758return myWalkingAreaCustomShapes;759}760761/// @brief return the crossing with the given id762Crossing* getCrossing(const std::string& id) const;763764/// @brief return the crossing with the given Edges765Crossing* getCrossing(const EdgeVector& edges, bool hardFail = true) const;766767/// @brief return the walkingArea with the given ID768WalkingArea& getWalkingArea(const std::string& id);769770/* @brief set tl indices of this nodes crossing starting at the given index771* @return Whether a custom index was used772*/773bool setCrossingTLIndices(const std::string& tlID, int startIndex, bool ignoreCustom = false);774775/// @brief return the number of lane-to-lane connections at this junction (excluding crossings)776int numNormalConnections() const;777778/// @brief fix overlap779void avoidOverlap();780781/// @brief whether the given index must yield to the foeIndex while turing right on a red light782bool extraConflict(int index, int foeIndex) const;783784/// @brief sort all edge containers for this node785void sortEdges(bool useNodeShape);786787/// @brief return the index of the given connection788int getConnectionIndex(const NBEdge* from, const NBEdge::Connection& con) const;789790/**791* @class nodes_by_id_sorter792* @brief Used for sorting the cells by the begin time they describe793*/794class nodes_by_id_sorter {795public:796/// @brief Constructor797explicit nodes_by_id_sorter() { }798799/// @brief Comparing operator800int operator()(NBNode* n1, NBNode* n2) const {801return n1->getID() < n2->getID();802}803};804805/** @class edge_by_direction_sorter806* @brief Sorts outgoing before incoming edges807*/808class edge_by_direction_sorter {809public:810/// @brief constructor811explicit edge_by_direction_sorter(NBNode* n) : myNode(n) {}812813/// @brief operator of selection814int operator()(NBEdge* e1, NBEdge* e2) const {815UNUSED_PARAMETER(e2);816return e1->getFromNode() == myNode;817}818819private:820/// @brief The node to compute the relative angle of821NBNode* myNode;822823};824825/// @brief return whether the given type is a traffic light826static bool isTrafficLight(SumoXMLNodeType type);827828inline bool isTrafficLight() const {829return isTrafficLight(myType);830}831832/// @brief check if node is a simple continuation833bool isSimpleContinuation(bool checkLaneNumbers = true, bool checkWidth = false) const;834835/// @brief mark whether a priority road turns at this node836void markBentPriority(bool isBent) {837myIsBentPriority = isBent;838}839840/// @brief return whether a priority road turns at this node841bool isBentPriority() const {842return myIsBentPriority;843}844845/// @brief return whether a priority road turns at this node846bool typeWasGuessed() const {847return myTypeWasGuessed;848}849850/// @brief detects whether a given junction splits or merges lanes while keeping constant road width851bool isConstantWidthTransition() const;852853/// @brief return list of unique endpoint coordinates of all edges at this node854std::vector<std::pair<Position, std::string> > getEndPoints() const;855856/// @brief ensure connectivity for all vClasses857void recheckVClassConnections(NBEdge* currentOutgoing);858859/// @brief initialize signalized rail classes860static void initRailSignalClasses(const NBNodeCont& nc);861862private:863/// @brief sets the priorites in case of a priority junction864void setPriorityJunctionPriorities();865866/// @brief returns a list of edges which are connected to the given outgoing edge867void getEdgesThatApproach(NBEdge* currentOutgoing, EdgeVector& approaching);868869/// @brief replace incoming connections prohibitions870void replaceInConnectionProhibitions(NBEdge* which, NBEdge* by, int whichLaneOff, int byLaneOff);871872/// @brief remap removed873void remapRemoved(NBTrafficLightLogicCont& tc, NBEdge* removed, const EdgeVector& incoming, const EdgeVector& outgoing);874875/// @brief return whether there is a non-sidewalk lane after the given index;876bool forbidsPedestriansAfter(std::vector<std::pair<NBEdge*, bool> > normalizedLanes, int startIndex);877878/// @brief returns the list of all edges sorted clockwise by getAngleAtNodeToCenter879EdgeVector getEdgesSortedByAngleAtNodeCenter() const;880881/// @brief check if is long enough882static bool isLongEnough(NBEdge* out, double minLength);883884/// @brief remove all traffic light definitions that are part of a joined tls885void removeJoinedTrafficLights();886887/// @brief displace lane shapes to account for change in lane width at this node888void displaceShapeAtWidthChange(const NBEdge* from, const NBEdge::Connection& con, PositionVector& fromShape, PositionVector& toShape) const;889890/// @brief returns whether sub is a subset of super891static bool includes(const std::set<const NBEdge*, ComparatorIdLess>& super,892const std::set<const NBEdge*, ComparatorIdLess>& sub);893894NBEdge* getNextCompatibleOutgoing(const NBEdge* incoming, SVCPermissions vehPerm, EdgeVector::const_iterator start, bool clockwise) const;895896/// @brief get the reduction in driving lanes at this junction897void getReduction(const NBEdge* in, const NBEdge* out, int& inOffset, int& inEnd, int& outOffset, int& outEnd, int& reduction) const;898899/// @brief helper function to add connections for unsatisfied modes900SVCPermissions findToLaneForPermissions(NBEdge* currentOutgoing, int fromLane, NBEdge* incoming, SVCPermissions unsatisfied);901902/// @brief check whether this edge has extra lanes on the right side903int addedLanesRight(NBEdge* out, int addedLanes) const;904905/// @brief check whether the candidate edge is more likely to be the straight continuation906bool isStraighter(const NBEdge* const incoming, const double angle, const SVCPermissions vehPerm, const int modeLanes, const NBEdge* const candidate) const;907908/// @brief return edges that permit passengers (either incoming or outgoing)909EdgeVector getPassengerEdges(bool incoming) const;910911/// @brief detect explict rail turns with potential geometry problem912static bool isExplicitRailNoBidi(const NBEdge* incoming, const NBEdge* outgoing);913914/// @brief geometry helper that cuts the first shape where bordered by the other two915PositionVector cutAtShapes(const PositionVector& cut, const PositionVector& border1, const PositionVector& border2, const PositionVector& def);916917/// @brief compute offset for centering path-across-street crossings918void patchOffset_pathAcrossStreet(double& offset);919920/// @brief whether the given rail connections at this node may run in unsignalized (right-of-way) mode921bool unsignalizedOperation() const;922923/// @brief ensure connectivity for all special vClass924void recheckSpecialConnections(NBEdge* incoming, NBEdge* currentOutgoing, SVCPermissions svcSpecial);925926/// @brief helper function for recheckSpecialConnections927bool avoidConfict(NBEdge* incoming, NBEdge* currentOutgoing, SVCPermissions svcSpecial, LinkDirection dir, int i);928929private:930/// @brief The position the node lies at931Position myPosition;932933/// @brief Vector of incoming edges934EdgeVector myIncomingEdges;935936/// @brief Vector of outgoing edges937EdgeVector myOutgoingEdges;938939/// @brief Vector of incoming and outgoing edges940EdgeVector myAllEdges;941942/// @brief Vector of crossings943std::vector<std::unique_ptr<Crossing> > myCrossings;944945/// @brief Vector of walking areas946std::vector<WalkingArea> myWalkingAreas;947948/// @brief Vector of custom walking areas shapes949std::vector<WalkingAreaCustomShape> myWalkingAreaCustomShapes;950951/// @brief The type of the junction952SumoXMLNodeType myType;953954/// @brief The container for connection block dependencies955NBConnectionProhibits myBlockedConnections;956957/// @brief The district the node is the centre of958NBDistrict* myDistrict;959960/// @brief the (outer) shape of the junction961PositionVector myPoly;962963/// @brief whether this nodes shape was set by the user964bool myHaveCustomPoly;965966/// @brief Node requests967NBRequest* myRequest;968969/// @brief traffic lights of node970std::set<NBTrafficLightDefinition*> myTrafficLights;971972/// @brief the turning radius (for all corners) at this node in m.973double myRadius;974975/// @brief whether the junction area must be kept clear976bool myKeepClear;977978/// @brief how to compute right of way for this node979RightOfWay myRightOfWay;980981/// @brief fringe type of this node982FringeType myFringeType;983984/// @brief The intersection name (or whatever arbitrary string you wish to attach)985std::string myName;986987/// @brief whether to discard all pedestrian crossings988bool myDiscardAllCrossings;989990/// @brief number of crossings loaded from a sumo net991int myCrossingsLoadedFromSumoNet;992993/// @brief geometry error after computation of internal lane shapes994double myDisplacementError;995996/* @brief whether this junction is a bent priority junction (main direction turns)997* @note see NBEdgePriorityComputer998*/999bool myIsBentPriority;10001001/// @brief whether the node type was guessed rather than loaded1002bool myTypeWasGuessed;10031004/// @brief all vehicle classes for which rail signals exist1005static SVCPermissions myHaveRailSignalClasses;10061007/// @brief all rail classes for which operation without rail signals is permitted1008static SVCPermissions myPermitUnsignalizedClasses;10091010private:1011/// @brief invalidated copy constructor1012NBNode(const NBNode& s);10131014/// @brief invalidated assignment operator1015NBNode& operator=(const NBNode& s);1016};101710181019