/****************************************************************************/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 MSLane.h14/// @author Christian Roessel15/// @author Daniel Krajzewicz16/// @author Jakob Erdmann17/// @author Christoph Sommer18/// @author Tino Morenz19/// @author Michael Behrisch20/// @author Mario Krumnow21/// @author Leonhard Luecken22/// @date Mon, 12 Mar 200123///24// Representation of a lane in the micro simulation25/****************************************************************************/26#pragma once27#include <config.h>2829#include <memory>30#include <vector>31#include <map>32#include <deque>33#include <cassert>34#include <utils/common/Named.h>35#include <utils/common/Parameterised.h>36#include <utils/common/SUMOVehicleClass.h>37#include <utils/vehicle/SUMOVehicle.h>38#include <utils/common/NamedRTree.h>39#include <utils/emissions/PollutantsInterface.h>40#include <utils/geom/PositionVector.h>41#include "MSGlobals.h"42#include "MSLeaderInfo.h"43#include "MSMoveReminder.h"44#include "MSVehicle.h"4546#include <utils/foxtools/MFXSynchQue.h>47#ifdef HAVE_FOX48#include <utils/foxtools/MFXWorkerThread.h>49#endif50#include <utils/common/StopWatch.h>515253// ===========================================================================54// class declarations55// ===========================================================================56class MSEdge;57class MSBaseVehicle;58class MSLaneChanger;59class MSLink;60class MSVehicleTransfer;61class MSVehicleControl;62class OutputDevice;63class MSLeaderInfo;64class MSJunction;656667// ===========================================================================68// type definitions69// ===========================================================================70/// Coverage info71typedef std::map<const MSLane*, std::pair<double, double> > LaneCoverageInfo;7273// ===========================================================================74// class definitions75// ===========================================================================76/**77* @class MSLane78* @brief Representation of a lane in the micro simulation79*80* Class which represents a single lane. Somekind of the main class of the81* simulation. Allows moving vehicles.82*/83class MSLane : public Named, public Parameterised {84public:85class StoringVisitor {86public:87/// @brief Constructor88StoringVisitor(std::set<const Named*>& objects, const PositionVector& shape,89const double range, const int domain)90: myObjects(objects), myShape(shape), myRange(range), myDomain(domain) {}9192/// @brief Adds the given object to the container93void add(const MSLane* const l) const;9495private:96/// @brief The container97std::set<const Named*>& myObjects;98const PositionVector& myShape;99const double myRange;100const int myDomain;101102private:103/// @brief invalidated copy constructor104StoringVisitor(const StoringVisitor& src);105106/// @brief invalidated assignment operator107StoringVisitor& operator=(const StoringVisitor& src);108};109110/// needs access to myTmpVehicles (this maybe should be done via double-buffering!!!)111friend class MSLaneChanger;112friend class MSLaneChangerSublane;113114friend class MSQueueExport;115friend class AnyVehicleIterator;116117/// Container for vehicles.118typedef std::vector<MSVehicle*> VehCont;119120// TODO: Better documentation121/// @brief AnyVehicleIterator is a structure, which manages the iteration through all vehicles on the lane,122/// that may be of importance for the car-following dynamics along that lane. The relevant types of vehicles are:123/// 1) vehicles with their front on the lane (myVehicles),124/// 2) vehicles intersecting the lane but with front on another lane (myPartialVehicles)125///126/// In the context of retrieving linkLeaders during lane changing a third group of vehicles is checked:127/// 3) vehicles processed during lane changing (myTmpVehicles)128class AnyVehicleIterator {129public:130AnyVehicleIterator(131const MSLane* lane,132int i1,133int i2,134int i3,135const int i1End,136const int i2End,137const int i3End,138bool downstream = true) :139myLane(lane),140myI1(i1),141myI2(i2),142myI3(i3),143myI1End(i1End),144myI2End(i2End),145myI3End(i3End),146myDownstream(downstream),147myDirection(downstream ? 1 : -1) {148}149150bool operator== (AnyVehicleIterator const& other) const {151return (myI1 == other.myI1152&& myI2 == other.myI2153&& myI3 == other.myI3154&& myI1End == other.myI1End155&& myI2End == other.myI2End156&& myI3End == other.myI3End);157}158159bool operator!= (AnyVehicleIterator const& other) const {160return !(*this == other);161}162163const MSVehicle* operator->() {164return **this;165}166167const MSVehicle* operator*();168169AnyVehicleIterator& operator++();170171private:172bool nextIsMyVehicles() const;173174/// @brief the lane that is being iterated175const MSLane* myLane;176/// @brief index for myVehicles177int myI1;178/// @brief index for myPartialVehicles179int myI2;180/// @brief index for myTmpVehicles181int myI3;182/// @brief end index for myVehicles183int myI1End;184/// @brief end index for myPartialVehicles185int myI2End;186/// @brief end index for myTmpVehicles187int myI3End;188/// @brief iteration direction189bool myDownstream;190/// @brief index delta191int myDirection;192193};194195196public:197/** @enum ChangeRequest198* @brief Requests set via TraCI199*/200enum CollisionAction {201COLLISION_ACTION_NONE,202COLLISION_ACTION_WARN,203COLLISION_ACTION_TELEPORT,204COLLISION_ACTION_REMOVE205};206207/** @brief Constructor208*209* @param[in] id The lane's id210* @param[in] maxSpeed The speed allowed on this lane211* @param[in] friction The friction of this lane212* @param[in] length The lane's length213* @param[in] edge The edge this lane belongs to214* @param[in] numericalID The numerical id of the lane215* @param[in] shape The shape of the lane216* @param[in] width The width of the lane217* @param[in] permissions Encoding of the Vehicle classes that may drive on this lane218* @param[in] index The index of this lane within its parent edge219* @param[in] isRampAccel Whether this lane is an acceleration lane220* @see SUMOVehicleClass221*/222MSLane(const std::string& id, double maxSpeed, double friction, double length, MSEdge* const edge,223int numericalID, const PositionVector& shape, double width,224SVCPermissions permissions,225SVCPermissions changeLeft, SVCPermissions changeRight,226int index, bool isRampAccel,227const std::string& type,228const PositionVector& outlineShape);229230231/// @brief Destructor232virtual ~MSLane();233234/// @brief returns the associated thread index235inline int getThreadIndex() const {236return myRNGIndex % MSGlobals::gNumSimThreads;237}238239/// @brief returns the associated RNG index240inline int getRNGIndex() const {241return myRNGIndex;242}243244/// @brief return the associated RNG245SumoRNG* getRNG() const {246return &myRNGs[myRNGIndex];247}248249/// @brief return the number of RNGs250static int getNumRNGs() {251return (int)myRNGs.size();252}253254/// @brief save random number generator states to the given output device255static void saveRNGStates(OutputDevice& out);256257/// @brief load random number generator state for the given rng index258static void loadRNGState(int index, const std::string& state);259260/// @name Additional initialisation261/// @{262263/** @brief Delayed initialization264*265* Not all lane-members are known at the time the lane is born, above all the pointers266* to other lanes, so we have to add them later.267*268* @param[in] link An outgoing link269*/270void addLink(MSLink* link);271272/** @brief Adds a neighbor to this lane273*274* @param[in] id The lane's id275*/276void setOpposite(MSLane* oppositeLane);277278/** @brief Adds the (overlapping) reverse direction lane to this lane279*280* @param[in] id The lane's id281*/282void setBidiLane(MSLane* bidyLane);283///@}284285/// @name Used by the GUI for secondary shape visualization286/// @{287virtual void addSecondaryShape(const PositionVector& /*shape*/) {}288289virtual double getLengthGeometryFactor(bool /*secondaryShape*/) const {290return myLengthGeometryFactor;291}292293virtual const PositionVector& getShape(bool /*secondaryShape*/) const {294return myShape;295}296///@}297298299/// @name interaction with MSMoveReminder300/// @{301302/** @brief Add a move-reminder to move-reminder container303*304* The move reminder will not be deleted by the lane.305*306* @param[in] rem The move reminder to add307*/308virtual void addMoveReminder(MSMoveReminder* rem, bool addToVehicles = true);309310311/** @brief Remove a move-reminder from move-reminder container312*313* The move reminder will not be deleted by the lane.314* @param[in] rem The move reminder to remvoe315*/316virtual void removeMoveReminder(MSMoveReminder* rem);317318319/** @brief Return the list of this lane's move reminders320* @return Previously added move reminder321*/322inline const std::vector< MSMoveReminder* >& getMoveReminders() const {323return myMoveReminders;324}325///@}326327328329/// @name Vehicle insertion330///@{331332/** @brief Tries to insert the given vehicle333*334* The insertion position and speed are determined in dependence335* to the vehicle's departure definition, first.336*337* Then, the vehicle is tried to be inserted into the lane338* using these values by a call to "isInsertionSuccess". The result of339* "isInsertionSuccess" is returned.340*341* @param[in] v The vehicle to insert342* @return Whether the vehicle could be inserted343* @see isInsertionSuccess344* @see MSVehicle::getDepartureDefinition345* @see MSVehicle::DepartArrivalDefinition346*/347bool insertVehicle(MSVehicle& v);348349350/** @brief Tries to insert the given vehicle with the given state (speed and pos)351*352* Checks whether the vehicle can be inserted at the given position with the353* given speed so that no collisions with leader/follower occur and the speed354* does not cause unexpected behaviour on consecutive lanes. Returns false355* if the vehicle can not be inserted.356*357* If the insertion can take place, incorporateVehicle() is called and true is returned.358*359* @param[in] vehicle The vehicle to insert360* @param[in] speed The speed with which it shall be inserted361* @param[in] pos The position at which it shall be inserted362* @param[in] posLat The lateral position at which it shall be inserted363* @param[in] recheckNextLanes Forces patching the speed for not being too fast on next lanes364* @param[in] notification The cause of insertion (i.e. departure, teleport, parking) defaults to departure365* @return Whether the vehicle could be inserted366* @see MSVehicle::enterLaneAtInsertion367*/368bool isInsertionSuccess(MSVehicle* vehicle, double speed, double pos, double posLat,369bool recheckNextLanes,370MSMoveReminder::Notification notification);371372// XXX: Documentation?373bool checkFailure(const MSVehicle* aVehicle, double& speed, double& dist, const double nspeed, const bool patchSpeed, const std::string errorMsg, InsertionCheck check) const;374375/** @brief inserts vehicle as close as possible to the last vehicle on this376* lane (or at the end of the lane if there is no leader)377*/378bool lastInsertion(MSVehicle& veh, double mspeed, double posLat, bool patchSpeed);379380/** @brief Tries to insert the given vehicle on any place381*382* @param[in] veh The vehicle to insert383* @param[in] speed The maximum insertion speed384* @param[in] notification The cause of insertion (i.e. departure, teleport, parking) defaults to departure385* @return Whether the vehicle could be inserted386*/387bool freeInsertion(MSVehicle& veh, double speed, double posLat,388MSMoveReminder::Notification notification = MSMoveReminder::NOTIFICATION_DEPARTED);389390391/** @brief Inserts the given vehicle at the given position392*393* No checks are done, vehicle insertion using this method may394* generate collisions (possibly delayed).395* @param[in] veh The vehicle to insert396* @param[in] pos The position at which the vehicle shall be inserted397* @param[in] notification The cause of insertion (i.e. departure, teleport, parking) defaults to departure398* @param[in] posLat The lateral position at which the vehicle shall be inserted399*/400void forceVehicleInsertion(MSVehicle* veh, double pos, MSMoveReminder::Notification notification, double posLat = 0);401/// @}402403404405/// @name Handling vehicles lapping into several lanes (-> partial occupation)406/// or which committed a maneuver that will lead them into another (sublane case -> maneuver reservations)407/// @{408/** @brief Sets the information about a vehicle lapping into this lane409*410* This vehicle is added to myVehicles and may be distinguished from regular411* vehicles by the disparity between this lane and v->getLane()412* @param[in] v The vehicle which laps into this lane413* @return This lane's length414*/415virtual double setPartialOccupation(MSVehicle* v);416417/** @brief Removes the information about a vehicle lapping into this lane418* @param[in] v The vehicle which laps into this lane419*/420virtual void resetPartialOccupation(MSVehicle* v);421422/** @brief Registers the lane change intentions (towards this lane) for the given vehicle423*/424virtual void setManeuverReservation(MSVehicle* v);425426/** @brief Unregisters a vehicle, which previously registered for maneuvering into this lane427* @param[in] v The vehicle428*/429virtual void resetManeuverReservation(MSVehicle* v);430431/** @brief Returns the last vehicles on the lane432*433* The information about the last vehicles in this lanes in all sublanes434* occupied by ego are435* returned. Partial occupators are included436* @param[in] ego The vehicle for which to restrict the returned leaderInfo437* @param[in] minPos The minimum position from which to start search for leaders438* @param[in] allowCached Whether the cached value may be used439* @return Information about the last vehicles440*/441const MSLeaderInfo getLastVehicleInformation(const MSVehicle* ego, double latOffset, double minPos = 0, bool allowCached = true) const;442443/// @brief analogue to getLastVehicleInformation but in the upstream direction444const MSLeaderInfo getFirstVehicleInformation(const MSVehicle* ego, double latOffset, bool onlyFrontOnLane, double maxPos = std::numeric_limits<double>::max(), bool allowCached = true) const;445446/// @}447448/// @name Access to vehicles449/// @{450451/** @brief Returns the number of vehicles on this lane (for which this lane452* is responsible)453* @return The number of vehicles with their front on this lane454*/455int getVehicleNumber() const {456return (int)myVehicles.size();457}458459/** @brief Returns the number of vehicles on this lane (including partial460* occupators)461* @return The number of vehicles with intersecting this lane462*/463int getVehicleNumberWithPartials() const {464return (int)myVehicles.size() + (int)myPartialVehicles.size();465}466467/** @brief Returns the number of vehicles partially on this lane (for which this lane468* is not responsible)469* @return The number of vehicles touching this lane but with their front on another lane470*/471int getPartialVehicleNumber() const {472return (int)myPartialVehicles.size();473}474475476/** @brief Returns the vehicles container; locks it for microsimulation477*478* Please note that it is necessary to release the vehicles container479* afterwards using "releaseVehicles".480* @return The vehicles on this lane481*/482virtual const VehCont& getVehiclesSecure() const {483return myVehicles;484}485486487/// @brief begin iterator for iterating over all vehicles touching this lane in downstream direction488AnyVehicleIterator anyVehiclesBegin() const {489return AnyVehicleIterator(this, 0, 0, 0,490(int)myVehicles.size(), (int)myPartialVehicles.size(), (int)myTmpVehicles.size(), true);491}492493/// @brief end iterator for iterating over all vehicles touching this lane in downstream direction494AnyVehicleIterator anyVehiclesEnd() const {495return AnyVehicleIterator(this, (int)myVehicles.size(), (int)myPartialVehicles.size(), (int)myTmpVehicles.size(),496(int)myVehicles.size(), (int)myPartialVehicles.size(), (int)myTmpVehicles.size(), true);497}498499/// @brief begin iterator for iterating over all vehicles touching this lane in upstream direction500AnyVehicleIterator anyVehiclesUpstreamBegin() const {501return AnyVehicleIterator(this, (int)myVehicles.size() - 1, (int)myPartialVehicles.size() - 1, (int)myTmpVehicles.size() - 1,502-1, -1, -1, false);503}504505/// @brief end iterator for iterating over all vehicles touching this lane in upstream direction506AnyVehicleIterator anyVehiclesUpstreamEnd() const {507return AnyVehicleIterator(this, -1, -1, -1, -1, -1, -1, false);508}509510/** @brief Allows to use the container for microsimulation again511*/512virtual void releaseVehicles() const { }513/// @}514515516517/// @name Atomar value getter518/// @{519520521/** @brief Returns this lane's numerical id522* @return This lane's numerical id523*/524inline int getNumericalID() const {525return myNumericalID;526}527528529/** @brief Returns this lane's shape530* @return This lane's shape531*/532inline const PositionVector& getShape() const {533return myShape;534}535536/// @brief return shape.length() / myLength537inline double getLengthGeometryFactor() const {538return myLengthGeometryFactor;539}540541/// @brief return whether this lane is an acceleration lane542inline bool isAccelLane() const {543return myIsRampAccel;544}545546/// @brief return the type of this lane547const std::string& getLaneType() const {548return myLaneType;549}550551/* @brief fit the given lane position to a visibly suitable geometry position552* (lane length might differ from geometry length) */553inline double interpolateLanePosToGeometryPos(double lanePos) const {554return lanePos * myLengthGeometryFactor;555}556557/* @brief fit the given lane position to a visibly suitable geometry position558* and return the coordinates */559inline const Position geometryPositionAtOffset(double offset, double lateralOffset = 0) const {560return myShape.positionAtOffset(interpolateLanePosToGeometryPos(offset), lateralOffset);561}562563/* @brief fit the given geometry position to a valid lane position564* (lane length might differ from geometry length) */565inline double interpolateGeometryPosToLanePos(double geometryPos) const {566return geometryPos / myLengthGeometryFactor;567}568569/** @brief Returns the lane's maximum speed, given a vehicle's speed limit adaptation570* @param[in] The vehicle to return the adapted speed limit for571* @return This lane's resulting max. speed572*/573inline double getVehicleMaxSpeed(const SUMOTrafficObject* const veh) const {574return getVehicleMaxSpeed(veh, veh->getMaxSpeed());575}576577578inline double getVehicleMaxSpeed(const SUMOTrafficObject* const veh, double vehMaxSpeed) const {579if (myRestrictions != nullptr) {580std::map<SUMOVehicleClass, double>::const_iterator r = myRestrictions->find(veh->getVClass());581if (r != myRestrictions->end()) {582if (mySpeedByVSS || mySpeedByTraCI) {583return MIN2(myMaxSpeed, MIN2(vehMaxSpeed, r->second * veh->getChosenSpeedFactor()));584} else {585return MIN2(vehMaxSpeed, r->second * veh->getChosenSpeedFactor());586}587}588}589return MIN2(vehMaxSpeed, myMaxSpeed * veh->getChosenSpeedFactor());590}591592593/** @brief Returns the lane's maximum allowed speed594* @return This lane's maximum allowed speed595*/596inline double getSpeedLimit() const {597return myMaxSpeed;598}599600/** @brief Returns the lane's friction coefficient601* @return This lane's friction coefficient602*/603inline double getFrictionCoefficient() const {604return myFrictionCoefficient;605}606607/** @brief Returns the lane's length608* @return This lane's length609*/610inline double getLength() const {611return myLength;612}613614615/** @brief Returns the vehicle class permissions for this lane616* @return This lane's allowed vehicle classes617*/618inline SVCPermissions getPermissions() const {619return myPermissions;620}621622/** @brief Returns the vehicle class permissions for changing to the left neighbour lane623* @return The vehicle classes allowed to change to the left neighbour lane624*/625inline SVCPermissions getChangeLeft() const {626return myChangeLeft;627}628629/** @brief Returns the vehicle class permissions for changing to the right neighbour lane630* @return The vehicle classes allowed to change to the right neighbour lane631*/632inline SVCPermissions getChangeRight() const {633return myChangeRight;634}635636/** @brief Returns the lane's width637* @return This lane's width638*/639double getWidth() const {640return myWidth;641}642643/** @brief Returns the lane's index644* @return This lane's index645*/646int getIndex() const {647return myIndex;648}649/// @}650651/// @brief return the index of the link to the next crossing if this is walkingArea, else -1652int getCrossingIndex() const;653654655/// @name Vehicle movement (longitudinal)656/// @{657658/** @brief Compute safe velocities for all vehicles based on positions and659* speeds from the last time step. Also registers660* ApproachingVehicleInformation for all links661*662* This method goes through all vehicles calling their "planMove" method.663* @see MSVehicle::planMove664*/665virtual void planMovements(const SUMOTime t);666667/** @brief Register junction approaches for all vehicles after velocities668* have been planned.669*670* This method goes through all vehicles calling their * "setApproachingForAllLinks" method.671*/672virtual void setJunctionApproaches() const;673674/** @brief This updates the MSLeaderInfo argument with respect to the given MSVehicle.675* All leader-vehicles on the same edge, which are relevant for the vehicle676* (i.e. with position > vehicle's position) and not already integrated into677* the LeaderInfo, are integrated.678* The given iterators vehPart and vehRes give access to these vehicles which are679* either partial occupators or have issued a maneuver reservation for the lane680* (the latter occurs only for the sublane model).681*/682void updateLeaderInfo(const MSVehicle* veh, VehCont::reverse_iterator& vehPart, VehCont::reverse_iterator& vehRes, MSLeaderInfo& ahead) const;683684/** @brief Executes planned vehicle movements with regards to right-of-way685*686* This method goes through all vehicles calling their executeMove method687* which causes vehicles to update their positions and speeds.688* Vehicles wich move to the next lane are stored in the targets lane buffer689*690* @return Returns true, if all vehicles left the lane.691*692* @see MSVehicle::executeMove693*/694virtual void executeMovements(const SUMOTime t);695696/// Insert buffered vehicle into the real lane.697virtual void integrateNewVehicles();698699/** @brief Set a flag to recalculate the brutto (including minGaps) occupancy of this lane (used if mingap is changed)700*/701void markRecalculateBruttoSum();702703/// @brief updated current vehicle length sum (delayed to avoid lane-order-dependency)704void updateLengthSum();705///@}706707708/// @brief short-circut collision check if nothing changed since the last check709inline bool needsCollisionCheck() const {710return myNeedsCollisionCheck;711}712713/// @brief require another collision check due to relevant changes in the simulation714inline void requireCollisionCheck() {715myNeedsCollisionCheck = true;716}717718/// Check if vehicles are too close.719virtual void detectCollisions(SUMOTime timestep, const std::string& stage);720721722/** Returns the information whether this lane may be used to continue723the current route */724virtual bool appropriate(const MSVehicle* veh) const;725726727/// returns the container with all links !!!728const std::vector<MSLink*>& getLinkCont() const {729return myLinks;730}731732/// returns the link to the given lane or nullptr, if it is not connected733const MSLink* getLinkTo(const MSLane* const) const;734735/// returns the internal lane leading to the given lane or nullptr, if there is none736const MSLane* getInternalFollowingLane(const MSLane* const) const;737738/// Returns the entry link if this is an internal lane, else nullptr739const MSLink* getEntryLink() const;740741742/// Returns true if there is not a single vehicle on the lane.743bool empty() const {744assert(myVehBuffer.size() == 0);745return myVehicles.empty();746}747748/** @brief Sets a new maximum speed for the lane (used by TraCI and MSCalibrator)749* @param[in] val the new speed in m/s750* @param[in] whether a variable speed sign (VSS) imposes the speed limit751* @param[in] whether TraCI imposes the speed limit752*/753void setMaxSpeed(double val, bool byVSS = false, bool byTraCI = false, double jamThreshold = -1);754755/** @brief Sets a new friction coefficient for the lane [*to be later (used by TraCI and MSCalibrator)*]756* @param[in] val the new friction coefficient [0..1]757*/758void setFrictionCoefficient(double val);759760/** @brief Sets a new length for the lane (used by TraCI only)761* @param[in] val the new length in m762*/763void setLength(double val);764765/** @brief Returns the lane's edge766* @return This lane's edge767*/768MSEdge& getEdge() const {769return *myEdge;770}771772const MSJunction* getFromJunction() const;773const MSJunction* getToJunction() const;774775/** @brief Returns the lane's follower if it is an internal lane, the edge of the lane otherwise776* @return This lane's follower777*/778const MSEdge* getNextNormal() const;779780781/** @brief Returns 0 if the lane is not internal. Otherwise the first part of the782* connection (sequence of internal lanes along junction) corresponding to the lane783* is returned and the offset is set to the distance of the begin of this lane784* to the begin of the returned.785*/786const MSLane* getFirstInternalInConnection(double& offset) const;787788789/// @brief Static (sic!) container methods790/// {791792/** @brief Inserts a MSLane into the static dictionary793*794* Returns true if the key id isn't already in the dictionary.795* Otherwise returns false.796* @param[in] id The id of the lane797* @param[in] lane The lane itself798* @return Whether the lane was added799* @todo make non-static800* @todo why is the id given? The lane is named801*/802static bool dictionary(const std::string& id, MSLane* lane);803804805/** @brief Returns the MSLane associated to the key id806*807* The lane is returned if exists, otherwise 0 is returned.808* @param[in] id The id of the lane809* @return The lane810*/811static MSLane* dictionary(const std::string& id);812813814/** @brief Clears the dictionary */815static void clear();816817818/** @brief Returns the number of stored lanes819* @return The number of stored lanes820*/821static int dictSize() {822return (int)myDict.size();823}824825826/** @brief Adds the ids of all stored lanes into the given vector827* @param[in, filled] into The vector to add the IDs into828*/829static void insertIDs(std::vector<std::string>& into);830831832/** @brief Fills the given RTree with lane instances833* @param[in, filled] into The RTree to fill834* @see TraCILaneRTree835*/836template<class RTREE>837static void fill(RTREE& into);838839840/// @brief initialize rngs841static void initRNGs(const OptionsCont& oc);842/// @}843844845846// XXX: succLink does not exist... Documentation?847/** Same as succLink, but does not throw any assertions when848the succeeding link could not be found;849Returns the myLinks.end() instead; Further, the number of edges to850look forward may be given */851static std::vector<MSLink*>::const_iterator succLinkSec(const SUMOVehicle& veh,852int nRouteSuccs,853const MSLane& succLinkSource,854const std::vector<MSLane*>& conts);855856857/** Returns the information whether the given link shows at the end858of the list of links (is not valid) */859inline bool isLinkEnd(std::vector<MSLink*>::const_iterator& i) const {860return i == myLinks.end();861}862863/** Returns the information whether the given link shows at the end864of the list of links (is not valid) */865inline bool isLinkEnd(std::vector<MSLink*>::iterator& i) {866return i == myLinks.end();867}868869/** Returns the information whether the lane is has no vehicle and no870partial occupation*/871inline bool isEmpty() const {872return myVehicles.empty() && myPartialVehicles.empty();873}874875/** Returns whether the lane pertains to an internal edge*/876bool isInternal() const;877878/** Returns whether the lane pertains to a normal edge*/879bool isNormal() const;880881/** Returns whether the lane pertains to a crossing edge*/882bool isCrossing() const;883884/** Returns whether the lane pertains to a walkingarea*/885bool isWalkingArea() const;886887/// @brief returns the last vehicle for which this lane is responsible or 0888MSVehicle* getLastFullVehicle() const;889890/// @brief returns the first vehicle for which this lane is responsible or 0891MSVehicle* getFirstFullVehicle() const;892893/// @brief returns the last vehicle that is fully or partially on this lane894MSVehicle* getLastAnyVehicle() const;895896/// @brief returns the first vehicle that is fully or partially on this lane897MSVehicle* getFirstAnyVehicle() const;898899/* @brief remove the vehicle from this lane900* @param[notify] whether moveReminders of the vehicle shall be triggered901*/902virtual MSVehicle* removeVehicle(MSVehicle* remVehicle, MSMoveReminder::Notification notification, bool notify = true);903904void leftByLaneChange(MSVehicle* v);905void enteredByLaneChange(MSVehicle* v);906907/** @brief Returns the lane with the given offset parallel to this one or 0 if it does not exist908* @param[in] offset The offset of the result lane909*/910MSLane* getParallelLane(int offset, bool includeOpposite = true) const;911912913/** @brief Sets the permissions to the given value. If a transientID is given, the permissions are recored as temporary914* @param[in] permissions The new permissions915* @param[in] transientID The id of the permission-modification or the special value PERMANENT916*/917void setPermissions(SVCPermissions permissions, long long transientID);918void resetPermissions(long long transientID);919bool hadPermissionChanges() const;920921/** @brief Sets the permissions for changing to the left neighbour lane922* @param[in] permissions The new permissions923*/924void setChangeLeft(SVCPermissions permissions);925926/** @brief Sets the permissions for changing to the right neighbour lane927* @param[in] permissions The new permissions928*/929void setChangeRight(SVCPermissions permissions);930931inline bool allowsVehicleClass(SUMOVehicleClass vclass) const {932return (myPermissions & vclass) == vclass;933}934935bool allowsVehicleClass(SUMOVehicleClass vclass, int routingMode) const;936937/** @brief Returns whether the given vehicle class may change left from this lane */938inline bool allowsChangingLeft(SUMOVehicleClass vclass) const {939return (myChangeLeft & vclass) == vclass;940}941942/** @brief Returns whether the given vehicle class may change left from this lane */943inline bool allowsChangingRight(SUMOVehicleClass vclass) const {944return (myChangeRight & vclass) == vclass;945}946947void addIncomingLane(MSLane* lane, MSLink* viaLink);948949950struct IncomingLaneInfo {951MSLane* lane;952double length;953MSLink* viaLink;954};955956const std::vector<IncomingLaneInfo>& getIncomingLanes() const {957return myIncomingLanes;958}959960961void addApproachingLane(MSLane* lane, bool warnMultiCon);962inline bool isApproachedFrom(MSEdge* const edge) {963return myApproachingLanes.find(edge) != myApproachingLanes.end();964}965bool isApproachedFrom(MSEdge* const edge, MSLane* const lane);966967/// @brief Returns vehicle class specific stopOffset for the vehicle968double getVehicleStopOffset(const MSVehicle* veh) const;969970/// @brief Returns vehicle class specific stopOffsets971const StopOffset& getLaneStopOffsets() const;972973/// @brief Set vehicle class specific stopOffsets974void setLaneStopOffset(const StopOffset& stopOffset);975976/** @enum MinorLinkMode977* @brief determine whether/how getFollowers looks upstream beyond minor links978*/979enum MinorLinkMode {980FOLLOW_NEVER = 0,981FOLLOW_ALWAYS = 1,982FOLLOW_ONCOMING = 2,983};984985/// @brief return the sublane followers with the largest missing rear gap among all predecessor lanes (within dist)986MSLeaderDistanceInfo getFollowersOnConsecutive(const MSVehicle* ego, double backOffset,987bool allSublanes, double searchDist = -1, MinorLinkMode mLinkMode = FOLLOW_ALWAYS) const;988989/// @brief return by how much further the leader must be inserted to avoid rear end collisions990double getMissingRearGap(const MSVehicle* leader, double backOffset, double leaderSpeed) const;991992/** @brief Returns the immediate leader of veh and the distance to veh993* starting on this lane994*995* Iterates over the current lane to find a leader and then uses996* getLeaderOnConsecutive()997* @param[in] veh The vehicle for which the information shall be computed998* @param[in] vehPos The vehicle position relative to this lane (may be negative)999* @param[in] bestLaneConts The succeding lanes that shall be checked (if any)1000* @param[in] dist Optional distance to override default (ego stopDist)1001* @param[in] checkTmpVehicles Whether myTmpVehicles should be used instead of myVehicles1002* @return1003*/1004std::pair<MSVehicle* const, double> getLeader(const MSVehicle* veh, const double vehPos, const std::vector<MSLane*>& bestLaneConts, double dist = -1, bool checkTmpVehicles = false) const;10051006/** @brief Returns the immediate leader and the distance to him1007*1008* Goes along the vehicle's estimated used lanes (bestLaneConts). For each link,1009* it is determined whether the vehicle will pass it. If so, the subsequent lane1010* is investigated. If a vehicle (leader) is found, it is returned, together with the length1011* of the investigated lanes until this vehicle's end, including the already seen1012* place (seen).1013*1014* If no leading vehicle was found, <0, -1> is returned.1015*1016* Pretty slow, as it has to go along lanes.1017*1018* @todo: There are some oddities:1019* - what about crossing a link at red, or if a link is closed? Has a following vehicle to be regarded or not?1020*1021* @param[in] dist The distance to investigate1022* @param[in] seen The already seen place (normally the place in front on own lane)1023* @param[in] speed The speed of the vehicle used for determining whether a subsequent link will be opened at arrival time1024* @param[in] veh The vehicle for which the information shall be computed1025* @param[in] bestLaneConts The lanes the vehicle will use in future1026* @param[in] considerCrossingFoes Whether vehicles on crossing foe links should be considered1027* @return1028*/1029std::pair<MSVehicle* const, double> getLeaderOnConsecutive(double dist, double seen,1030double speed, const MSVehicle& veh, const std::vector<MSLane*>& bestLaneConts, bool considerCrossingFoes = true) const;10311032/// @brief Returns the immediate leaders and the distance to them (as getLeaderOnConsecutive but for the sublane case)1033void getLeadersOnConsecutive(double dist, double seen, double speed, const MSVehicle* ego,1034const std::vector<MSLane*>& bestLaneConts, MSLeaderDistanceInfo& result, bool oppositeDirection = false) const;103510361037/// @brief get leaders for ego on the given lane1038void addLeaders(const MSVehicle* vehicle, double vehPos, MSLeaderDistanceInfo& result, bool oppositeDirection = false);103910401041/** @brief Returns the most dangerous leader and the distance to him1042*1043* Goes along the vehicle's estimated used lanes (bestLaneConts). For each link,1044* it is determined whether the ego vehicle will pass it. If so, the subsequent lane1045* is investigated. Check all lanes up to the stopping distance of ego.1046* Return the leader vehicle (and the gap) which puts the biggest speed constraint on ego.1047*1048* If no leading vehicle was found, <0, -1> is returned.1049*1050* Pretty slow, as it has to go along lanes.1051*1052* @param[in] dist The distance to investigate1053* @param[in] seen The already seen place (normally the place in front on own lane)1054* @param[in] speed The speed of the vehicle used for determining whether a subsequent link will be opened at arrival time1055* @param[in] veh The (ego) vehicle for which the information shall be computed1056* @return1057*/1058std::pair<MSVehicle* const, double> getCriticalLeader(double dist, double seen, double speed, const MSVehicle& veh) const;10591060/* @brief return the partial vehicle closest behind ego or 01061* if no such vehicle exists */1062MSVehicle* getPartialBehind(const MSVehicle* ego) const;10631064/// @brief get all vehicles that are inlapping from consecutive edges1065MSLeaderInfo getPartialBeyond() const;10661067/// @brief Returns all vehicles closer than downstreamDist along the road network starting on the given1068/// position. Predecessor lanes are searched upstream for the given upstreamDistance.1069/// @note Re-implementation of the corresponding method in MSDevice_SSM, which cannot be easily adapted, as it gathers1070/// additional information for conflict lanes, etc.1071/// @param[in] startPos - start position of the search on the first lane1072/// @param[in] downstreamDist - distance to search downstream1073/// @param[in] upstreamDist - distance to search upstream1074/// @param[in/out] checkedLanes - lanes, which were already scanned (current lane is added, if not present,1075/// otherwise the scan is aborted; TODO: this may disregard unscanned parts of the lane in specific circular set ups.)1076/// @return vehs - List of vehicles found1077std::set<MSVehicle*> getSurroundingVehicles(double startPos, double downstreamDist, double upstreamDist, std::shared_ptr<LaneCoverageInfo> checkedLanes) const;10781079/// @brief Returns all vehicles on the lane overlapping with the interval [a,b]1080/// @note Does not consider vehs with front on subsequent lanes1081std::set<MSVehicle*> getVehiclesInRange(const double a, const double b) const;10821083/// @brief Returns all upcoming junctions within given range along the given (non-internal) continuation lanes measured from given position1084std::vector<const MSJunction*> getUpcomingJunctions(double pos, double range, const std::vector<MSLane*>& contLanes) const;10851086/// @brief Returns all upcoming links within given range along the given (non-internal) continuation lanes measured from given position1087std::vector<const MSLink*> getUpcomingLinks(double pos, double range, const std::vector<MSLane*>& contLanes) const;10881089/** @brief get the most likely precedecessor lane (sorted using by_connections_to_sorter).1090* The result is cached in myLogicalPredecessorLane1091*/1092MSLane* getLogicalPredecessorLane() const;10931094/** @brief get normal lane leading to this internal lane, for normal lanes,1095* the lane itself is returned1096*/1097const MSLane* getNormalPredecessorLane() const;10981099/** @brief get normal lane following this internal lane, for normal lanes,1100* the lane itself is returned1101*/1102const MSLane* getNormalSuccessorLane() const;11031104/** @brief return the (first) predecessor lane from the given edge1105*/1106MSLane* getLogicalPredecessorLane(const MSEdge& fromEdge) const;110711081109/** Return the main predecessor lane for the current.1110* If there are several incoming lanes, the first attempt is to return the priorized.1111* If this does not yield an unambiguous lane, the one with the least angle difference1112* to the current is selected.1113*/1114MSLane* getCanonicalPredecessorLane() const;111511161117/** Return the main successor lane for the current.1118* If there are several outgoing lanes, the first attempt is to return the priorized.1119* If this does not yield an unambiguous lane, the one with the least angle difference1120* to the current is selected.1121*/1122MSLane* getCanonicalSuccessorLane() const;11231124/// @brief get the state of the link from the logical predecessor to this lane1125LinkState getIncomingLinkState() const;11261127/// @brief get the list of outgoing lanes1128const std::vector<std::pair<const MSLane*, const MSEdge*> > getOutgoingViaLanes() const;11291130/// @brief get the list of all direct (disregarding internal predecessors) non-internal predecessor lanes of this lane1131std::vector<const MSLane*> getNormalIncomingLanes() const;11321133/// @name Current state retrieval1134//@{11351136/** @brief Returns the mean speed on this lane1137* @return The average speed of vehicles during the last step; default speed if no vehicle was on this lane1138*/1139double getMeanSpeed() const;11401141/// @brief get the mean speed of all bicycles on this lane1142double getMeanSpeedBike() const;11431144/** @brief Returns the overall waiting time on this lane1145* @return The sum of the waiting time of all vehicles during the last step;1146*/1147double getWaitingSeconds() const;114811491150/** @brief Returns the brutto (including minGaps) occupancy of this lane during the last step1151* @return The occupancy during the last step1152*/1153double getBruttoOccupancy() const;115411551156/** @brief Returns the netto (excluding minGaps) occupancy of this lane during the last step (including minGaps)1157* @return The occupancy during the last step1158*/1159double getNettoOccupancy() const;116011611162/** @brief Returns the sum of lengths of vehicles, including their minGaps, which were on the lane during the last step1163* @return The sum of vehicle lengths of vehicles in the last step1164*/1165inline double getBruttoVehLenSum() const {1166return myBruttoVehicleLengthSum;1167}116811691170/** @brief Returns the sum of last step emissions1171* The value is always per 1s, so multiply by step length if necessary.1172* @return emissions of vehicles on this lane during the last step1173*/1174template<PollutantsInterface::EmissionType ET>1175double getEmissions() const {1176double ret = 0;1177for (MSVehicle* const v : getVehiclesSecure()) {1178ret += v->getEmissions<ET>();1179}1180releaseVehicles();1181return ret;1182}118311841185/** @brief Returns the sum of last step noise emissions1186* @return noise emissions of vehicles on this lane during the last step1187*/1188double getHarmonoise_NoiseEmissions() const;1189/// @}11901191void setRightSideOnEdge(double value, int rightmostSublane) {1192myRightSideOnEdge = value;1193myRightmostSublane = rightmostSublane;1194}11951196/// @brief initialized vClass-specific speed limits1197void initRestrictions();11981199void checkBufferType();12001201double getRightSideOnEdge() const {1202return myRightSideOnEdge;1203}12041205int getRightmostSublane() const {1206return myRightmostSublane;1207}12081209double getCenterOnEdge() const {1210return myRightSideOnEdge + 0.5 * myWidth;1211}12121213/// @brief sorts myPartialVehicles1214void sortPartialVehicles();12151216/// @brief sorts myManeuverReservations1217void sortManeuverReservations();12181219/// @brief return the neighboring opposite direction lane for lane changing or nullptr1220MSLane* getOpposite() const;12211222/// @brief return the opposite direction lane of this lanes edge or nullptr1223MSLane* getParallelOpposite() const;12241225/// @brief return the corresponding position on the opposite lane1226double getOppositePos(double pos) const;12271228/* @brief find leader for a vehicle depending on the relative driving direction1229* @param[in] ego The ego vehicle1230* @param[in] dist The look-ahead distance when looking at consecutive lanes1231* @param[in] oppositeDir Whether the lane has the opposite driving direction of ego1232* @return the leader vehicle and its gap to ego1233*/1234std::pair<MSVehicle* const, double> getOppositeLeader(const MSVehicle* ego, double dist, bool oppositeDir, MinorLinkMode mLinkMode = MinorLinkMode::FOLLOW_NEVER) const;12351236/* @brief find follower for a vehicle that is located on the opposite of this lane1237* @param[in] ego The ego vehicle1238* @return the follower vehicle and its gap to ego1239*/1240std::pair<MSVehicle* const, double> getOppositeFollower(const MSVehicle* ego) const;124112421243/** @brief Find follower vehicle for the given ego vehicle (which may be on the opposite direction lane)1244* @param[in] ego The ego vehicle1245* @param[in] egoPos The ego position mapped to the current lane1246* @param[in] dist The look-back distance when looking at consecutive lanes1247* @param[in] ignoreMinorLinks Whether backward search should stop at minor links1248* @return the follower vehicle and its gap to ego1249*/1250std::pair<MSVehicle* const, double> getFollower(const MSVehicle* ego, double egoPos, double dist, MinorLinkMode mLinkMode) const;125112521253///@brief add parking vehicle. This should only used during state loading1254void addParking(MSBaseVehicle* veh);12551256///@brief remove parking vehicle. This must be syncrhonized when running with GUI1257virtual void removeParking(MSBaseVehicle* veh);12581259/// @brief retrieve the parking vehicles (see GUIParkingArea)1260const std::set<const MSBaseVehicle*>& getParkingVehicles() const {1261return myParkingVehicles;1262}12631264/// @brief whether this lane is selected in the GUI1265virtual bool isSelected() const {1266return false;1267}12681269/// @brief retrieve bidirectional lane or nullptr1270MSLane* getBidiLane() const;12711272/// @brief whether this lane must check for junction collisions1273bool mustCheckJunctionCollisions() const;12741275#ifdef HAVE_FOX1276MFXWorkerThread::Task* getPlanMoveTask(const SUMOTime time) {1277mySimulationTask.init(&MSLane::planMovements, time);1278return &mySimulationTask;1279}12801281MFXWorkerThread::Task* getExecuteMoveTask(const SUMOTime time) {1282mySimulationTask.init(&MSLane::executeMovements, time);1283return &mySimulationTask;1284}12851286MFXWorkerThread::Task* getLaneChangeTask(const SUMOTime time) {1287mySimulationTask.init(&MSLane::changeLanes, time);1288return &mySimulationTask;1289}1290#endif12911292std::vector<StopWatch<std::chrono::nanoseconds> >& getStopWatch() {1293return myStopWatch;1294}12951296void changeLanes(const SUMOTime time);12971298/// @name State saving/loading1299/// @{13001301/** @brief Saves the state of this lane into the given stream1302*1303* Basically, a list of vehicle ids1304*1305* @param[in, filled] out The (possibly binary) device to write the state into1306* @todo What about throwing an IOError?1307*/1308void saveState(OutputDevice& out);13091310/** @brief Remove all vehicles before quick-loading state */1311void clearState();13121313/** @brief Loads the state of this segment with the given parameters1314*1315* This method is called for every internal que the segment has.1316* Every vehicle is retrieved from the given MSVehicleControl and added to this1317* lane.1318*1319* @param[in] vehs The vehicles for the current lane1320* @todo What about throwing an IOError?1321* @todo What about throwing an error if something else fails (a vehicle can not be referenced)?1322*/1323void loadState(const std::vector<SUMOVehicle*>& vehs);132413251326/* @brief helper function for state saving: checks whether any outgoing1327* links are being approached */1328bool hasApproaching() const;13291330/// @}133113321333/** @brief Callback for visiting the lane when traversing an RTree1334*1335* This is used in the TraCIServerAPI_Lane for context subscriptions.1336*1337* @param[in] cont The context doing all the work1338* @see libsumo::Helper::LaneStoringVisitor::add1339*/1340void visit(const MSLane::StoringVisitor& cont) const {1341cont.add(this);1342}13431344/// @brief whether the lane has pedestrians on it1345bool hasPedestrians() const;13461347/// This is just a wrapper around MSPModel::nextBlocking. You should always check using hasPedestrians before calling this method.1348std::pair<const MSPerson*, double> nextBlocking(double minPos, double minRight, double maxLeft, double stopTime = 0, bool bidi = false) const;13491350/// @brief return the empty space up to the last standing vehicle or the empty space on the whole lane if no vehicle is standing1351double getSpaceTillLastStanding(const MSVehicle* ego, bool& foundStopped) const;13521353/// @brief compute maximum braking distance on this lane1354double getMaximumBrakeDist() const;13551356inline const PositionVector* getOutlineShape() const {1357return myOutlineShape;1358}13591360static void initCollisionOptions(const OptionsCont& oc);1361static void initCollisionAction(const OptionsCont& oc, const std::string& option, CollisionAction& myAction);13621363static CollisionAction getCollisionAction() {1364return myCollisionAction;1365}13661367static CollisionAction getIntermodalCollisionAction() {1368return myIntermodalCollisionAction;1369}13701371static DepartSpeedDefinition& getDefaultDepartSpeedDefinition() {1372return myDefaultDepartSpeedDefinition;1373}13741375static double& getDefaultDepartSpeed() {1376return myDefaultDepartSpeed;1377}137813791380static const long CHANGE_PERMISSIONS_PERMANENT = 0;1381static const long CHANGE_PERMISSIONS_GUI = 1;13821383protected:1384/// moves myTmpVehicles int myVehicles after a lane change procedure1385virtual void swapAfterLaneChange(SUMOTime t);13861387/** @brief Inserts the vehicle into this lane, and informs it about entering the network1388*1389* Calls the vehicles enterLaneAtInsertion function,1390* updates statistics and modifies the active state as needed1391* @param[in] veh The vehicle to be incorporated1392* @param[in] pos The position of the vehicle1393* @param[in] speed The speed of the vehicle1394* @param[in] posLat The lateral position of the vehicle1395* @param[in] at1396* @param[in] notification The cause of insertion (i.e. departure, teleport, parking) defaults to departure1397*/1398virtual void incorporateVehicle(MSVehicle* veh, double pos, double speed, double posLat,1399const MSLane::VehCont::iterator& at,1400MSMoveReminder::Notification notification = MSMoveReminder::NOTIFICATION_DEPARTED);14011402/// @brief detect whether a vehicle collids with pedestrians on the junction1403void detectPedestrianJunctionCollision(const MSVehicle* collider, const PositionVector& colliderBoundary, const MSLane* foeLane,1404SUMOTime timestep, const std::string& stage,1405std::set<const MSVehicle*, ComparatorNumericalIdLess>& toRemove,1406std::set<const MSVehicle*, ComparatorNumericalIdLess>& toTeleport);14071408/// @brief detect whether there is a collision between the two vehicles1409bool detectCollisionBetween(SUMOTime timestep, const std::string& stage, MSVehicle* collider, MSVehicle* victim,1410std::set<const MSVehicle*, ComparatorNumericalIdLess>& toRemove,1411std::set<const MSVehicle*, ComparatorNumericalIdLess>& toTeleport) const;14121413/// @brief take action upon collision1414void handleCollisionBetween(SUMOTime timestep, const std::string& stage, const MSVehicle* collider, const MSVehicle* victim,1415double gap, double latGap,1416std::set<const MSVehicle*, ComparatorNumericalIdLess>& toRemove,1417std::set<const MSVehicle*, ComparatorNumericalIdLess>& toTeleport) const;14181419void handleIntermodalCollisionBetween(SUMOTime timestep, const std::string& stage, const MSVehicle* collider, const MSTransportable* victim,1420double gap, const std::string& collisionType,1421std::set<const MSVehicle*, ComparatorNumericalIdLess>& toRemove,1422std::set<const MSVehicle*, ComparatorNumericalIdLess>& toTeleport) const;14231424/* @brief determine depart speed and whether it may be patched1425* @param[in] veh The departing vehicle1426* @param[out] whether the speed may be patched to account for safety1427* @return the depart speed1428*/1429double getDepartSpeed(const MSVehicle& veh, bool& patchSpeed);14301431/* @brief determine the lateral depart position1432* @param[in] veh The departing vehicle1433* @return the lateral depart position1434*/1435double getDepartPosLat(const MSVehicle& veh);14361437/** @brief return the maximum safe speed for insertion behind leaders1438* (a negative value indicates that safe insertion is impossible) */1439double safeInsertionSpeed(const MSVehicle* veh, double seen, const MSLeaderInfo& leaders, double speed);14401441/// @brief check whether pedestrians on this lane interfere with vehicle insertion1442bool checkForPedestrians(const MSVehicle* aVehicle, double& speed, double& dist, double pos, bool patchSpeed) const;14431444/// @brief check whether any of the outgoing links are being approached1445bool hasApproaching(const std::vector<MSLink*>& links) const;14461447/// @brief return length of fractional vehicles on this lane1448double getFractionalVehicleLength(bool brutto) const;14491450/// @brief detect frontal collisions1451static bool isFrontalCollision(const MSVehicle* collider, const MSVehicle* victim);14521453/// Unique numerical ID (set on reading by netload)1454int myNumericalID;14551456/// The shape of the lane1457PositionVector myShape;14581459/// @brief the outline of the lane (optional)1460PositionVector* myOutlineShape = nullptr;14611462/// The lane index1463int myIndex;14641465/** @brief The lane's vehicles.1466This container holds all vehicles that have their front (longitudinally)1467and their center (laterally) on this lane.1468These are the vehicles that this lane is 'responsibly' for (i.e. when executing movements)14691470The entering vehicles are inserted at the front1471of this container and the leaving ones leave from the back, e.g. the1472vehicle in front of the junction (often called first) is1473myVehicles.back() (if it exists). And if it is an iterator at a1474vehicle, ++it points to the vehicle in front. This is the interaction1475vehicle. */1476VehCont myVehicles;14771478/** @brief The lane's partial vehicles.1479This container holds all vehicles that are partially on this lane but which are1480in myVehicles of another lane.1481Reasons for partial occupancies include the following1482- the back is still on this lane during regular movement1483- the vehicle is performing a continuous lane-change maneuver1484- sub-lane simulation where vehicles can freely move laterally among the lanes of an edge14851486The entering vehicles are inserted at the front1487of this container and the leaving ones leave from the back. */1488VehCont myPartialVehicles;14891490/** @brief Container for lane-changing vehicles. After completion of lane-change-1491process, the containers will be swapped with myVehicles. */1492VehCont myTmpVehicles;14931494/** @brief Buffer for vehicles that moved from their previous lane onto this one.1495* Integrated after all vehicles executed their moves*/1496MFXSynchQue<MSVehicle*, std::vector<MSVehicle*> > myVehBuffer;14971498/** @brief The vehicles which registered maneuvering into the lane within their current action step.1499* This is currently only relevant for sublane simulation, since continuous lanechanging1500* uses the partial vehicle mechanism.1501*1502* The entering vehicles are inserted at the front1503* of this container and the leaving ones leave from the back. */1504VehCont myManeuverReservations;15051506/* @brief list of vehicles that are parking near this lane1507* (not necessarily on the road but having reached their stop on this lane)1508* */1509std::set<const MSBaseVehicle*> myParkingVehicles;15101511/// Lane length [m]1512double myLength;15131514/// Lane width [m]1515const double myWidth;15161517/// Lane's vClass specific stop offset [m]. The map is either of length 0, which means no1518/// special stopOffset was set, or of length 1, where the key is a bitset representing a subset1519/// of the SUMOVehicleClass Enum and the value is the offset in meters.1520StopOffset myLaneStopOffset;15211522/// The lane's edge, for routing only.1523MSEdge* const myEdge;15241525/// Lane-wide speed limit [m/s]1526double myMaxSpeed;1527/// Lane-wide friction coefficient [0..1]1528double myFrictionCoefficient;15291530/// @brief Whether the current speed limit is set by a variable speed sign (VSS)1531bool mySpeedByVSS;15321533/// @brief Whether the current speed limit has been set through TraCI1534bool mySpeedByTraCI;15351536/// The vClass permissions for this lane1537SVCPermissions myPermissions;15381539/// The vClass permissions for changing from this lane1540SVCPermissions myChangeLeft;1541SVCPermissions myChangeRight;15421543/// The original vClass permissions for this lane (before temporary modifications)1544SVCPermissions myOriginalPermissions;15451546/// The vClass speed restrictions for this lane1547const std::map<SUMOVehicleClass, double>* myRestrictions;15481549/// All direct predecessor lanes1550std::vector<IncomingLaneInfo> myIncomingLanes;15511552///1553mutable MSLane* myLogicalPredecessorLane;15541555/// Similar to LogicalPredecessorLane, @see getCanonicalPredecessorLane()1556mutable MSLane* myCanonicalPredecessorLane;15571558/// Main successor lane, @see getCanonicalSuccessorLane()1559mutable MSLane* myCanonicalSuccessorLane;15601561/// @brief The current length of all vehicles on this lane, including their minGaps1562double myBruttoVehicleLengthSum;15631564/// @brief The current length of all vehicles on this lane, excluding their minGaps1565double myNettoVehicleLengthSum;15661567/// @brief The length of all vehicles that have left this lane in the current step (this lane, including their minGaps)1568double myBruttoVehicleLengthSumToRemove;15691570/// @brief The length of all vehicles that have left this lane in the current step (this lane, excluding their minGaps)1571double myNettoVehicleLengthSumToRemove;15721573/// @brief Flag to recalculate the occupancy (including minGaps) after a change in minGap1574bool myRecalculateBruttoSum;15751576/** The lane's Links to its succeeding lanes and the default1577right-of-way rule, i.e. blocked or not blocked. */1578std::vector<MSLink*> myLinks;15791580/// All direct internal and direct (disregarding internal predecessors) non-internal predecessor lanes of this lane1581std::map<MSEdge*, std::vector<MSLane*> > myApproachingLanes;15821583/// @brief leaders on all sublanes as seen by approaching vehicles (cached)1584mutable MSLeaderInfo myLeaderInfo;1585/// @brief followers on all sublanes as seen by vehicles on consecutive lanes (cached)1586mutable MSLeaderInfo myFollowerInfo;15871588/// @brief time step for which myLeaderInfo was last updated1589mutable SUMOTime myLeaderInfoTime;1590/// @brief time step for which myFollowerInfo was last updated1591mutable SUMOTime myFollowerInfoTime;15921593/// @brief precomputed myShape.length / myLength1594const double myLengthGeometryFactor;15951596/// @brief whether this lane is an acceleration lane1597const bool myIsRampAccel;15981599/// @brief the type of this lane1600const std::string myLaneType;16011602/// @brief the combined width of all lanes with lower index on myEdge1603double myRightSideOnEdge;1604/// @brief the index of the rightmost sublane of this lane on myEdge1605int myRightmostSublane;16061607/// @brief whether a collision check is currently needed1608bool myNeedsCollisionCheck;16091610// @brief the neighboring opposite direction or nullptr1611MSLane* myOpposite;16121613// @brief bidi lane or nullptr1614MSLane* myBidiLane;16151616// @brief transient changes in permissions1617std::map<long long, SVCPermissions> myPermissionChanges;16181619// @brief index of the associated thread-rng1620int myRNGIndex;16211622/// definition of the static dictionary type1623typedef std::map< std::string, MSLane* > DictType;16241625/// Static dictionary to associate string-ids with objects.1626static DictType myDict;16271628static std::vector<SumoRNG> myRNGs;16291630private:1631/// @brief This lane's move reminder1632std::vector< MSMoveReminder* > myMoveReminders;16331634/// @brief the action to take on collisions1635static CollisionAction myCollisionAction;1636static CollisionAction myIntermodalCollisionAction;1637static bool myCheckJunctionCollisions;1638static double myCheckJunctionCollisionMinGap;1639static SUMOTime myCollisionStopTime;1640static SUMOTime myIntermodalCollisionStopTime;1641static double myCollisionMinGapFactor;1642static bool myExtrapolateSubstepDepart;1643static DepartSpeedDefinition myDefaultDepartSpeedDefinition;1644static double myDefaultDepartSpeed;1645/**1646* @class vehicle_position_sorter1647* @brief Sorts vehicles by their position (descending)1648*/1649class vehicle_position_sorter {1650public:1651/// @brief Constructor1652explicit vehicle_position_sorter(const MSLane* lane) :1653myLane(lane) {1654}165516561657/** @brief Comparing operator1658* @param[in] v1 First vehicle to compare1659* @param[in] v2 Second vehicle to compare1660* @return Whether the first vehicle is further on the lane than the second1661*/1662int operator()(MSVehicle* v1, MSVehicle* v2) const;16631664const MSLane* myLane;16651666};16671668/**1669* @class vehicle_reverse_position_sorter1670* @brief Sorts vehicles by their position (ascending)1671*/1672class vehicle_natural_position_sorter {1673public:1674/// @brief Constructor1675explicit vehicle_natural_position_sorter(const MSLane* lane) :1676myLane(lane) {1677}167816791680/** @brief Comparing operator1681* @param[in] v1 First vehicle to compare1682* @param[in] v2 Second vehicle to compare1683* @return Whether the first vehicle is further on the lane than the second1684*/1685int operator()(MSVehicle* v1, MSVehicle* v2) const;16861687const MSLane* myLane;16881689};16901691/** @class by_connections_to_sorter1692* @brief Sorts edges by their angle relative to the given edge (straight comes first)1693*1694*/1695class by_connections_to_sorter {1696public:1697/// @brief constructor1698explicit by_connections_to_sorter(const MSEdge* const e);16991700/// @brief comparing operator1701int operator()(const MSEdge* const e1, const MSEdge* const e2) const;17021703private:1704const MSEdge* const myEdge;1705double myLaneDir;1706};1707170817091710/** @class incoming_lane_priority_sorter1711* @brief Sorts lanes (IncomingLaneInfos) by their priority or, if this doesn't apply,1712* wrt. the angle difference magnitude relative to the target lane's angle (straight comes first)1713*/1714class incoming_lane_priority_sorter {1715public:1716/// @brief constructor1717explicit incoming_lane_priority_sorter(const MSLane* targetLane);17181719/// @brief comparing operator1720int operator()(const IncomingLaneInfo& lane1, const IncomingLaneInfo& lane2) const;17211722private:1723const MSLane* const myLane;1724double myLaneDir;1725};172617271728/** @class outgoing_lane_priority_sorter1729* @brief Sorts lanes (their origin link) by the priority of their noninternal target edges or, if this doesn't yield an unambiguous result,1730* wrt. the angle difference magnitude relative to the target lane's angle (straight comes first)1731*/1732class outgoing_lane_priority_sorter {1733public:1734/// @brief constructor1735explicit outgoing_lane_priority_sorter(const MSLane* sourceLane);17361737/// @brief comparing operator1738int operator()(const MSLink* link1, const MSLink* link2) const;17391740private:1741double myLaneDir;1742};17431744/**1745* @class edge_finder1746*/1747class edge_finder {1748public:1749edge_finder(MSEdge* e) : myEdge(e) {}1750bool operator()(const IncomingLaneInfo& ili) const {1751return &(ili.lane->getEdge()) == myEdge;1752}1753private:1754const MSEdge* const myEdge;1755};17561757#ifdef HAVE_FOX1758/// Type of the function that is called for the simulation stage (e.g. planMovements).1759typedef void(MSLane::*Operation)(const SUMOTime);17601761/**1762* @class SimulationTask1763* @brief the routing task which mainly calls reroute of the vehicle1764*/1765class SimulationTask : public MFXWorkerThread::Task {1766public:1767SimulationTask(MSLane& l, const SUMOTime time)1768: myLane(l), myTime(time) {}1769void init(Operation operation, const SUMOTime time) {1770myOperation = operation;1771myTime = time;1772}1773void run(MFXWorkerThread* /*context*/) {1774try {1775(myLane.*(myOperation))(myTime);1776} catch (ProcessError& e) {1777WRITE_ERROR(e.what());1778}1779}1780private:1781Operation myOperation = nullptr;1782MSLane& myLane;1783SUMOTime myTime;1784private:1785/// @brief Invalidated assignment operator.1786SimulationTask& operator=(const SimulationTask&) = delete;1787};17881789SimulationTask mySimulationTask;1790/// @brief Mutex for access to the cached leader info value1791mutable FXMutex myLeaderInfoMutex;1792/// @brief Mutex for access to the cached follower info value1793mutable FXMutex myFollowerInfoMutex;1794/// @brief Mutex for access to the cached follower info value1795mutable FXMutex myPartialOccupatorMutex;1796#endif1797std::vector<StopWatch<std::chrono::nanoseconds> > myStopWatch;17981799private:1800/// @brief invalidated copy constructor1801MSLane(const MSLane&) = delete;18021803/// @brief invalidated assignment operator1804MSLane& operator=(const MSLane&) = delete;180518061807};18081809// specialized implementation for speedup and avoiding warnings1810#define LANE_RTREE_QUAL RTree<MSLane*, MSLane, float, 2, MSLane::StoringVisitor>18111812template<>1813inline float LANE_RTREE_QUAL::RectSphericalVolume(Rect* a_rect) {1814ASSERT(a_rect);1815const float extent0 = a_rect->m_max[0] - a_rect->m_min[0];1816const float extent1 = a_rect->m_max[1] - a_rect->m_min[1];1817return .78539816f * (extent0 * extent0 + extent1 * extent1);1818}18191820template<>1821inline LANE_RTREE_QUAL::Rect LANE_RTREE_QUAL::CombineRect(Rect* a_rectA, Rect* a_rectB) {1822ASSERT(a_rectA && a_rectB);1823Rect newRect;1824newRect.m_min[0] = rtree_min(a_rectA->m_min[0], a_rectB->m_min[0]);1825newRect.m_max[0] = rtree_max(a_rectA->m_max[0], a_rectB->m_max[0]);1826newRect.m_min[1] = rtree_min(a_rectA->m_min[1], a_rectB->m_min[1]);1827newRect.m_max[1] = rtree_max(a_rectA->m_max[1], a_rectB->m_max[1]);1828return newRect;1829}183018311832