71 #ifdef CHECK_MEMORY_LEAKS
73 #endif // CHECK_MEMORY_LEAKS
89 myShape(shape), myNumericalID(numericalID),
90 myVehicles(), myLength(length), myWidth(width), myEdge(edge), myMaxSpeed(maxSpeed),
91 myPermissions(permissions),
92 myLogicalPredecessorLane(0),
93 myVehicleLengthSum(0), myInlappingVehicleEnd(10000), myInlappingVehicle(0),
94 myLengthGeometryFactor(myShape.length() / myLength) {}
98 for (MSLinkCont::iterator i =
myLinks.begin(); i !=
myLinks.end(); ++i) {
115 (*veh)->addReminder(rem);
154 if (leader.first != 0) {
156 vIn = leader.first->getSpeed();
157 leaderDecel = leader.first->getCarFollowModel().getMaxDecel();
163 const SUMOReal vHlp = 0.5 * (vIn + mspeed);
167 for (
int i = 0; i <= 10; i++) {
178 }
else if (x > maxPos) {
198 if (leader.first != 0) {
200 vIn = leader.first->getSpeed();
206 const SUMOReal vHlp = 0.5 * (mspeed + vIn);
210 }
else if (xIn > maxPos) {
224 MSLane::VehCont::iterator predIt =
myVehicles.begin();
227 MSLane::VehCont::iterator maxIt =
myVehicles.begin();
246 const SUMOReal lhs = nettoGap / tau + tauDecel - fSpeed - fSpeed * fSpeed / (2 * tauDecel) + leaderSpeed * leaderSpeed / (2 * tauDecel);
247 if (lhs >= sqrt(tauDecel * tauDecel + leaderSpeed * leaderSpeed)) {
249 const SUMOReal currentMaxSpeed = lhs - tauDecel;
250 if (
MIN2(currentMaxSpeed, mspeed) > maxSpeed) {
251 maxSpeed = currentMaxSpeed;
252 maxPos = leaderRearPos + frontGap;
270 bool adaptableSpeed =
true;
280 if (adaptableSpeed) {
284 if (leaderPos - frontGapNeeded >= 0) {
293 MSLane::VehCont::iterator predIt =
myVehicles.begin();
301 if (adaptableSpeed && leader != 0) {
313 frontMax = leaderRearPos - frontGapNeeded;
321 if (frontMax > 0 && backMin +
POSITION_EPS < frontMax) {
338 bool patchSpeed =
true;
374 for (
unsigned int i = 0; i < 10; i++) {
411 aVehicle->
getID() +
"'. Inserting at lane end instead.");
417 std::vector<MSLane*>::const_iterator ri = bestLaneConts.begin();
422 unsigned int nRouteSuccs = 1;
423 MSLane* currentLane =
this;
426 while (seen < dist && ri != bestLaneConts.end()) {
428 MSLinkCont::const_iterator link = currentLane->
succLinkSec(*aVehicle, nRouteSuccs, *currentLane, bestLaneConts);
434 if (nspeed < speed) {
436 speed =
MIN2(nspeed, speed);
440 WRITE_ERROR(
"Vehicle '" + aVehicle->
getID() +
"' will not be able to depart using the given velocity due (arrival speed too low)!");
449 if (nspeed < speed) {
451 speed =
MIN2(nspeed, speed);
455 WRITE_ERROR(
"Vehicle '" + aVehicle->
getID() +
"' will not be able to depart using the given velocity (junction too close)!");
464 || !(*link)->havePriority()) {
467 if (nspeed < speed) {
469 speed =
MIN2(nspeed, speed);
473 const LinkState state = (*link)->getState();
479 WRITE_ERROR(
"Vehicle '" + aVehicle->
getID() +
"' will not be able to depart using the given velocity (unpriorised junction too close)!");
488 nextLane = (*link)->getViaLaneOrLane();
508 if (nspeed < speed) {
510 speed =
MIN2(nspeed, speed);
520 if (nspeed < speed) {
523 speed =
MIN2(cfModel.
freeSpeed(aVehicle, speed, seen, nspeed), speed);
527 WRITE_ERROR(
"Vehicle '" + aVehicle->
getID() +
"' will not be able to depart using the given velocity (slow lane ahead)!");
537 if ((*link)->hasApproachingFoe(arrivalTime, leaveTime, speed, cfModel.
getMaxDecel())) {
539 if (nspeed < speed) {
541 speed =
MIN2(nspeed, speed);
550 currentLane = nextLane;
551 #ifdef HAVE_INTERNAL_LANES
552 if ((*link)->getViaLane() == 0) {
570 if (gap < frontGapNeeded) {
582 if (gap < backGapNeeded) {
595 if (missingRearGap > 0) {
597 const SUMOReal neededStartPos = pos + missingRearGap;
600 pos = neededStartPos;
626 if (leftVehicleLength > myLength) {
644 std::pair<MSVehicle*, SUMOReal>
650 return std::make_pair(last, pos);
656 return std::make_pair<MSVehicle*, SUMOReal>(0, 0);
667 if ((*veh)->getLane() ==
this) {
668 (*veh)->planMove(t, pred, cumulatedVehLength);
682 VehCont::iterator lastVeh =
myVehicles.end() - 1;
683 for (VehCont::iterator veh =
myVehicles.begin(); veh != lastVeh;) {
684 VehCont::iterator pred = veh + 1;
685 if ((*veh)->hasInfluencer() && (*veh)->getInfluencer().isVTDControlled()) {
689 if ((*pred)->hasInfluencer() && (*pred)->getInfluencer().isVTDControlled()) {
693 SUMOReal gap = (*pred)->getPositionOnLane() - (*pred)->getVehicleType().getLength() - (*veh)->getPositionOnLane() - (*veh)->getVehicleType().getMinGap();
698 + (*pred)->getID() +
"', lane='" +
getID() +
"', gap=" +
toString(gap)
710 + (*pred)->getID() +
"', lane='" +
getID() +
"', gap=" +
toString(gap)
748 }
else if (target != 0 && moved) {
759 into.push_back(target);
762 if (shadowLane != 0) {
763 into.push_back(shadowLane);
774 WRITE_WARNING(
"Teleporting vehicle '" + veh->
getID() +
"'; beyond lane (2), targetLane='" +
getID() +
"', time=" +
795 + (r2 ?
" on highway" :
"")
808 DictType::iterator it =
myDict.find(
id);
811 myDict.insert(DictType::value_type(
id, ptr));
820 DictType::iterator it =
myDict.find(
id);
831 for (DictType::iterator i =
myDict.begin(); i !=
myDict.end(); ++i) {
840 for (DictType::iterator i =
myDict.begin(); i !=
myDict.end(); ++i) {
841 into.push_back((*i).first);
852 return (link !=
myLinks.end());
900 MSLinkCont::const_iterator
902 const MSLane& succLinkSource,
const std::vector<MSLane*>& conts)
const {
905 if (nRouteEdge == 0) {
907 return succLinkSource.
myLinks.end();
911 assert(succLinkSource.
myLinks.size() == 1);
913 return succLinkSource.
myLinks.begin();
923 MSLinkCont::const_iterator link;
924 if (nRouteSuccs < conts.size()) {
926 for (link = succLinkSource.
myLinks.begin(); link != succLinkSource.
myLinks.end(); ++link) {
927 if ((*link)->getLane() != 0 && (*link)->getLane()->myEdge == nRouteEdge && (*link)->getLane()->allowsVehicleClass(veh.
getVehicleType().
getVehicleClass())) {
929 if ((*link)->getLane() == conts[nRouteSuccs]) {
936 return succLinkSource.
myLinks.end();
939 return succLinkSource.
myLinks.end();
960 if (remVehicle == *it) {
1005 std::map<MSEdge*, std::vector<MSLane*> >::const_iterator i =
myApproachingLanes.find(edge);
1009 const std::vector<MSLane*>& lanes = (*i).second;
1010 return find(lanes.begin(), lanes.end(), lane) != lanes.end();
1016 inline int operator()(
const std::pair<const MSVehicle* , SUMOReal>& p1,
const std::pair<const MSVehicle* , SUMOReal>& p2)
const {
1017 return p1.second < p2.second;
1027 std::set<MSLane*> visited;
1028 std::vector<MSLane::IncomingLaneInfo> newFound;
1030 while (toExamine.size() != 0) {
1031 for (std::vector<MSLane::IncomingLaneInfo>::iterator i = toExamine.begin(); i != toExamine.end(); ++i) {
1032 MSLane* next = (*i).lane;
1038 result =
MAX2(result, missingRearGap);
1040 if ((*i).length < dist) {
1041 const std::vector<MSLane::IncomingLaneInfo>& followers = next->
getIncomingLanes();
1042 for (std::vector<MSLane::IncomingLaneInfo>::const_iterator j = followers.begin(); j != followers.end(); ++j) {
1043 if (visited.find((*j).lane) == visited.end()) {
1044 visited.insert((*j).lane);
1046 ili.
lane = (*j).lane;
1047 ili.
length = (*j).length + (*i).length;
1049 newFound.push_back(ili);
1056 swap(newFound, toExamine);
1062 std::pair<MSVehicle* const, SUMOReal>
1067 std::set<MSLane*> visited;
1068 std::vector<std::pair<MSVehicle*, SUMOReal> > possible;
1069 std::vector<MSLane::IncomingLaneInfo> newFound;
1071 while (toExamine.size() != 0) {
1072 for (std::vector<MSLane::IncomingLaneInfo>::iterator i = toExamine.begin(); i != toExamine.end(); ++i) {
1078 MSLane* next = (*i).lane;
1083 possible.push_back(std::make_pair(v, agap));
1086 if ((*i).length + seen < dist) {
1087 const std::vector<MSLane::IncomingLaneInfo>& followers = next->
getIncomingLanes();
1088 for (std::vector<MSLane::IncomingLaneInfo>::const_iterator j = followers.begin(); j != followers.end(); ++j) {
1089 if (visited.find((*j).lane) == visited.end()) {
1090 visited.insert((*j).lane);
1092 ili.
lane = (*j).lane;
1093 ili.
length = (*j).length + (*i).length;
1095 newFound.push_back(ili);
1102 swap(newFound, toExamine);
1104 if (possible.size() == 0) {
1105 return std::pair<MSVehicle* const, SUMOReal>(
static_cast<MSVehicle*
>(0), -1);
1108 return *(possible.begin());
1112 std::pair<MSVehicle* const, SUMOReal>
1114 const std::vector<MSLane*>& bestLaneConts)
const {
1116 return std::pair<MSVehicle* const, SUMOReal>(
static_cast<MSVehicle*
>(0), -1);
1118 unsigned int view = 1;
1120 const MSLane* targetLane =
this;
1125 const MSLane* nextLane = targetLane;
1129 MSLinkCont::const_iterator link = targetLane->
succLinkSec(veh, view, *nextLane, bestLaneConts);
1134 #ifdef HAVE_INTERNAL_LANES
1137 if (linkLeaders.size() > 0) {
1140 return linkLeaders[0];
1142 bool nextInternal = (*link)->getViaLane() != 0;
1144 nextLane = (*link)->getViaLaneOrLane();
1145 if (nextLane == 0) {
1151 return std::pair<MSVehicle* const, SUMOReal>(leader, seen + leader->getPositionOnLane() - leader->getVehicleType().getLength() - veh.
getVehicleType().
getMinGap());
1162 #ifdef HAVE_INTERNAL_LANES
1163 if (!nextInternal) {
1169 }
while (seen <= dist);
1170 return std::pair<MSVehicle* const, SUMOReal>(
static_cast<MSVehicle*
>(0), -1);
1182 for (std::vector<MSEdge*>::iterator i = pred.begin(); i != pred.end();) {
1191 if (pred.size() != 0) {
1193 MSEdge* best = *pred.begin();
1234 for (VehCont::const_iterator i = vehs.begin(); i != vehs.end(); ++i) {
1235 v += (*i)->getSpeed();
1247 for (MSLane::VehCont::const_iterator i = vehs.begin(); i != vehs.end(); ++i) {
1248 ret += (*i)->getHBEFA_CO2Emissions();
1259 for (MSLane::VehCont::const_iterator i = vehs.begin(); i != vehs.end(); ++i) {
1260 ret += (*i)->getHBEFA_COEmissions();
1271 for (MSLane::VehCont::const_iterator i = vehs.begin(); i != vehs.end(); ++i) {
1272 ret += (*i)->getHBEFA_PMxEmissions();
1283 for (MSLane::VehCont::const_iterator i = vehs.begin(); i != vehs.end(); ++i) {
1284 ret += (*i)->getHBEFA_NOxEmissions();
1295 for (MSLane::VehCont::const_iterator i = vehs.begin(); i != vehs.end(); ++i) {
1296 ret += (*i)->getHBEFA_HCEmissions();
1307 for (MSLane::VehCont::const_iterator i = vehs.begin(); i != vehs.end(); ++i) {
1308 ret += (*i)->getHBEFA_FuelConsumption();
1319 if (vehs.size() == 0) {
1323 for (MSLane::VehCont::const_iterator i = vehs.begin(); i != vehs.end(); ++i) {
1324 SUMOReal sv = (*i)->getHarmonoise_NoiseEmissions();
1325 ret += (
SUMOReal) pow(10., (sv / 10.));
1345 myLaneDir(e->getLanes()[0]->
getShape().getBegLine().atan2PositiveAngle())
1354 if (ae1 != 0 && ae1->size() != 0) {
1358 if (ae2 != 0 && ae2->size() != 0) {
1377 for (std::vector<std::string>::const_iterator it = vehIds.begin(); it != vehIds.end(); ++it) {
void forceVehicleInsertion(MSVehicle *veh, SUMOReal pos)
Inserts the given vehicle at the given position.
void loadState(std::vector< std::string > &vehIDs, MSVehicleControl &vc)
Loads the state of this segment with the given parameters.
virtual const std::vector< LaneQ > & getBestLanes(bool forceRebuild=false, MSLane *startLane=0) const
Returns the description of best lanes to use in order to continue the route.
OutputDevice & writeAttr(const SumoXMLAttr attr, const T &val)
writes a named attribute
VehCont myVehicles
The lane's vehicles. The entering vehicles are inserted at the front of this container and the leavin...
MSEdge & getEdge() const
Returns the lane's edge.
Representation of a vehicle in the micro simulation.
bool isLinkEnd(MSLinkCont::const_iterator &i) const
SUMOVehicleClass getVehicleClass() const
Get this vehicle type's vehicle class.
void descheduleDeparture(SUMOVehicle *veh)
stops trying to emit the given vehicle
static void insertIDs(std::vector< std::string > &into)
SUMOReal getImpatience() const
Returns this vehicles impatience.
virtual void releaseVehicles() const
Allows to use the container for microsimulation again.
const MSCFModel & getCarFollowModel() const
Returns the vehicle's car following model definition.
int operator()(MSVehicle *v1, MSVehicle *v2) const
Comparing operator.
bool isChangingLanes() const
return true if the vehicle currently performs a lane change maneuver
void endLaneChangeManeuver()
SUMOReal getMaxSpeed() const
Returns the maximum speed.
virtual const MSEdge * succEdge(unsigned int nSuccs) const =0
Returns the nSuccs'th successor of edge the vehicle is currently at.
bool hasInfluencer() const
SUMOReal getLengthWithGap() const
Get vehicle's length including the minimum gap [m].
void registerTeleport()
register one non-collision-related teleport
static bool dictionary(std::string id, MSLane *lane)
Inserts a MSLane into the static dictionary Returns true if the key id isn't already in the dictionar...
MSEdgeVector::const_iterator MSRouteIterator
The vehicle arrived at a junction.
std::vector< std::pair< MSVehicle *, SUMOReal > > LinkLeaders
bool isVTDControlled() const
SUMOTime getWaitingTime() const
Returns the SUMOTime waited (speed was lesser than 0.1m/s)
virtual SUMOReal followSpeed(const MSVehicle *const veh, SUMOReal speed, SUMOReal gap2pred, SUMOReal predSpeed, SUMOReal predMaxDecel) const =0
Computes the vehicle's safe speed (no dawdling)
This is an uncontrolled, minor link, has to stop.
const MSEdge * getLastEdge() const
returns the destination edge
SUMOReal getLength() const
Returns the lane's length.
SUMOReal departSpeed
(optional) The initial speed of the vehicle
virtual SUMOReal maxNextSpeed(SUMOReal speed, const MSVehicle *const veh) const
Returns the maximum speed given the current speed.
bool hasArrived() const
Returns whether this vehicle has already arived (reached the arrivalPosition on its final edge) ...
std::vector< IncomingLaneInfo > myIncomingLanes
The car-following model abstraction.
void addLink(MSLink *link)
Delayed initialization.
virtual MSLinkCont::const_iterator succLinkSec(const SUMOVehicle &veh, unsigned int nRouteSuccs, const MSLane &succLinkSource, const std::vector< MSLane * > &conts) const
virtual bool integrateNewVehicle(SUMOTime t)
Insert buffered vehicle into the real lane.
SUMOReal arrivalSpeed
(optional) The final speed of the vehicle (not used yet)
std::vector< MSVehicle * > VehCont
Container for vehicles.
Notification
Definition of a vehicle state.
static SUMOReal rand()
Returns a random real number in [0, 1)
std::string time2string(SUMOTime t)
SUMOReal getLength() const
Get vehicle's length [m].
virtual void incorporateVehicle(MSVehicle *veh, SUMOReal pos, SUMOReal speed, const MSLane::VehCont::iterator &at, MSMoveReminder::Notification notification=MSMoveReminder::NOTIFICATION_DEPARTED)
Inserts the vehicle into this lane, and informs it about entering the network.
MSLane(const std::string &id, SUMOReal maxSpeed, SUMOReal length, MSEdge *const edge, unsigned int numericalID, const PositionVector &shape, SUMOReal width, SVCPermissions permissions)
Constructor.
void addIncomingLane(MSLane *lane, MSLink *viaLink)
static MSNet * getInstance()
Returns the pointer to the unique instance of MSNet (singleton).
const MSRoute & getRoute() const
Returns the current route.
by_connections_to_sorter(const MSEdge *const e)
constructor
The speed is chosen randomly.
virtual void addMoveReminder(MSMoveReminder *rem)
Add a move-reminder to move-reminder container.
The vehicle got vaporized.
void leftByLaneChange(MSVehicle *v)
SUMOReal getSecureGap(const SUMOReal speed, const SUMOReal leaderSpeed, const SUMOReal leaderMaxDecel) const
Returns the minimum gap to reserve if the leader is braking at maximum.
This is an uncontrolled, right-before-left link.
bool executeMove()
Executes planned vehicle movements with regards to right-of-way.
ArrivalSpeedDefinition arrivalSpeedProcedure
Information how the vehicle's end speed shall be chosen.
SUMOReal getPositionOnLane() const
Get the vehicle's position along the lane.
int operator()(const MSEdge *const e1, const MSEdge *const e2) const
comparing operator
void gotActive(MSLane *l)
Informs the control that the given lane got active.
bool pWagGenericInsertion(MSVehicle &veh, SUMOReal speed, SUMOReal maxPos, SUMOReal minPos)
SUMOTime getCurrentTimeStep() const
Returns the current simulation step (in s)
bool freeInsertion(MSVehicle &veh, SUMOReal speed, MSMoveReminder::Notification notification=MSMoveReminder::NOTIFICATION_DEPARTED)
Tries to insert the given vehicle on any place.
The position is chosen randomly.
This is an uncontrolled, all-way stop link.
SUMOReal myMaxSpeed
Lane-wide speedlimit [m/s].
Generic max-flow insertion by P.Wagner.
SUMOReal setPartialOccupation(MSVehicle *v, SUMOReal leftVehicleLength)
Sets the information about a vehicle lapping into this lane.
#define WRITE_WARNING(msg)
A gap is chosen where the maximum speed may be achieved.
MSAbstractLaneChangeModel & getLaneChangeModel()
virtual const VehCont & getVehiclesSecure() const
Returns the vehicles container; locks it for microsimulation.
SUMOReal getPartialOccupatorEnd() const
Returns the position of the in-lapping vehicle's end.
std::map< std::string, MSLane * > DictType
definition of the static dictionary type
virtual bool executeMovements(SUMOTime t, std::vector< MSLane * > &into)
Executes planned vehicle movements with regards to right-of-way.
static DictType myDict
Static dictionary to associate string-ids with objects.
void enterLaneAtInsertion(MSLane *enteredLane, SUMOReal pos, SUMOReal speed, MSMoveReminder::Notification notification)
Update when the vehicle enters a new lane in the emit step.
const std::string & getID() const
Returns the id.
A road/street connecting two junctions.
SUMOReal getHBEFA_HCEmissions() const
Returns the sum of last step HC emissions.
bool insertVehicle(MSVehicle &v)
Tries to insert the given vehicle.
virtual bool isInsertionSuccess(MSVehicle *vehicle, SUMOReal speed, SUMOReal pos, bool recheckNextLanes, MSMoveReminder::Notification notification=MSMoveReminder::NOTIFICATION_DEPARTED)
Tries to insert the given vehicle with the given state (speed and pos)
MSLane * getLogicalPredecessorLane() const
SUMOReal brakeGap(const SUMOReal speed) const
Returns the distance the vehicle needs to halt including driver's reaction time.
DepartSpeedDefinition departSpeedProcedure
Information how the vehicle's initial speed shall be chosen.
std::pair< MSVehicle *const, SUMOReal > getLeaderOnConsecutive(SUMOReal dist, SUMOReal seen, SUMOReal speed, const MSVehicle &veh, const std::vector< MSLane * > &bestLaneConts) const
Returns the leader and the distance to him.
void workOnMoveReminders(SUMOReal oldPos, SUMOReal newPos, SUMOReal newSpeed)
Processes active move reminder.
virtual MSVehicle * removeVehicle(MSVehicle *remVehicle, MSMoveReminder::Notification notification)
remove the vehicle from this lane
void resetPartialOccupation(MSVehicle *v)
Removes the information about a vehicle lapping into this lane.
void addVeh(const SUMOTime t, MSVehicle *veh)
Adds a vehicle to this transfer object.
Representation of a vehicle.
std::vector< MSVehicle * > myVehBuffer
DepartPosDefinition departPosProcedure
Information how the vehicle shall choose the departure position.
SUMOReal getMinGap() const
Get the free space in front of vehicles of this class.
This is an uncontrolled, minor link, has to brake.
bool alreadyMoved() const
reset the flag whether a vehicle already moved to false
Sorts vehicles by their position (descending)
const std::vector< MSLane * > & getBestLanesContinuation() const
Returns the subpart of best lanes that describes the vehicle's current lane and their successors...
std::pair< MSVehicle *const, SUMOReal > getFollowerOnConsecutive(SUMOReal dist, SUMOReal seen, SUMOReal leaderSpeed, SUMOReal backOffset, SUMOReal predMaxDecel) const
SUMOReal getHBEFA_COEmissions() const
Returns the sum of last step CO emissions.
void enteredByLaneChange(MSVehicle *v)
MSVehicleControl & getVehicleControl()
Returns the vehicle control.
MSLane * getParallelLane(int offset) const
Returns the lane with the given offset parallel to this one or 0 if it does not exist.
SUMOReal getMeanSpeed() const
Returns the mean speed on this lane.
static SUMOReal gap(SUMOReal predPos, SUMOReal predLength, SUMOReal pos)
Uses the given values to compute the brutto-gap.
SUMOReal getVehLenSum() const
Returns the sum of lengths of vehicles which were on the lane during the last step.
The vehicle arrived at its destination (is deleted)
bool isStopped() const
Returns whether the vehicle is at a stop.
std::pair< MSVehicle *, SUMOReal > getLastVehicleInformation() const
Returns the last vehicle which is still on the lane.
LinkState
The right-of-way state of a link between two lanes used when constructing a NBTrafficLightLogic, in MSLink and GNEInternalLane.
The maximum speed is used.
bool isVaporizing() const
Returns whether vehicles on this edge shall be vaporized.
virtual SUMOReal stopSpeed(const MSVehicle *const veh, const SUMOReal speed, SUMOReal gap2pred) const =0
Computes the vehicle's safe speed for approaching a non-moving obstacle (no dawdling) ...
SUMOReal getSpeedLimit() const
Returns the lane's maximum allowed speed.
MSEdge * myEdge
The lane's edge, for routing only.
No information given; use default.
void onRemovalFromNet(const MSMoveReminder::Notification reason)
Called when the vehicle is removed from the network.
MSLane * myLogicalPredecessorLane
Something on a lane to be noticed about vehicle movement.
SUMOReal getHBEFA_PMxEmissions() const
Returns the sum of last step PMx emissions.
SUMOReal myLength
Lane length [m].
SUMOReal getMaxDecel() const
Get the vehicle type's maximum deceleration [m/s^2].
virtual MSVehicle * getLastVehicle() const
returns the last vehicle
MSLane * getShadowLane() const
Returns the lane the vehicles shadow is on during continuouss lane change.
virtual void swapAfterLaneChange(SUMOTime t)
moves myTmpVehicles int myVehicles after a lane change procedure
std::string toString(const T &t, std::streamsize accuracy=OUTPUT_ACCURACY)
virtual const MSVehicle * getFirstVehicle() const
virtual SUMOReal getHeadwayTime() const
Get the driver's reaction time [s].
If a fixed number of random choices fails, a free position is chosen.
bool isParking() const
Returns whether the vehicle is parking.
std::map< MSEdge *, std::vector< MSLane * > > myApproachingLanes
Base class for objects which have an id.
std::vector< MSMoveReminder * > myMoveReminders
This lane's move reminder.
bool pWagSimpleInsertion(MSVehicle &veh, SUMOReal speed, SUMOReal maxPos, SUMOReal minPos)
static MSVehicleTransfer * getInstance()
Returns the instance of this object.
void leaveLane(const MSMoveReminder::Notification reason)
Update of members if vehicle leaves a new lane in the lane change step or at arrival.
const std::vector< MSLane * > * allowedLanes(const MSEdge &destination, SUMOVehicleClass vclass=SVC_UNKNOWN) const
Get the allowed lanes to reach the destination-edge.
static SUMOTime gTimeToGridlockHighways
EdgeBasicFunction getPurpose() const
Returns the edge type (EdgeBasicFunction)
const std::vector< MSEdge * > & getIncomingEdges() const
Returns the list of edges from which this edge may be reached.
Influencer & getInfluencer()
Returns the velocity/lane influencer.
void scheduleVehicleRemoval(SUMOVehicle *veh)
Removes a vehicle after it has ended.
Structure representing possible vehicle parameter.
virtual SUMOReal freeSpeed(const MSVehicle *const veh, SUMOReal speed, SUMOReal seen, SUMOReal maxSpeed) const
Computes the vehicle's safe speed without a leader.
bool operator()(const MSVehicle *cmp, SUMOReal pos) const
compares vehicle position to the detector position
MSVehicle * myInlappingVehicle
The vehicle which laps into this lane.
MSLane * parallelLane(const MSLane *const lane, int offset) const
Returns the lane with the given offset parallel to the given lane one or 0 if it does not exist...
MSInsertionControl & getInsertionControl()
Returns the insertion control.
The link has red light (must brake)
static SUMOReal getMinAngleDiff(SUMOReal angle1, SUMOReal angle2)
Returns the minimum distance (clockwise/counter-clockwise) between both angles.
SUMOReal myInlappingVehicleEnd
End position of a vehicle which laps into this lane.
const MSVehicleType & getVehicleType() const
Returns the vehicle's type definition.
bool maxSpeedGapInsertion(MSVehicle &veh, SUMOReal mspeed)
bool isApproachedFrom(MSEdge *const edge)
static SUMOReal sum(SUMOReal val)
Computes the resulting noise.
SUMOReal getSpeed() const
Returns the vehicle's current speed.
static SUMOTime gTimeToGridlock
const SUMOVehicleParameter & getParameter() const
Returns the vehicle's parameter (including departure definition)
SUMOReal departPos
(optional) The position the vehicle shall depart from
SUMOVehicle * getVehicle(const std::string &id) const
Returns the vehicle with the given id.
SUMOReal getMissingRearGap(SUMOReal dist, SUMOReal backOffset, SUMOReal leaderSpeed, SUMOReal leaderMaxDecel) const
return by how much further the leader must be inserted to avoid rear end collisions ...
SUMOReal getHBEFA_FuelConsumption() const
Returns the sum of last step fuel consumption.
SUMOReal getHBEFA_NOxEmissions() const
Returns the sum of last step NOx emissions.
void saveState(OutputDevice &out)
Saves the state of this lane into the given stream.
const PositionVector & getShape() const
Returns this lane's shape.
MSVehicle * getPartialOccupator() const
Returns the vehicle which laps into this lane.
Static storage of an output device and its base (abstract) implementation.
bool closeTag()
Closes the most recently opened tag.
SUMOReal getHBEFA_CO2Emissions() const
Returns the sum of last step CO2 emissions.
void registerCollision()
registers one collision-related teleport
MSEdgeControl & getEdgeControl()
Returns the edge control.
SUMOReal myVehicleLengthSum
The current length of all vehicles on this lane.
virtual ~MSLane()
Destructor.
int operator()(const std::pair< const MSVehicle *, SUMOReal > &p1, const std::pair< const MSVehicle *, SUMOReal > &p2) const
const MSLinkCont & getLinkCont() const
returns the container with all links !!!
No information given; use default.
A free position is chosen.
The class responsible for building and deletion of vehicles.
Simple max-flow insertion by P.Wagner.
SUMOReal getVehicleMaxSpeed(const SUMOVehicle *const veh) const
Returns the lane's maximum speed, given a vehicle's speed limit adaptation.
SUMOReal getHarmonoise_NoiseEmissions() const
Returns the sum of last step noise emissions.
MSLane * getLane() const
Returns the lane the vehicle is on.
const std::vector< IncomingLaneInfo > & getIncomingLanes() const
The edge is an internal edge.
Representation of a lane in the micro simulation.
void addApproachingLane(MSLane *lane)
OutputDevice & openTag(const std::string &xmlElement)
Opens an XML tag.
MSRouteIterator begin() const
Returns the begin of the list of edges to pass.
virtual bool appropriate(const MSVehicle *veh)
The vehicle is being teleported.
virtual void planMovements(const SUMOTime t)
Compute safe velocities for all vehicles based on positions and speeds from the last time step...
const std::string & getID() const
Returns the name of the vehicle.
virtual const MSVehicleType & getVehicleType() const =0
Returns the vehicle's type.
SUMOReal getOccupancy() const
Returns the occupancy of this lane during the last step.
virtual void detectCollisions(SUMOTime timestep, int stage)
Check if vehicles are too close.