90 const double range,
const int domain)
139 bool downstream =
true) :
161 return !(*
this == other);
223 MSLane(
const std::string&
id,
double maxSpeed,
double friction,
double length,
MSEdge*
const edge,
227 int index,
bool isRampAccel,
228 const std::string& type,
252 return (
int)
myRNGs.size();
259 static void loadRNGState(
int index,
const std::string& state);
370 bool recheckNextLanes,
374 bool checkFailure(
const MSVehicle* aVehicle,
double& speed,
double& dist,
const double nspeed,
const bool patchSpeed,
const std::string errorMsg,
InsertionCheck check)
const;
749 void setMaxSpeed(
double val,
bool byVSS =
false,
bool byTraCI =
false,
double jamThreshold = -1);
816 return (
int)
myDict.size();
823 static void insertIDs(std::vector<std::string>& into);
830 template<
class RTREE>
831 static void fill(RTREE& into);
847 const MSLane& succLinkSource,
848 const std::vector<MSLane*>& conts);
853 inline bool isLinkEnd(std::vector<MSLink*>::const_iterator& i)
const {
859 inline bool isLinkEnd(std::vector<MSLink*>::iterator& i) {
998 std::pair<MSVehicle* const, double>
getLeader(
const MSVehicle* veh,
const double vehPos,
const std::vector<MSLane*>& bestLaneConts,
double dist = -1,
bool checkTmpVehicles =
false)
const;
1023 double speed,
const MSVehicle& veh,
const std::vector<MSLane*>& bestLaneConts)
const;
1027 const std::vector<MSLane*>& bestLaneConts,
MSLeaderDistanceInfo& result,
bool oppositeDirection =
false)
const;
1070 std::set<MSVehicle*>
getSurroundingVehicles(
double startPos,
double downstreamDist,
double upstreamDist, std::shared_ptr<LaneCoverageInfo> checkedLanes)
const;
1077 std::vector<const MSJunction*>
getUpcomingJunctions(
double pos,
double range,
const std::vector<MSLane*>& contLanes)
const;
1080 std::vector<const MSLink*>
getUpcomingLinks(
double pos,
double range,
const std::vector<MSLane*>& contLanes)
const;
1167 template<PollutantsInterface::EmissionType ET>
1171 ret += v->getEmissions<ET>();
1271 return &mySimulationTask;
1276 return &mySimulationTask;
1281 return &mySimulationTask;
1342 std::pair<const MSPerson*, double>
nextBlocking(
double minPos,
double minRight,
double maxLeft,
double stopTime = 0,
bool bidi =
false)
const;
1384 const MSLane::VehCont::iterator& at,
1389 SUMOTime timestep,
const std::string& stage,
1390 std::set<const MSVehicle*, ComparatorNumericalIdLess>& toRemove,
1391 std::set<const MSVehicle*, ComparatorNumericalIdLess>& toTeleport);
1395 std::set<const MSVehicle*, ComparatorNumericalIdLess>& toRemove,
1396 std::set<const MSVehicle*, ComparatorNumericalIdLess>& toTeleport)
const;
1400 double gap,
double latGap,
1401 std::set<const MSVehicle*, ComparatorNumericalIdLess>& toRemove,
1402 std::set<const MSVehicle*, ComparatorNumericalIdLess>& toTeleport)
const;
1405 double gap,
const std::string& collisionType,
1406 std::set<const MSVehicle*, ComparatorNumericalIdLess>& toRemove,
1407 std::set<const MSVehicle*, ComparatorNumericalIdLess>& toTeleport)
const;
1751 : myLane(l), myTime(time) {}
1752 void init(Operation operation,
const SUMOTime time) {
1753 myOperation = operation;
1758 (myLane.*(myOperation))(myTime);
1764 Operation myOperation =
nullptr;
1769 SimulationTask& operator=(
const SimulationTask&) =
delete;
1772 SimulationTask mySimulationTask;
1774 mutable FXMutex myLeaderInfoMutex;
1776 mutable FXMutex myFollowerInfoMutex;
1778 mutable FXMutex myPartialOccupatorMutex;
1793#define LANE_RTREE_QUAL RTree<MSLane*, MSLane, float, 2, MSLane::StoringVisitor>
1796inline float LANE_RTREE_QUAL::RectSphericalVolume(Rect* a_rect) {
1798 const float extent0 = a_rect->m_max[0] - a_rect->m_min[0];
1799 const float extent1 = a_rect->m_max[1] - a_rect->m_min[1];
1800 return .78539816f * (extent0 * extent0 + extent1 * extent1);
1804inline LANE_RTREE_QUAL::Rect LANE_RTREE_QUAL::CombineRect(Rect* a_rectA, Rect* a_rectB) {
1805 ASSERT(a_rectA && a_rectB);
1807 newRect.m_min[0] =
rtree_min(a_rectA->m_min[0], a_rectB->m_min[0]);
1808 newRect.m_max[0] =
rtree_max(a_rectA->m_max[0], a_rectB->m_max[0]);
1809 newRect.m_min[1] =
rtree_min(a_rectA->m_min[1], a_rectB->m_min[1]);
1810 newRect.m_max[1] =
rtree_max(a_rectA->m_max[1], a_rectB->m_max[1]);
std::map< const MSLane *, std::pair< double, double > > LaneCoverageInfo
Coverage info.
long long int SVCPermissions
bitset where each bit declares whether a certain SVC may use this edge/lane
SUMOVehicleClass
Definition of vehicle classes to differ between different lane usage and authority types.
InsertionCheck
different checking levels for vehicle insertion
LinkState
The right-of-way state of a link between two lanes used when constructing a NBTrafficLightLogic,...
Abstract superclass of a task to be run with an index to keep track of pending tasks.
A thread repeatingly calculating incoming tasks.
The base class for microscopic and mesoscopic vehicles.
A road/street connecting two junctions.
static int gNumSimThreads
how many threads to use for simulation
The base class for an intersection.
AnyVehicleIterator is a structure, which manages the iteration through all vehicles on the lane,...
bool operator!=(AnyVehicleIterator const &other) const
int myI2End
end index for myPartialVehicles
int myI2
index for myPartialVehicles
bool myDownstream
iteration direction
const MSVehicle * operator->()
bool nextIsMyVehicles() const
int myI3
index for myTmpVehicles
int myDirection
index delta
AnyVehicleIterator & operator++()
const MSLane * myLane
the lane that is being iterated
bool operator==(AnyVehicleIterator const &other) const
const MSVehicle * operator*()
int myI3End
end index for myTmpVehicles
AnyVehicleIterator(const MSLane *lane, int i1, int i2, int i3, const int i1End, const int i2End, const int i3End, bool downstream=true)
int myI1End
end index for myVehicles
int myI1
index for myVehicles
StoringVisitor(const StoringVisitor &src)
invalidated copy constructor
void add(const MSLane *const l) const
Adds the given object to the container.
StoringVisitor(std::set< const Named * > &objects, const PositionVector &shape, const double range, const int domain)
Constructor.
StoringVisitor & operator=(const StoringVisitor &src)
invalidated assignment operator
std::set< const Named * > & myObjects
The container.
const PositionVector & myShape
Sorts edges by their angle relative to the given edge (straight comes first)
const MSEdge *const myEdge
int operator()(const MSEdge *const e1, const MSEdge *const e2) const
comparing operator
bool operator()(const IncomingLaneInfo &ili) const
const MSEdge *const myEdge
Sorts lanes (IncomingLaneInfos) by their priority or, if this doesn't apply, wrt. the angle differenc...
const MSLane *const myLane
int operator()(const IncomingLaneInfo &lane1, const IncomingLaneInfo &lane2) const
comparing operator
Sorts lanes (their origin link) by the priority of their noninternal target edges or,...
int operator()(const MSLink *link1, const MSLink *link2) const
comparing operator
vehicle_natural_position_sorter(const MSLane *lane)
Constructor.
int operator()(MSVehicle *v1, MSVehicle *v2) const
Comparing operator.
Sorts vehicles by their position (descending)
int operator()(MSVehicle *v1, MSVehicle *v2) const
Comparing operator.
vehicle_position_sorter(const MSLane *lane)
Constructor.
Performs lane changing of vehicles.
Performs lane changing of vehicles.
Representation of a lane in the micro simulation.
std::vector< StopWatch< std::chrono::nanoseconds > > & getStopWatch()
void addApproachingLane(MSLane *lane, bool warnMultiCon)
bool detectCollisionBetween(SUMOTime timestep, const std::string &stage, MSVehicle *collider, MSVehicle *victim, std::set< const MSVehicle *, ComparatorNumericalIdLess > &toRemove, std::set< const MSVehicle *, ComparatorNumericalIdLess > &toTeleport) const
detect whether there is a collision between the two vehicles
static SUMOTime myIntermodalCollisionStopTime
MFXSynchQue< MSVehicle *, std::vector< MSVehicle * > > myVehBuffer
Buffer for vehicles that moved from their previous lane onto this one. Integrated after all vehicles ...
SVCPermissions myPermissions
The vClass permissions for this lane.
MSLane * myLogicalPredecessorLane
static void initCollisionAction(const OptionsCont &oc, const std::string &option, CollisionAction &myAction)
virtual void setJunctionApproaches(const SUMOTime t) const
Register junction approaches for all vehicles after velocities have been planned.
const std::vector< MSMoveReminder * > & getMoveReminders() const
Return the list of this lane's move reminders.
std::set< const MSBaseVehicle * > myParkingVehicles
bool checkForPedestrians(const MSVehicle *aVehicle, double &speed, double &dist, double pos, bool patchSpeed) const
check whether pedestrians on this lane interfere with vehicle insertion
std::pair< MSVehicle *const, double > getFollower(const MSVehicle *ego, double egoPos, double dist, MinorLinkMode mLinkMode) const
Find follower vehicle for the given ego vehicle (which may be on the opposite direction lane)
std::pair< const MSPerson *, double > nextBlocking(double minPos, double minRight, double maxLeft, double stopTime=0, bool bidi=false) const
This is just a wrapper around MSPModel::nextBlocking. You should always check using hasPedestrians be...
MSLane * getParallelLane(int offset, bool includeOpposite=true) const
Returns the lane with the given offset parallel to this one or 0 if it does not exist.
double myRightSideOnEdge
the combined width of all lanes with lower index on myEdge
const StopOffset & getLaneStopOffsets() const
Returns vehicle class specific stopOffsets.
virtual void removeParking(MSBaseVehicle *veh)
remove parking vehicle. This must be syncrhonized when running with GUI
virtual ~MSLane()
Destructor.
static CollisionAction getIntermodalCollisionAction()
bool insertVehicle(MSVehicle &v)
Tries to insert the given vehicle.
const MSLeaderInfo getFirstVehicleInformation(const MSVehicle *ego, double latOffset, bool onlyFrontOnLane, double maxPos=std::numeric_limits< double >::max(), bool allowCached=true) const
analogue to getLastVehicleInformation but in the upstream direction
virtual void integrateNewVehicles()
Insert buffered vehicle into the real lane.
double myLength
Lane length [m].
bool isApproachedFrom(MSEdge *const edge)
double getNettoOccupancy() const
Returns the netto (excluding minGaps) occupancy of this lane during the last step (including minGaps)
virtual MSVehicle * removeVehicle(MSVehicle *remVehicle, MSMoveReminder::Notification notification, bool notify=true)
int getCrossingIndex() const
return the index of the link to the next crossing if this is walkingArea, else -1
PositionVector myShape
The shape of the lane.
PositionVector * myOutlineShape
the outline of the lane (optional)
std::map< long long, SVCPermissions > myPermissionChanges
int getRNGIndex() const
returns the associated RNG index
double getFrictionCoefficient() const
Returns the lane's friction coefficient.
const std::map< SUMOVehicleClass, double > * myRestrictions
The vClass speed restrictions for this lane.
virtual void incorporateVehicle(MSVehicle *veh, double pos, double speed, double posLat, const MSLane::VehCont::iterator &at, MSMoveReminder::Notification notification=MSMoveReminder::NOTIFICATION_DEPARTED)
Inserts the vehicle into this lane, and informs it about entering the network.
void initRestrictions()
initialized vClass-specific speed limits
std::vector< MSMoveReminder * > myMoveReminders
This lane's move reminder.
MSLane & operator=(const MSLane &)=delete
invalidated assignment operator
bool hasApproaching() const
SVCPermissions getChangeRight() const
Returns the vehicle class permissions for changing to the right neighbour lane.
void addParking(MSBaseVehicle *veh)
add parking vehicle. This should only used during state loading
VehCont myTmpVehicles
Container for lane-changing vehicles. After completion of lane-change- process, the containers will b...
double getDepartSpeed(const MSVehicle &veh, bool &patchSpeed)
MSLeaderInfo myFollowerInfo
followers on all sublanes as seen by vehicles on consecutive lanes (cached)
const MSLane * getNormalSuccessorLane() const
get normal lane following this internal lane, for normal lanes, the lane itself is returned
int getVehicleNumber() const
Returns the number of vehicles on this lane (for which this lane is responsible)
static SUMOTime myCollisionStopTime
static CollisionAction myCollisionAction
the action to take on collisions
MSLane * myCanonicalSuccessorLane
Main successor lane,.
SVCPermissions myChangeLeft
The vClass permissions for changing from this lane.
void getLeadersOnConsecutive(double dist, double seen, double speed, const MSVehicle *ego, const std::vector< MSLane * > &bestLaneConts, MSLeaderDistanceInfo &result, bool oppositeDirection=false) const
Returns the immediate leaders and the distance to them (as getLeaderOnConsecutive but for the sublane...
std::vector< IncomingLaneInfo > myIncomingLanes
All direct predecessor lanes.
AnyVehicleIterator anyVehiclesEnd() const
end iterator for iterating over all vehicles touching this lane in downstream direction
static void insertIDs(std::vector< std::string > &into)
Adds the ids of all stored lanes into the given vector.
bool hadPermissionChanges() const
void sortPartialVehicles()
sorts myPartialVehicles
double myFrictionCoefficient
Lane-wide friction coefficient [0..1].
MSVehicle * getFirstAnyVehicle() const
returns the first vehicle that is fully or partially on this lane
MSLane(const MSLane &)=delete
invalidated copy constructor
const MSLink * getEntryLink() const
Returns the entry link if this is an internal lane, else nullptr.
int getVehicleNumberWithPartials() const
Returns the number of vehicles on this lane (including partial occupators)
static bool myCheckJunctionCollisions
static void clear()
Clears the dictionary.
double getBruttoVehLenSum() const
Returns the sum of lengths of vehicles, including their minGaps, which were on the lane during the la...
virtual void resetManeuverReservation(MSVehicle *v)
Unregisters a vehicle, which previously registered for maneuvering into this lane.
SVCPermissions myOriginalPermissions
The original vClass permissions for this lane (before temporary modifications)
MSEdge *const myEdge
The lane's edge, for routing only.
double myNettoVehicleLengthSum
The current length of all vehicles on this lane, excluding their minGaps.
bool empty() const
Returns true if there is not a single vehicle on the lane.
static int getInsertionChecks(const MSVehicle *veh)
bool allowsChangingRight(SUMOVehicleClass vclass) const
Returns whether the given vehicle class may change left from this lane.
static std::vector< MSLink * >::const_iterator succLinkSec(const SUMOVehicle &veh, int nRouteSuccs, const MSLane &succLinkSource, const std::vector< MSLane * > &conts)
void detectPedestrianJunctionCollision(const MSVehicle *collider, const PositionVector &colliderBoundary, const MSLane *foeLane, SUMOTime timestep, const std::string &stage, std::set< const MSVehicle *, ComparatorNumericalIdLess > &toRemove, std::set< const MSVehicle *, ComparatorNumericalIdLess > &toTeleport)
detect whether a vehicle collids with pedestrians on the junction
double getMissingRearGap(const MSVehicle *leader, double backOffset, double leaderSpeed) const
return by how much further the leader must be inserted to avoid rear end collisions
double myMaxSpeed
Lane-wide speed limit [m/s].
void saveState(OutputDevice &out)
Saves the state of this lane into the given stream.
void markRecalculateBruttoSum()
Set a flag to recalculate the brutto (including minGaps) occupancy of this lane (used if mingap is ch...
const MSLink * getLinkTo(const MSLane *const) const
returns the link to the given lane or nullptr, if it is not connected
int myRightmostSublane
the index of the rightmost sublane of this lane on myEdge
void setChangeRight(SVCPermissions permissions)
Sets the permissions for changing to the right neighbour lane.
const bool myIsRampAccel
whether this lane is an acceleration lane
virtual void planMovements(const SUMOTime t)
Compute safe velocities for all vehicles based on positions and speeds from the last time step....
virtual double getLengthGeometryFactor(bool) const
static void saveRNGStates(OutputDevice &out)
save random number generator states to the given output device
void visit(const MSLane::StoringVisitor &cont) const
Callback for visiting the lane when traversing an RTree.
SUMOTime myFollowerInfoTime
time step for which myFollowerInfo was last updated
MSLeaderInfo myLeaderInfo
leaders on all sublanes as seen by approaching vehicles (cached)
bool isInsertionSuccess(MSVehicle *vehicle, double speed, double pos, double posLat, bool recheckNextLanes, MSMoveReminder::Notification notification)
Tries to insert the given vehicle with the given state (speed and pos)
void forceVehicleInsertion(MSVehicle *veh, double pos, MSMoveReminder::Notification notification, double posLat=0)
Inserts the given vehicle at the given position.
double getVehicleStopOffset(const MSVehicle *veh) const
Returns vehicle class specific stopOffset for the vehicle.
static void initCollisionOptions(const OptionsCont &oc)
int myNumericalID
Unique numerical ID (set on reading by netload)
bool isAccelLane() const
return whether this lane is an acceleration lane
VehCont myVehicles
The lane's vehicles. This container holds all vehicles that have their front (longitudinally) and the...
double getSpeedLimit() const
Returns the lane's maximum allowed speed.
MSLeaderInfo getPartialBeyond() const
get all vehicles that are inlapping from consecutive edges
std::vector< MSVehicle * > VehCont
Container for vehicles.
bool checkFailure(const MSVehicle *aVehicle, double &speed, double &dist, const double nspeed, const bool patchSpeed, const std::string errorMsg, InsertionCheck check) const
static DictType myDict
Static dictionary to associate string-ids with objects.
static void fill(RTREE &into)
Fills the given RTree with lane instances.
double safeInsertionSpeed(const MSVehicle *veh, double seen, const MSLeaderInfo &leaders, double speed)
return the maximum safe speed for insertion behind leaders (a negative value indicates that safe inse...
std::vector< const MSJunction * > getUpcomingJunctions(double pos, double range, const std::vector< MSLane * > &contLanes) const
Returns all upcoming junctions within given range along the given (non-internal) continuation lanes m...
void addIncomingLane(MSLane *lane, MSLink *viaLink)
bool isWalkingArea() const
const MSEdge * getNextNormal() const
Returns the lane's follower if it is an internal lane, the edge of the lane otherwise.
SVCPermissions getChangeLeft() const
Returns the vehicle class permissions for changing to the left neighbour lane.
void addLink(MSLink *link)
Delayed initialization.
std::set< MSVehicle * > getVehiclesInRange(const double a, const double b) const
Returns all vehicles on the lane overlapping with the interval [a,b].
void enteredByLaneChange(MSVehicle *v)
double getDepartPosLat(const MSVehicle &veh)
const std::string & getLaneType() const
return the type of this lane
std::pair< MSVehicle *const, double > getOppositeLeader(const MSVehicle *ego, double dist, bool oppositeDir, MinorLinkMode mLinkMode=MinorLinkMode::FOLLOW_NEVER) const
int getThreadIndex() const
returns the associated thread index
SVCPermissions getPermissions() const
Returns the vehicle class permissions for this lane.
LinkState getIncomingLinkState() const
get the state of the link from the logical predecessor to this lane
void updateLengthSum()
updated current vehicle length sum (delayed to avoid lane-order-dependency)
const std::vector< IncomingLaneInfo > & getIncomingLanes() const
static const long CHANGE_PERMISSIONS_PERMANENT
MSLane * getCanonicalPredecessorLane() const
void resetPermissions(long long transientID)
MSVehicle * getLastFullVehicle() const
returns the last vehicle for which this lane is responsible or 0
static void loadRNGState(int index, const std::string &state)
load random number generator state for the given rng index
const std::string myLaneType
the type of this lane
VehCont myManeuverReservations
The vehicles which registered maneuvering into the lane within their current action step....
void addLeaders(const MSVehicle *vehicle, double vehPos, MSLeaderDistanceInfo &result, bool oppositeDirection=false)
get leaders for ego on the given lane
bool needsCollisionCheck() const
short-circut collision check if nothing changed since the last check
static double myCheckJunctionCollisionMinGap
double getLength() const
Returns the lane's length.
double myBruttoVehicleLengthSum
The current length of all vehicles on this lane, including their minGaps.
const PositionVector & getShape() const
Returns this lane's shape.
void setChangeLeft(SVCPermissions permissions)
Sets the permissions for changing to the left neighbour lane.
std::vector< const MSLink * > getUpcomingLinks(double pos, double range, const std::vector< MSLane * > &contLanes) const
Returns all upcoming links within given range along the given (non-internal) continuation lanes measu...
const MSLane * getFirstInternalInConnection(double &offset) const
Returns 0 if the lane is not internal. Otherwise the first part of the connection (sequence of intern...
static int getNumRNGs()
return the number of RNGs
void handleCollisionBetween(SUMOTime timestep, const std::string &stage, const MSVehicle *collider, const MSVehicle *victim, double gap, double latGap, std::set< const MSVehicle *, ComparatorNumericalIdLess > &toRemove, std::set< const MSVehicle *, ComparatorNumericalIdLess > &toTeleport) const
take action upon collision
double getMaximumBrakeDist() const
compute maximum braking distance on this lane
static CollisionAction myIntermodalCollisionAction
const MSLane * getInternalFollowingLane(const MSLane *const) const
returns the internal lane leading to the given lane or nullptr, if there is none
bool isLinkEnd(std::vector< MSLink * >::iterator &i)
static std::vector< SumoRNG > myRNGs
bool allowsChangingLeft(SUMOVehicleClass vclass) const
Returns whether the given vehicle class may change left from this lane.
virtual void swapAfterLaneChange(SUMOTime t)
moves myTmpVehicles int myVehicles after a lane change procedure
std::pair< MSVehicle *const, double > getCriticalLeader(double dist, double seen, double speed, const MSVehicle &veh) const
Returns the most dangerous leader and the distance to him.
StopOffset myLaneStopOffset
const MSLeaderInfo getLastVehicleInformation(const MSVehicle *ego, double latOffset, double minPos=0, bool allowCached=true) const
Returns the last vehicles on the lane.
static void initRNGs(const OptionsCont &oc)
initialize rngs
std::set< MSVehicle * > getSurroundingVehicles(double startPos, double downstreamDist, double upstreamDist, std::shared_ptr< LaneCoverageInfo > checkedLanes) const
Returns all vehicles closer than downstreamDist along the road network starting on the given position...
bool myRecalculateBruttoSum
Flag to recalculate the occupancy (including minGaps) after a change in minGap.
virtual void removeMoveReminder(MSMoveReminder *rem)
Remove a move-reminder from move-reminder container.
void clearState()
Remove all vehicles before quick-loading state.
MSLane * myCanonicalPredecessorLane
Similar to LogicalPredecessorLane,.
bool myNeedsCollisionCheck
whether a collision check is currently needed
bool isLinkEnd(std::vector< MSLink * >::const_iterator &i) const
bool allowsVehicleClass(SUMOVehicleClass vclass) const
virtual double setPartialOccupation(MSVehicle *v)
Sets the information about a vehicle lapping into this lane.
double getVehicleMaxSpeed(const SUMOTrafficObject *const veh) const
Returns the lane's maximum speed, given a vehicle's speed limit adaptation.
void setBidiLane(MSLane *bidyLane)
Adds the (overlapping) reverse direction lane to this lane.
double getRightSideOnEdge() const
std::pair< MSVehicle *const, double > getOppositeFollower(const MSVehicle *ego) const
bool mySpeedByTraCI
Whether the current speed limit has been set through TraCI.
bool hasPedestrians() const
whether the lane has pedestrians on it
const std::vector< std::pair< const MSLane *, const MSEdge * > > getOutgoingViaLanes() const
get the list of outgoing lanes
MSVehicle * getPartialBehind(const MSVehicle *ego) const
int getIndex() const
Returns the lane's index.
void setLaneStopOffset(const StopOffset &stopOffset)
Set vehicle class specific stopOffsets.
double myBruttoVehicleLengthSumToRemove
The length of all vehicles that have left this lane in the current step (this lane,...
void leftByLaneChange(MSVehicle *v)
MSLane * getCanonicalSuccessorLane() const
void requireCollisionCheck()
require another collision check due to relevant changes in the simulation
std::vector< StopWatch< std::chrono::nanoseconds > > myStopWatch
void setPermissions(SVCPermissions permissions, long long transientID)
Sets the permissions to the given value. If a transientID is given, the permissions are recored as te...
const double myWidth
Lane width [m].
bool lastInsertion(MSVehicle &veh, double mspeed, double posLat, bool patchSpeed)
inserts vehicle as close as possible to the last vehicle on this lane (or at the end of the lane if t...
virtual void addSecondaryShape(const PositionVector &)
void changeLanes(const SUMOTime time)
double getOppositePos(double pos) const
return the corresponding position on the opposite lane
SVCPermissions myChangeRight
const double myLengthGeometryFactor
precomputed myShape.length / myLength
virtual void executeMovements(const SUMOTime t)
Executes planned vehicle movements with regards to right-of-way.
const std::set< const MSBaseVehicle * > & getParkingVehicles() const
retrieve the parking vehicles (see GUIParkingArea)
MSLane * getLogicalPredecessorLane() const
get the most likely precedecessor lane (sorted using by_connections_to_sorter). The result is cached ...
double getBruttoOccupancy() const
Returns the brutto (including minGaps) occupancy of this lane during the last step.
AnyVehicleIterator anyVehiclesUpstreamEnd() const
end iterator for iterating over all vehicles touching this lane in upstream direction
int myIndex
The lane index.
double getCenterOnEdge() const
double getMeanSpeedBike() const
get the mean speed of all bicycles on this lane
void updateLeaderInfo(const MSVehicle *veh, VehCont::reverse_iterator &vehPart, VehCont::reverse_iterator &vehRes, MSLeaderInfo &ahead) const
This updates the MSLeaderInfo argument with respect to the given MSVehicle. All leader-vehicles on th...
double getWaitingSeconds() const
Returns the overall waiting time on this lane.
static bool dictionary(const std::string &id, MSLane *lane)
Static (sic!) container methods {.
virtual bool isSelected() const
whether this lane is selected in the GUI
virtual void detectCollisions(SUMOTime timestep, const std::string &stage)
Check if vehicles are too close.
std::vector< MSLink * > myLinks
MSVehicle * getLastAnyVehicle() const
returns the last vehicle that is fully or partially on this lane
static const long CHANGE_PERMISSIONS_GUI
VehCont myPartialVehicles
The lane's partial vehicles. This container holds all vehicles that are partially on this lane but wh...
void sortManeuverReservations()
sorts myManeuverReservations
MinorLinkMode
determine whether/how getFollowers looks upstream beyond minor links
int getPartialVehicleNumber() const
Returns the number of vehicles partially on this lane (for which this lane is not responsible)
double interpolateGeometryPosToLanePos(double geometryPos) const
AnyVehicleIterator anyVehiclesUpstreamBegin() const
begin iterator for iterating over all vehicles touching this lane in upstream direction
std::vector< const MSLane * > getNormalIncomingLanes() const
get the list of all direct (disregarding internal predecessors) non-internal predecessor lanes of thi...
bool mySpeedByVSS
Whether the current speed limit is set by a variable speed sign (VSS)
virtual void resetPartialOccupation(MSVehicle *v)
Removes the information about a vehicle lapping into this lane.
SumoRNG * getRNG() const
return the associated RNG
void setOpposite(MSLane *oppositeLane)
Adds a neighbor to this lane.
static int dictSize()
Returns the number of stored lanes.
AnyVehicleIterator anyVehiclesBegin() const
begin iterator for iterating over all vehicles touching this lane in downstream direction
double getHarmonoise_NoiseEmissions() const
Returns the sum of last step noise emissions.
std::pair< MSVehicle *const, double > getLeader(const MSVehicle *veh, const double vehPos, const std::vector< MSLane * > &bestLaneConts, double dist=-1, bool checkTmpVehicles=false) const
Returns the immediate leader of veh and the distance to veh starting on this lane.
void handleIntermodalCollisionBetween(SUMOTime timestep, const std::string &stage, const MSVehicle *collider, const MSTransportable *victim, double gap, const std::string &collisionType, std::set< const MSVehicle *, ComparatorNumericalIdLess > &toRemove, std::set< const MSVehicle *, ComparatorNumericalIdLess > &toTeleport) const
static bool myExtrapolateSubstepDepart
MSLane * getOpposite() const
return the neighboring opposite direction lane for lane changing or nullptr
void setLength(double val)
Sets a new length for the lane (used by TraCI only)
std::map< MSEdge *, std::vector< MSLane * > > myApproachingLanes
All direct internal and direct (disregarding internal predecessors) non-internal predecessor lanes of...
virtual const VehCont & getVehiclesSecure() const
Returns the vehicles container; locks it for microsimulation.
virtual void releaseVehicles() const
Allows to use the container for microsimulation again.
bool mustCheckJunctionCollisions() const
whether this lane must check for junction collisions
double interpolateLanePosToGeometryPos(double lanePos) const
virtual void setManeuverReservation(MSVehicle *v)
Registers the lane change intentions (towards this lane) for the given vehicle.
MSLane * getBidiLane() const
retrieve bidirectional lane or nullptr
static double myCollisionMinGapFactor
std::pair< MSVehicle *const, double > getLeaderOnConsecutive(double dist, double seen, double speed, const MSVehicle &veh, const std::vector< MSLane * > &bestLaneConts) const
Returns the immediate leader and the distance to him.
bool hasApproaching(const std::vector< MSLink * > &links) const
check whether any of the outgoing links are being approached
double getLengthGeometryFactor() const
return shape.length() / myLength
SUMOTime myLeaderInfoTime
time step for which myLeaderInfo was last updated
@ COLLISION_ACTION_TELEPORT
@ COLLISION_ACTION_REMOVE
virtual const PositionVector & getShape(bool) const
MSLane * getParallelOpposite() const
return the opposite direction lane of this lanes edge or nullptr
std::map< std::string, MSLane * > DictType
definition of the static dictionary type
double getFractionalVehicleLength(bool brutto) const
return length of fractional vehicles on this lane
MSEdge & getEdge() const
Returns the lane's edge.
const PositionVector * getOutlineShape() const
double getSpaceTillLastStanding(const MSVehicle *ego, bool &foundStopped) const
return the empty space up to the last standing vehicle or the empty space on the whole lane if no veh...
double getEmissions() const
Returns the sum of last step emissions The value is always per 1s, so multiply by step length if nece...
const MSLane * getNormalPredecessorLane() const
get normal lane leading to this internal lane, for normal lanes, the lane itself is returned
int getNumericalID() const
Returns this lane's numerical id.
void setRightSideOnEdge(double value, int rightmostSublane)
virtual bool appropriate(const MSVehicle *veh) const
MSLeaderDistanceInfo getFollowersOnConsecutive(const MSVehicle *ego, double backOffset, bool allSublanes, double searchDist=-1, MinorLinkMode mLinkMode=FOLLOW_ALWAYS) const
return the sublane followers with the largest missing rear gap among all predecessor lanes (within di...
double getWidth() const
Returns the lane's width.
const std::vector< MSLink * > & getLinkCont() const
returns the container with all links !!!
bool freeInsertion(MSVehicle &veh, double speed, double posLat, MSMoveReminder::Notification notification=MSMoveReminder::NOTIFICATION_DEPARTED)
Tries to insert the given vehicle on any place.
void setMaxSpeed(double val, bool byVSS=false, bool byTraCI=false, double jamThreshold=-1)
Sets a new maximum speed for the lane (used by TraCI and MSCalibrator)
virtual void addMoveReminder(MSMoveReminder *rem)
Add a move-reminder to move-reminder container.
MSVehicle * getFirstFullVehicle() const
returns the first vehicle for which this lane is responsible or 0
int getRightmostSublane() const
double getMeanSpeed() const
Returns the mean speed on this lane.
double myNettoVehicleLengthSumToRemove
The length of all vehicles that have left this lane in the current step (this lane,...
void loadState(const std::vector< std::string > &vehIDs, MSVehicleControl &vc)
Loads the state of this segment with the given parameters.
const Position geometryPositionAtOffset(double offset, double lateralOffset=0) const
void setFrictionCoefficient(double val)
Sets a new friction coefficient for the lane [to be later (used by TraCI and MSCalibrator)].
static CollisionAction getCollisionAction()
saves leader/follower vehicles and their distances relative to an ego vehicle
Something on a lane to be noticed about vehicle movement.
Notification
Definition of a vehicle state.
@ NOTIFICATION_DEPARTED
The vehicle has departed (was inserted into the network)
Export the queueing length in front of a junction (very experimental!)
The class responsible for building and deletion of vehicles.
Representation of a vehicle in the micro simulation.
Base class for objects which have an id.
A storage for options typed value containers)
Static storage of an output device and its base (abstract) implementation.
An upper class for objects with additional parameters.
A point in 2D or 3D with translation and scaling methods.
Position positionAtOffset(double pos, double lateralOffset=0) const
Returns the position at the given length.
Representation of a vehicle, person, or container.
virtual double getChosenSpeedFactor() const =0
virtual double getMaxSpeed() const =0
Returns the object's maximum speed (minimum of technical and desired maximum speed)
virtual SUMOVehicleClass getVClass() const =0
Returns the object's access class.
Representation of a vehicle.