Eclipse SUMO - Simulation of Urban MObility
AccessEdge< E, L, N, V > Class Template Reference

the access edge connecting different modes that is given to the internal router (SUMOAbstractRouter) More...

#include <AccessEdge.h>

Inheritance diagram for AccessEdge< E, L, N, V >:
[legend]
Collaboration diagram for AccessEdge< E, L, N, V >:
[legend]

Public Member Functions

 AccessEdge (int numericalID, const _IntermodalEdge *inEdge, const _IntermodalEdge *outEdge, const double length, SVCPermissions modeRestriction=SVC_IGNORING, SVCPermissions vehicleRestriction=SVC_IGNORING, double traveltime=-1)
 
 AccessEdge (int numericalID, const std::string &id, const E *edge, const double length=0, SVCPermissions modeRestriction=SVC_IGNORING, SVCPermissions vehicleRestriction=SVC_IGNORING)
 
void addSuccessor (IntermodalEdge *const s, IntermodalEdge *const via=nullptr)
 
void addTo (const StoringVisitor &cont) const
 Adds this object to the given container. More...
 
IntermodalEdgegetBidiEdge () const
 only used by mono-modal routing More...
 
double getDistanceTo (const IntermodalEdge *other) const
 
const E * getEdge () const
 
virtual double getEffort (const IntermodalTrip< E, N, V > *const, double) const
 
virtual double getEndPos () const
 
const std::string & getID () const
 Returns the id. More...
 
virtual double getIntended (const double, std::string &) const
 get intended vehicle id and departure time of next public transport ride More...
 
double getLength () const
 required by DijkstraRouter et al for external effort computation More...
 
double getLengthGeometryFactor () const
 
const std::string & getLine () const
 
double getMinimumTravelTime (const IntermodalTrip< E, N, V > *const trip) const
 
int getNumericalID () const
 
virtual double getPartialLength (const IntermodalTrip< E, N, V > *const) const
 
double getSpeedLimit () const
 
virtual double getStartPos () const
 
virtual const std::vector< IntermodalEdge * > & getSuccessors (SUMOVehicleClass vClass=SVC_IGNORING) const
 
double getTravelTime (const IntermodalTrip< E, N, V > *const trip, double) const
 
virtual double getTravelTimeAggregated (const IntermodalTrip< E, N, V > *const trip, double time) const
 
virtual const std::vector< std::pair< const IntermodalEdge *, const IntermodalEdge * > > & getViaSuccessors (SUMOVehicleClass vClass=SVC_IGNORING, bool ignoreTransientPermissions=false) const
 
virtual bool hasEffort () const
 
virtual bool includeInRoute (bool) const
 
bool isInternal () const
 
bool prohibits (const IntermodalTrip< E, N, V > *const trip) const
 
bool removeSuccessor (const IntermodalEdge *const edge)
 
virtual bool restricts (const IntermodalTrip< E, N, V > *const) const
 
virtual void setID (const std::string &newID)
 resets the id More...
 
void setLength (const double length)
 
void transferSuccessors (IntermodalEdge *to)
 

Static Public Member Functions

static double getEffortStatic (const IntermodalEdge *const edge, const IntermodalTrip< E, N, V > *const trip, double time)
 
template<class T >
static std::string getIDSecure (const T *obj, const std::string &fallBack="NULL")
 get an identifier for Named-like object which may be Null More...
 
static double getTravelTimeAggregated (const IntermodalEdge *const edge, const IntermodalTrip< E, N, V > *const trip, double time)
 
static double getTravelTimeStatic (const IntermodalEdge *const edge, const IntermodalTrip< E, N, V > *const trip, double time)
 
static double getTravelTimeStaticRandomized (const IntermodalEdge *const edge, const IntermodalTrip< E, N, V > *const trip, double time)
 

Protected Attributes

std::vector< IntermodalEdge * > myFollowingEdges
 List of edges that may be approached from this edge. More...
 
std::vector< std::pair< const IntermodalEdge *, const IntermodalEdge * > > myFollowingViaEdges
 List of edges that may be approached from this edge with optional internal vias. More...
 
std::string myID
 The name of the object. More...
 

Private Types

typedef IntermodalEdge< E, L, N, V > _IntermodalEdge
 

Private Attributes

const E *const myEdge
 the original edge More...
 
ValueTimeLine< double > * myEfforts
 Container for passing effort varying over time for the edge. More...
 
double myLength
 adaptable length (for splitted edges) More...
 
const std::string myLine
 public transport line or ped vs car More...
 
const SVCPermissions myModeRestrictions
 only allow using this edge if the modeSet matches (i.e. entering a taxi) More...
 
const int myNumericalID
 the index in myEdges More...
 
const double myTraveltime
 travel time (alternative to length) More...
 
const SVCPermissions myVehicleRestriction
 only allow using this edge if the vehicle class matches (i.e. exiting a taxi) More...
 

Detailed Description

template<class E, class L, class N, class V>
class AccessEdge< E, L, N, V >

the access edge connecting different modes that is given to the internal router (SUMOAbstractRouter)

Definition at line 31 of file AccessEdge.h.

Member Typedef Documentation

◆ _IntermodalEdge

template<class E , class L , class N , class V >
typedef IntermodalEdge<E, L, N, V> AccessEdge< E, L, N, V >::_IntermodalEdge
private

Definition at line 33 of file AccessEdge.h.

Constructor & Destructor Documentation

◆ AccessEdge() [1/2]

template<class E , class L , class N , class V >
AccessEdge< E, L, N, V >::AccessEdge ( int  numericalID,
const _IntermodalEdge inEdge,
const _IntermodalEdge outEdge,
const double  length,
SVCPermissions  modeRestriction = SVC_IGNORING,
SVCPermissions  vehicleRestriction = SVC_IGNORING,
double  traveltime = -1 
)
inline

Definition at line 36 of file AccessEdge.h.

◆ AccessEdge() [2/2]

template<class E , class L , class N , class V >
AccessEdge< E, L, N, V >::AccessEdge ( int  numericalID,
const std::string &  id,
const E *  edge,
const double  length = 0,
SVCPermissions  modeRestriction = SVC_IGNORING,
SVCPermissions  vehicleRestriction = SVC_IGNORING 
)
inline

Definition at line 47 of file AccessEdge.h.

Member Function Documentation

◆ addSuccessor()

template<class E , class L , class N , class V >
void IntermodalEdge< E, L, N, V >::addSuccessor ( IntermodalEdge< E, L, N, V > *const  s,
IntermodalEdge< E, L, N, V > *const  via = nullptr 
)
inlineinherited

◆ addTo()

void Named::addTo ( const StoringVisitor cont) const
inlineinherited

Adds this object to the given container.

Parameters
[in,filled]cont The container to add this item to

Definition at line 118 of file Named.h.

References Named::StoringVisitor::add().

◆ getBidiEdge()

template<class E , class L , class N , class V >
IntermodalEdge* IntermodalEdge< E, L, N, V >::getBidiEdge ( ) const
inlineinherited

only used by mono-modal routing

Definition at line 240 of file IntermodalEdge.h.

◆ getDistanceTo()

template<class E , class L , class N , class V >
double IntermodalEdge< E, L, N, V >::getDistanceTo ( const IntermodalEdge< E, L, N, V > *  other) const
inlineinherited

Definition at line 230 of file IntermodalEdge.h.

References IntermodalEdge< E, L, N, V >::myEdge.

◆ getEdge()

◆ getEffort()

template<class E , class L , class N , class V >
virtual double IntermodalEdge< E, L, N, V >::getEffort ( const IntermodalTrip< E, N, V > * const  ,
double   
) const
inlinevirtualinherited

Definition at line 185 of file IntermodalEdge.h.

Referenced by IntermodalEdge< E, L, N, V >::getEffortStatic().

Here is the caller graph for this function:

◆ getEffortStatic()

template<class E , class L , class N , class V >
static double IntermodalEdge< E, L, N, V >::getEffortStatic ( const IntermodalEdge< E, L, N, V > *const  edge,
const IntermodalTrip< E, N, V > *const  trip,
double  time 
)
inlinestaticinherited

Definition at line 189 of file IntermodalEdge.h.

References IntermodalEdge< E, L, N, V >::getEffort(), and IntermodalEdge< E, L, N, V >::hasEffort().

Referenced by IntermodalRouter< E, L, N, V >::createNet().

Here is the caller graph for this function:

◆ getEndPos()

template<class E , class L , class N , class V >
virtual double IntermodalEdge< E, L, N, V >::getEndPos ( ) const
inlinevirtualinherited

◆ getID()

const std::string& Named::getID ( ) const
inlineinherited

Returns the id.

Returns
The stored id

Definition at line 74 of file Named.h.

References Named::myID.

Referenced by MSLCM_LC2013::_patchSpeed(), MSLCM_SL2015::_patchSpeed(), MSCFModel_EIDM::_v(), MSCFModel_ACC::_v(), MSCFModel_IDM::_v(), MSCFModel_CACC::_v(), MSCFModel_Wiedemann::_v(), MSLCM_LC2013::_wantsChange(), MSLCM_SL2015::_wantsChangeSublane(), MSTransportableControl::abortAnyWaitingForVehicle(), MSLaneChangerSublane::abortLCManeuver(), MSTransportable::abortStage(), MSLCM_LC2013::adaptSpeedToPedestrians(), MSVehicle::adaptToJunctionLeader(), MSVehicle::adaptToLeader(), MSVehicle::adaptToLeaderDistance(), MSVehicle::adaptToLeaders(), MSVehicle::adaptToOncomingLeader(), MSVehicleTransfer::add(), MSPModel_JuPedSim::add(), MSPModel_Striping::add(), PCPolyContainer::add(), ShapeContainer::add(), MSDetectorControl::add(), NLTriggerBuilder::addAccess(), RORouteDef::addAlternative(), MSLane::addApproachingLane(), MSTractionSubstation::addChargeValueForOutput(), MSChargingStation::addChargeValueForOutput(), MSOverheadWire::addChargeValueForOutput(), NBNodeCont::addCluster2Join(), NLHandler::addConflict(), NLHandler::addConnection(), NBLoadedSUMOTLDef::addConnection(), MSPModel_Striping::addCrossingVehs(), RODFDetectorCon::addDetector(), NIXMLEdgesHandler::addEdge(), RONet::addEdge(), ROJTREdge::addFollowerProbability(), MSLane::addLeaders(), MSTLLogicControl::TLSLogicVariants::addLogic(), RONet::addNode(), MSLaneChangerSublane::addOutsideLeaders(), MSTractionSubstation::addOverheadWireClampToCircuit(), MSTractionSubstation::addOverheadWireInnerSegmentToCircuit(), MSTractionSubstation::addOverheadWireSegmentToCircuit(), NIImporter_SUMO::addPhase(), GUIEdge::addRerouter(), MSDevice_Taxi::addReservation(), MSDispatch::addReservation(), MSRouteHandler::addRideOrTransport(), RONet::addRouteDef(), NIXMLEdgesHandler::addSplit(), NBTrafficLightLogic::addStep(), MSRouteHandler::addStop(), RORouteHandler::addStop(), ROVehicle::addStop(), MSBaseVehicle::addStop(), MSNet::addStoppingPlace(), MSRouteHandler::addTranship(), MSVehicle::addTransportable(), AGActivityTripWriter::addTrip(), MSPModel_JuPedSim::addWaitingSet(), NIXMLConnectionsHandler::addWalkingArea(), MSBaseVehicle::allowsBoarding(), MSTransportable::appendStage(), LIBSUMO_NAMESPACE::Person::appendWalkingStage(), MSCFModel::applyHeadwayAndSpeedDifferencePerceptionErrors(), MSCFModel::applyHeadwayPerceptionError(), libsumo::Helper::applySubscriptionFilterLanes(), libsumo::Helper::applySubscriptionFilterLateralDistance(), libsumo::Helper::applySubscriptionFilterLateralDistanceSinglePass(), libsumo::Helper::applySubscriptionFilters(), libsumo::Helper::applySubscriptionFilterTurn(), MSLaneChanger::avoidDeadlock(), MSDevice_ToC::awarenessRecoveryStep(), GUITrafficLightLogicWrapper::begin2TrackPhases(), MSPModel_Interacting::blockedAtDist(), MSLink::blockedAtTime(), MSLink::blockedByFoe(), MSVehicle::boardTransportables(), MSVehicle::brakeForOverlap(), NIVisumTL::build(), LIBSUMO_NAMESPACE::TrafficLight::buildConstraint(), MSSOTLE2Sensors::buildContinueSensior(), MSSOTLE2Sensors::buildCountSensorForLane(), MSSOTLE2Sensors::buildCountSensorForOutLane(), NBNode::buildCrossings(), NBNode::buildCrossingsAndWalkingAreas(), MSTransportableDevice_Routing::buildDevices(), MSTransportableDevice_BTreceiver::buildDevices(), MSTransportableDevice_BTsender::buildDevices(), MSTransportableDevice_FCD::buildDevices(), MSTransportableDevice_FCDReplay::buildDevices(), NIImporter_VISUM::buildDistrictNode(), MSRailSignal::LinkInfo::buildDriveWay(), NLDetectorBuilder::buildE2Detector(), RODFNet::buildEdgeFlowMap(), NLDetectorBuilder::buildInductLoop(), NBEdge::buildInnerEdges(), NLTriggerBuilder::buildInnerOverheadWireSegments(), GNETLSEditorFrame::buildInternalLanes(), NIVissimEdge::buildNBEdge(), NGEdge::buildNBEdge(), NBOwnTLDef::buildNemaPhases(), NBRampsComputer::buildOffRamp(), NBRampsComputer::buildOnRamp(), MSPModel_JuPedSim::buildPedestrianNetwork(), MSRailSignal::DriveWay::buildRoute(), MELoop::buildSegmentsFor(), MSSOTLE2Sensors::buildSensorForLane(), MSSOTLE2Sensors::buildSensorForOutLane(), libsumo::Helper::buildStopParameters(), MSDevice_Bluelight::buildVehicleDevices(), MSVehicleDevice_BTreceiver::buildVehicleDevices(), MSVehicleDevice_BTsender::buildVehicleDevices(), MSDevice_DriverState::buildVehicleDevices(), MSDevice_ElecHybrid::buildVehicleDevices(), MSDevice_Example::buildVehicleDevices(), MSDevice_FCD::buildVehicleDevices(), MSDevice_FCDReplay::buildVehicleDevices(), MSDevice_Friction::buildVehicleDevices(), MSDevice_GLOSA::buildVehicleDevices(), MSDevice_Routing::buildVehicleDevices(), MSDevice_SSM::buildVehicleDevices(), MSDevice_Taxi::buildVehicleDevices(), MSDevice_ToC::buildVehicleDevices(), MSDevice_Tripinfo::buildVehicleDevices(), MSDevice_Transportable::buildVehicleDevices(), MSDevice_Vehroutes::buildVehicleDevices(), MSDevice_Battery::buildVehicleDevices(), NBNode::buildWalkingAreas(), MSBaseVehicle::calculateArrivalParams(), MSSwarmTrafficLightLogic::calculateEtaDiff(), MSSwarmTrafficLightLogic::calculateEtaRatio(), NEMALogic::calculateInitialPhases170(), MSE2Collector::calculateTimeLossAndTimeOnDetector(), MSDevice_Taxi::cancelCurrentCustomers(), MSDevice_Taxi::cancelCustomer(), MSStageDriving::canLeaveVehicle(), MSSOTLPolicyBasedTrafficLightLogic::canRelease(), MSLCHelper::canSaveBlockerLength(), MSLaneChanger::change(), MSLaneChangerSublane::change(), MSLCM_SL2015::changed(), MSLaneChanger::changeOpposite(), MELoop::changeSegment(), MSActuatedTrafficLightLogic::changeStepAndDuration(), MSSimpleTrafficLightLogic::changeStepAndDuration(), LIBSUMO_NAMESPACE::Vehicle::changeTarget(), MSCFModel_CC::changeWholePlatoonLane(), MSTLLogicControl::check2Switch(), MSEdge::checkAndRegisterBiDirEdge(), MSLaneChanger::checkChange(), MSLaneChanger::checkChangeOpposite(), MSLaneChangerSublane::checkChangeOpposite(), MSLaneChangerSublane::checkChangeSublane(), NBEdgeCont::checkConsistency(), MSRailSignal::DriveWay::checkCrossingFlanks(), MSDevice_ToC::checkDynamicToC(), MSLane::checkFailure(), MSRailSignal::DriveWay::checkFlanks(), MSLane::checkForPedestrians(), MSVehicleTransfer::checkInsertions(), MSVehicle::checkLinkLeader(), MSE2Collector::checkPositioning(), MSRoute::checkRemoval(), MSVehicle::checkReversal(), MSVehicle::checkRewindLinkLanes(), MEVehicle::checkStop(), MSLCM_SL2015::checkStrategicChange(), MSAbstractLaneChangeModel::checkTraCICommands(), MSLaneChanger::checkTraCICommands(), MSLink::checkWalkingAreaFoe(), MSSwarmTrafficLightLogic::choosePolicy(), MSDevice_SSM::classifyEncounter(), ShapeContainer::clearHighlights(), NBTrafficLightLogic::closeBuilding(), ODDistrictHandler::closeDistrict(), NLHandler::closeEdge(), MSDevice_SSM::closeEncounter(), RORouteHandler::closeRouteDistribution(), MSRouteHandler::closeVehicle(), RORouteHandler::closeVehicle(), NBTrafficLightDefinition::collectAllLinks(), NBTrafficLightDefinition::collectEdges(), NBLoadedSUMOTLDef::collectEdgeVectors(), NBLoadedTLDef::collectLinks(), MSLCM_SL2015::commitManoeuvre(), IntermodalRouter< E, L, N, V >::compute(), NBTrafficLightDefinition::compute(), ROJTRRouter::compute(), MSVehicle::computeAngle(), MSDispatch::computeDetourTime(), NBNodeShapeComputer::computeEdgeBoundaries(), MSVehicle::computeFurtherLanes(), MSDevice_SSM::computeGlobalMeasures(), NBNode::computeInternalLaneShape(), NBNode::computeLanes2Lanes(), NBNode::computeLogic(), NBOwnTLDef::computeLogicAndConts(), NBNodeShapeComputer::computeNodeShapeDefault(), NBNodeShapeComputer::computeNodeShapeSmall(), NBNodeTypeComputer::computeNodeTypes(), NBRampsComputer::computeRamps(), RODFNet::computeRoutesFor(), MSLaneChanger::computeSafeOppositeLength(), NBTrafficLightLogicCont::computeSingleLogic(), NBNode::computeSmoothShape(), MSLCM_LC2013::computeSpeedLat(), MSLCM_SL2015::computeSpeedLat(), MSDevice_SSM::computeSSMs(), MSLaneChanger::computeSurplusGap(), NBTurningDirectionsComputer::computeTurnDirectionsForNode(), MSVehicle::Manoeuvre::configureEntryManoeuvre(), MSVehicle::Manoeuvre::configureExitManoeuvre(), MSRailSignal::DriveWay::conflictLaneOccupied(), NGNet::connect(), MSRailSignal::constraintsAllow(), NEMALogic::constructTimingAndPhaseDefs(), MSLaneChanger::continueChange(), MSLaneChangerSublane::continueChangeSublane(), libsumo::Helper::convertCartesianToRoadMap(), LIBSUMO_NAMESPACE::Person::convertTraCIStage(), NBLoadedSUMOTLDef::copyIndices(), NBOwnTLDef::correctConflicting(), NBOwnTLDef::corridorLike(), MSSOTLWaveTrafficLightLogic::countVehicles(), MSSOTLE2Sensors::countVehicles(), MSDevice_SSM::createEncounters(), GNETLSEditorFrame::TLSDefinition::createTLS(), GUINet::createTLWrapper(), MSDevice_Taxi::customerArrived(), NBNodeCont::customTLID(), MSDevice_ToC::deactivateDeliberateLCs(), MSRailSignal::DriveWay::deadlockLaneOccupied(), libsumo::Helper::debugPrint(), MSLCM_SL2015::decideDirection(), MSActuatedTrafficLightLogic::decideNextPhase(), MSDeterministicHiLevelTrafficLightLogic::decideNextPhase(), MSSOTLPolicyBasedTrafficLightLogic::decideNextPhase(), MSSwarmTrafficLightLogic::decideNextPhase(), MSDeterministicHiLevelTrafficLightLogic::decidePolicy(), MSSwarmTrafficLightLogic::decidePolicy(), MSVehicleControl::deleteVehicle(), MSDevice_ElecHybrid::deleteVehicleFromCircuit(), MSLane::detectCollisionBetween(), MSLane::detectCollisions(), MSE3Collector::detectorUpdate(), MSLane::detectPedestrianJunctionCollision(), NIVissimDistrictConnection::dict_BuildDistrictNodes(), NIVissimDistrictConnection::dict_BuildDistricts(), MSEdge::dictionaryHint(), NBNodeCont::discardTrafficLights(), MSDispatch_Greedy::dispatch(), MSDispatch_GreedyShared::dispatch(), MSDispatch_RouteExtension::dispatch(), MSDevice_Taxi::dispatchShared(), GUILane::drawGL(), MSDevice_SSM::Encounter::Encounter(), MSAbstractLaneChangeModel::endLaneChangeManeuver(), MSE3Collector::enter(), NEMAPhase::enter(), MSParkingArea::enter(), MSVehicle::enterLaneAtLaneChange(), MSVehicle::enterLaneAtMove(), MSVehicle::Manoeuvre::entryManoeuvreIsComplete(), MSTransportableControl::erase(), NEMALogic::error_handle_not_set(), MSStoppingPlaceRerouter::evaluateDestination(), METriggeredCalibrator::execute(), Command_SaveTLSProgram::execute(), Command_SaveTLSState::execute(), Command_SaveTLSSwitches::execute(), Command_SaveTLSSwitchStates::execute(), Command_RouteReplacement::execute(), MSDevice_BTreceiver::BTreceiverUpdate::execute(), MSVTypeProbe::execute(), MSPModel_Striping::MovePedestrians::execute(), MSCalibrator::execute(), MSPModel_JuPedSim::execute(), MSVehicle::executeFractionalMove(), MSVehicle::executeMove(), MSLane::executeMovements(), NBNodeCont::extract(), NBTrafficLightLogicCont::extract(), MSDevice_SSM::filterByConflictType(), LIBSUMO_NAMESPACE::Person::filterReservation(), NBLoadedSUMOTLDef::finalChecks(), MSCFModel::finalizeSpeed(), MSCFModel_Daniel1::finalizeSpeed(), MSCFModel_EIDM::finalizeSpeed(), MSLaneChanger::findCandidate(), LIBSUMO_NAMESPACE::TrafficLight::findConstraintsDeadLocks(), MSRailSignal::DriveWay::findFlankProtection(), MSDevice_SSM::findFoeConflictLane(), LIBSUMO_NAMESPACE::Simulation::findIntermodalRoute(), MSDevice_SSM::findSurroundingVehicles(), MSDevice_SSM::flushConflicts(), MSDevice_SSM::flushGlobalMeasures(), MSCFModel_CACC::followSpeed(), MSCFModel_EIDM::followSpeed(), MSCFModel_W99::followSpeed(), NBTrafficLightDefinition::forbids(), MSLaneChanger::foundHilltop(), MSCFModel_EIDM::freeSpeed(), NBNodeCont::generateNodeClusters(), MSDevice_Tripinfo::generateOutput(), MSDevice_StationFinder::generateOutput(), MSStopOut::generateOutputForUnfinished(), GUITrafficLightLogicWrapper::getActiveTLLogic(), RODFDetectorCon::getAggFlowFor(), RODFDetectorCon::getAnyDetectorForEdge(), MSPModel_Striping::getArbitraryPath(), MSVehicle::getBackPosition(), MSVehicle::getBackPositionOnLane(), LIBSUMO_NAMESPACE::Vehicle::getBestLanes(), MSLaneChanger::getBestLanesOpposite(), NBOwnTLDef::getBestPair(), LIBSUMO_NAMESPACE::Edge::getBidiEdge(), LIBSUMO_NAMESPACE::Lane::getBidiLane(), SUMOTrafficObject::getBoolParam(), NBRailwayTopologyAnalyzer::getBrokenRailNodes(), MSLane::getCanonicalPredecessorLane(), MSLane::getCanonicalSuccessorLane(), MSVehicle::getCenterOnEdge(), MSDevice_Battery::getChargingStationID(), MSRailSignal::getClickableTLLinkID(), LIBSUMO_NAMESPACE::Simulation::getCollisions(), GUIVehicle::getColorValue(), MSLaneChanger::getColumnleader(), MSActuatedTrafficLightLogic::getConditions(), LIBSUMO_NAMESPACE::TrafficLight::getConstraintsByFoe(), LIBSUMO_NAMESPACE::TrafficLight::getControlledLinks(), MSLane::getCriticalLeader(), MSCalibrator::getCurrentStateInterval(), NBNodeShapeComputer::getDefaultRadius(), MSLink::getDescription(), MSStop::getDescription(), NBTrafficLightDefinition::getDescription(), MSStageTrip::getDestinationDescription(), GUIPerson::getDestinationEdgeID(), GUIPerson::getDestinationStopID(), MSDevice_SSM::getDetectionRange(), RODFNet::getDetectorEdge(), MSActuatedTrafficLightLogic::getDetectorPriority(), MSRailSignal::LinkInfo::getDriveWay(), MSSimpleTrafficLightLogic::getEarliest(), GUIPerson::getEdgeID(), GUIMEVehicle::getEdgeID(), MSMeanData::getEdgeID(), LIBSUMO_NAMESPACE::RouteProbe::getEdgeID(), MSDevice_SSM::getExtraTime(), MSLane::getFirstVehicleInformation(), SUMOTrafficObject::getFloatParam(), MSBaseVehicle::getFlowID(), MSLane::getFollower(), MSLane::getFollowersOnConsecutive(), GUIPerson::getFromEdgeID(), MSPModel_InteractingState::getID(), NBEdge::getID(), LIBSUMO_NAMESPACE::Vehicle::getJunctionFoes(), MSRailSignal::getJunctionLinkID(), LIBSUMO_NAMESPACE::Calibrator::getLaneID(), NEMALogic::getLaneInfoFromNEMAState(), MSParkingArea::getLastFreePos(), MSParkingArea::getLastFreePosWithReservation(), MSLane::getLastVehicleInformation(), MSSimpleTrafficLightLogic::getLatest(), MSVehicle::getLatOffset(), MSLane::getLeader(), MSLink::getLeaderInfo(), MSLane::getLeaderOnConsecutive(), MSLaneChangerSublane::getLeaders(), MSLane::getLeadersOnConsecutive(), MSLink::getLengthBeforeCrossing(), MSDevice_BTsender::getLocation(), MSDevice_SSM::getMDRAC_PRT(), MSDeterministicHiLevelTrafficLightLogic::getMeanSpeedForInputLanes(), MSDeterministicHiLevelTrafficLightLogic::getMeanSpeedForOutputLanes(), MSDevice_SSM::getMeasuresAndThresholds(), NIImporter_VISUM::getNamedEdgeContinuating(), MSPModel_Striping::getNeighboringObstacles(), MSCalibrator::getNewVehicleID(), MSPerson::getNextEdge(), MSPModel_Striping::getNextLane(), MSPModel_Striping::getNextLaneObstacles(), LIBSUMO_NAMESPACE::Vehicle::getNextLinks(), MSLaneChanger::getOncomingOppositeVehicle(), MSLane::getOppositeFollower(), MSLane::getOppositeLeader(), MSStageTrip::getOriginDescription(), MSDevice_SSM::getOutputFilename(), MSDevice_ElecHybrid::getOverheadWireSegmentID(), MSOverheadWire::getOverheadWireSegmentName(), MSDevice_StationFinder::getParameter(), MSDevice_ToC::getParameter(), MSActuatedTrafficLightLogic::getParameter(), NEMALogic::getParameter(), LIBSUMO_NAMESPACE::Simulation::getParameter(), GUITrafficLightLogicWrapper::getParameterWindow(), GUIContainer::getParameterWindow(), GUILane::getParameterWindow(), GUILane::getParentName(), MSLane::getPartialBehind(), MSSimpleDriverState::getPerceivedHeadway(), MSSimpleDriverState::getPerceivedSpeedDifference(), MSSOTLTrafficLightLogic::getPhaseIndexWithMaxCTS(), MSSwarmTrafficLightLogic::getPheromoneForInputLanes(), MSSwarmTrafficLightLogic::getPheromoneForOutputLanes(), PolygonDynamics::getPolygonID(), GUITrafficLightLogicWrapper::getPopUpMenu(), NLTriggerBuilder::getPosition(), NLDetectorBuilder::getPositionChecking(), MSBaseVehicle::getPrefixedParameter(), MSCFModel_CC::getRadarMeasurements(), MSLaneChanger::getRealFollower(), MSLaneChanger::getRealLeader(), LIBSUMO_NAMESPACE::Vehicle::getRoadID(), MSLCHelper::getRoundaboutDistBonus(), LIBSUMO_NAMESPACE::Vehicle::getRouteID(), LIBSUMO_NAMESPACE::Calibrator::getRouteProbeID(), MSBaseVehicle::getRouteValidity(), GUIBaseVehicle::getScaleValue(), MSAbstractLaneChangeModel::getShadowLane(), MSBaseVehicle::getSingularType(), MSTransportable::getSingularType(), LIBSUMO_NAMESPACE::Person::getStage(), MSStageDriving::getStageSummary(), MSStageTranship::getStageSummary(), MSStageWaiting::getStageSummary(), MSStageWalking::getStageSummary(), MSDevice_Taxi::getStopLane(), MSNet::getStoppingPlaceID(), SUMOTrafficObject::getStringParam(), MSLane::getSurroundingVehicles(), MSActuatedTrafficLightLogic::getTarget(), LIBSUMO_NAMESPACE::Vehicle::getTeleportingIDList(), SUMOTrafficObject::getTimeParam(), MSRailSignal::getTLLinkID(), NIImporter_OpenDrive::getTLSSecure(), MSDevice_ElecHybrid::getTractionSubstationID(), PedestrianEdge< E, L, N, V >::getTravelTime(), MSVehicle::getUpcomingLanesUntil(), MSLane::getUpcomingLinks(), MSDevice_SSM::getUpstreamVehicles(), LIBSUMO_NAMESPACE::Person::getVehicle(), LIBSUMO_NAMESPACE::TrafficLight::getVehicleByTripId(), GUIPerson::getVehicleID(), MSPModel_Striping::getVehicleObstacles(), MSStageTrip::getVehicles(), MSDevice_SSM::getVehiclesOnJunction(), MSRailSignalConstraint::getVehID(), MSStageDriving::getWaitingDescription(), MSEdge::getWaitingVehicle(), MSStoppingPlaceRerouter::getWeight(), MSLink::getZipperSpeed(), GNEEdge::GNEEdge(), NBNode::guessCrossings(), RODFDetectorCon::guessEmptyFlows(), NBNodeCont::guessTLs(), GUITLLogicPhasesTrackerWindow::GUITLLogicPhasesTrackerWindow(), MSLane::handleCollisionBetween(), MSLane::handleIntermodalCollisionBetween(), MSRailSignal::hasInsertionConstraint(), MSRailSignal::hasOncomingRailTraffic(), MSBaseVehicle::hasValidRouteStart(), MSVehicle::hasValidRouteStart(), MSBaseVehicle::haveValidStopEdges(), LIBSUMO_NAMESPACE::POI::highlight(), LIBSUMO_NAMESPACE::Vehicle::highlight(), MSIdling_Stop::idle(), MSIdling_RandomCircling::idle(), MSIdling_TaxiStand::idle(), MSLink::ignoreFoe(), MSVehicle::ignoreFoe(), MSVehicle::ignoreRed(), MSVehicle::Influencer::implicitDeltaPosRemote(), NBNode::indirectLeftShape(), MSLCM_LC2013::inform(), MSLCM_SL2015::inform(), MSLCM_SL2015::informFollower(), MSLCM_LC2013::informFollower(), MSLCM_SL2015::informLeader(), MSLCM_LC2013::informLeader(), MSCalibrator::init(), NBEdge::init(), MSDeterministicHiLevelTrafficLightLogic::init(), MSSOTLTrafficLightLogic::init(), MSSwarmTrafficLightLogic::init(), MSTrafficLightLogic::init(), MSActuatedTrafficLightLogic::init(), MSDelayBasedTrafficLightLogic::init(), MSRailSignal::init(), NEMALogic::init(), MSActuatedTrafficLightLogic::initAttributeOverride(), MSE2Collector::initAuxiliaries(), MESegment::initialise(), MSPModel_JuPedSim::initialize(), MSTrafficLightLogic::initMesoTLSPenalties(), NBOwnTLDef::initNeedsContRelation(), PolygonDynamics::initTrackedPosition(), NIImporter_SUMO::initTrafficLightLogic(), NIXMLTrafficLightsHandler::initTrafficLightLogic(), NBDistrictCont::insert(), NBNodeCont::insert(), NBTrafficLightLogicCont::insert(), NIImporter_OpenStreetMap::insertEdge(), MSCFModel_IDM::insertionFollowSpeed(), MSBaseVehicle::insertStop(), MSLane::insertVehicle(), MSEdge::insertVehicle(), MSPModel_Striping::insertWalkArePaths(), MSLane::integrateNewVehicles(), IntermodalNetwork< E, L, N, V >::IntermodalNetwork(), GNEJunction::invalidateTLS(), NBNode::invalidateTLS(), MSTLLogicControl::isActive(), MSPedestrianPushButton::isActiveForEdge(), MSPedestrianPushButton::isActiveOnAnySideOfTheRoad(), RODFNet::isAllowed(), RODFNet::isDestination(), RODFNet::isFalseSource(), MSLane::isInsertionSuccess(), MSBaseVehicle::isJumping(), MSVehicle::isLeader(), MESegment::isOpen(), MSCFModel_CC::isPlatoonLaneChangeSafe(), RODFNet::isSource(), NIImporter_VISUM::isSplitEdge(), MSSOTLTrafficLightLogic::isThresholdPassed(), RORoute::isValid(), MSStageDriving::isWaitingFor(), MESegment::jamThresholdForSpeed(), NBNodeCont::joinNodeCluster(), NBNodeCont::joinSameJunctions(), MSVehicle::joinTrainPartFront(), MSAbstractLaneChangeModel::laneChangeOutput(), MSVehicle::lateralDistanceToLane(), MSE3Collector::leave(), MSE3Collector::leaveFront(), MSVehicle::leaveLane(), MSDevice_BTreceiver::BTreceiverUpdate::leaveRange(), MSPedestrianPushButton::loadCrossingEdgeMap(), MSStopOut::loadedContainers(), MSStopOut::loadedPersons(), NIImporter_OpenDrive::loadNetwork(), MSPedestrianPushButton::loadPushButtons(), MSVehicle::loadState(), MSVehicleTransfer::loadState(), MSActuatedTrafficLightLogic::loadState(), ODDistrictCont::makeDistricts(), MSE2Collector::makeMoveNotification(), MSE2Collector::makeVehicleInfo(), NWWriter_OpenDrive::mapmatchRoadObjects(), MEVehicle::mayProceed(), MSSOTLE2Sensors::meanVehiclesSpeed(), METriggeredCalibrator::METriggeredCalibrator(), MSDevice_FCDReplay::move(), MSTransportableDevice_FCDReplay::move(), MSPModel_Striping::moveInDirection(), MSPModel_Striping::moveInDirectionOnLane(), MSPModel_Striping::PState::moveTo(), MSPModel_Striping::PState::moveToNextLane(), LIBSUMO_NAMESPACE::Person::moveToXY(), LIBSUMO_NAMESPACE::Vehicle::moveToXY(), MSPModel_Striping::PState::moveToXY(), libsumo::Helper::moveToXYMap(), MSDevice_ToC::MRMExecutionStep(), MSChargingStation::MSChargingStation(), MSDevice_Battery::MSDevice_Battery(), MSDevice_ElecHybrid::MSDevice_ElecHybrid(), MSDevice_Taxi::MSDevice_Taxi(), MSDevice_ToC::MSDevice_ToC(), MSE2Collector::MSE2Collector(), MSLCM_LC2013::MSLCM_LC2013(), MSParkingArea::MSParkingArea(), MSSimpleDriverState::MSSimpleDriverState(), MSLCM_SL2015::mustOvertakeStopped(), NBLoadedTLDef::myCompute(), NIImporter_SUMO::myEndElement(), MSStateHandler::myStartElement(), MSCalibrator::myStartElement(), MSLaneSpeedTrigger::myStartElement(), MSTriggeredRerouter::myStartElement(), MSDevice_FCDReplay::FCDHandler::myStartElement(), MSPModel_Interacting::nextBlocking(), MSLane::AnyVehicleIterator::nextIsMyVehicles(), MSDevice_ElecHybrid::notifyEnter(), MSE2Collector::notifyEnter(), MSDevice_Bluelight::notifyEnter(), MSDevice_BTreceiver::notifyEnter(), MSDevice_BTsender::notifyEnter(), MSDevice_Example::notifyEnter(), MSDevice_GLOSA::notifyEnter(), MSDevice_SSM::notifyEnter(), MSDevice_Tripinfo::notifyEnter(), MSMeanData::MeanDataValues::notifyEnter(), MSMeanData::MeanDataValueTracker::notifyEnter(), MSMeanData_Net::MSLaneMeanDataValues::notifyEnter(), MSRailSignalConstraint_Predecessor::PassedTracker::notifyEnter(), MSCalibrator::VehicleRemover::notifyEnter(), MSE3Collector::MSE3EntryReminder::notifyEnter(), MSE3Collector::MSE3LeaveReminder::notifyEnter(), MSDevice_ElecHybrid::notifyLeave(), MSDevice_Bluelight::notifyLeave(), MSDevice_BTreceiver::notifyLeave(), MSDevice_BTsender::notifyLeave(), MSDevice_Example::notifyLeave(), MSDevice_SSM::notifyLeave(), MSDevice_Transportable::notifyLeave(), MSDevice_Tripinfo::notifyLeave(), MSE2Collector::notifyLeave(), MSE3Collector::MSE3EntryReminder::notifyLeave(), MSE3Collector::MSE3LeaveReminder::notifyLeave(), MSDevice_ElecHybrid::notifyMove(), MSDevice_Battery::notifyMove(), MSDevice_Bluelight::notifyMove(), MSDevice_BTreceiver::notifyMove(), MSDevice_BTsender::notifyMove(), MSDevice_Example::notifyMove(), MSDevice_GLOSA::notifyMove(), MSDevice_SSM::notifyMove(), MSE2Collector::notifyMove(), MSInductLoop::notifyMove(), MSMeanData::MeanDataValues::notifyMove(), MSDevice_StationFinder::notifyMove(), MSDevice_ToC::notifyMove(), MSE3Collector::MSE3LeaveReminder::notifyMove(), MSE3Collector::MSE3EntryReminder::notifyMove(), MSMeanData_Net::MSLaneMeanDataValues::notifyMoveInternal(), GNETLSEditorFrame::TLSDefinition::onCmdResetCurrentProgram(), MSVehicle::onRemovalFromNet(), MSLink::opened(), RORouteHandler::openRoute(), MSLane::incoming_lane_priority_sorter::operator()(), MSLane::outgoing_lane_priority_sorter::operator()(), MSEdge::transportable_by_position_sorter::operator()(), NBNetBuilder::by_id_sorter::operator()(), NBNode::nodes_by_id_sorter::operator()(), RODFNet::idComp::operator()(), MSLaneChangerSublane::outputLCStarted(), NIImporter_VISUM::parse_Connectors_legacy(), NIImporter_VISUM::parse_EdgePolys(), NIImporter_VISUM::parse_Lanes(), NIImporter_VISUM::parse_stopPoints(), NIImporter_VISUM::parse_Turns(), NLTriggerBuilder::parseAndBuildCalibrator(), NLTriggerBuilder::parseAndBuildOverheadWireSection(), MSRouteHandler::parseWalkPositions(), NBLoadedSUMOTLDef::patchIfCrossingsAdded(), MSLCM_LC2013::patchSpeed(), MSLCM_SL2015::patchSpeed(), MSRoutingEngine::patchSpeedForTurns(), NBLoadedTLDef::SignalGroup::patchTYellow(), MSCFModel_CC::performAutoLaneChange(), MSVehicle::planMove(), MSVehicle::planMoveInternal(), MSLane::planMovements(), PolygonDynamics::PolygonDynamics(), MSInternalJunction::postloadInit(), MSRightOfWayJunction::postloadInit(), MSVehicle::Influencer::postProcessRemoteControl(), MSLCM_SL2015::prepareStep(), MSDevice_Taxi::prepareStop(), MSLCM_SL2015::preventSliding(), MSAbstractLaneChangeModel::primaryLaneChanged(), AGStreet::print(), MSStageDriving::proceed(), MSDevice_SSM::processEncounters(), MSVehicle::processLaneAdvances(), MSVehicle::processLinkApproaches(), MSVehicle::processNextStop(), NIXMLNodesHandler::processNodeType(), TraCIServerAPI_Vehicle::processSet(), MSVehicle::processTraCISpeedControl(), NIXMLNodesHandler::processTrafficLightDefinitions(), MSDelayBasedTrafficLightLogic::proposeProlongation(), NBNodeCont::pruneClusterFringe(), NBNodeCont::pruneSlipLaneNodes(), MSPModel_Striping::PState::PState(), NBTrafficLightDefinition::railSignalUncontrolled(), MSDevice_Battery::readParameterValue(), MSOffTrafficLightLogic::rebuildPhase(), NBEdge::recheckLanes(), NBEdgeCont::recheckPostProcessConnections(), NIImporter_OpenStreetMap::reconstructLayerElevation(), NBLoadedSUMOTLDef::reconstructLogic(), NBEdge::reduceGeometry(), MSNet::registerCollision(), MSPModel_Striping::registerCrossingApproach(), MSRailSignalControl::registerProtectedDriveway(), MSLink::removeApproaching(), MSLink::removeApproachingPerson(), LIBSUMO_NAMESPACE::TrafficLight::removeConstraints(), MSVehicle::removePassedDriveItems(), MSCalibrator::removePending(), MSDispatch::removeReservation(), GNEJunction::removeTLSConnections(), NBNodeCont::rename(), NBTrafficLightLogicCont::rename(), RORouteDef::repairCurrentRoute(), GNEJunction::replaceIncomingConnections(), MSBaseVehicle::replaceParkingArea(), MSBaseVehicle::replaceRoute(), MSBaseVehicle::replaceRouteEdges(), MSBaseVehicle::replaceStop(), MSTransportable::replaceVehicleType(), MSPerson::replaceWalk(), NIImporter_DlrNavteq::TrafficlightsHandler::report(), NLEdgeControlBuilder::reportCurrentEdgeOrLane(), MSDevice_SSM::requestsTrajectories(), MSDevice_ToC::requestToC(), MSStageTrip::reroute(), MSStoppingPlaceRerouter::reroute(), MSBaseVehicle::reroute(), MSRailSignal::LinkInfo::reroute(), GUIVehicle::rerouteDRTStop(), MSVehicle::rerouteParkingArea(), MSTransportable::rerouteParkingArea(), MSDevice_StationFinder::rerouteToChargingStation(), MSDevice_ToC::resetDeliberateLCs(), MSLane::resetManeuverReservation(), MSLane::resetPartialOccupation(), MSDevice_Bluelight::resetVehicle(), MSLaneChanger::resolveDeadlock(), LIBSUMO_NAMESPACE::Vehicle::resume(), MEVehicle::resumeFromStopping(), MSVehicle::resumeFromStopping(), MSRailSignal::retrieveDriveWay(), NIImporter_OpenDrive::retrieveSignalEdges(), RODFNet::revalidateFlows(), NBRailwayTopologyAnalyzer::reverseEdges(), MSStageDriving::routeOutput(), MSStageTranship::routeOutput(), MSStageTrip::routeOutput(), MSStageWaiting::routeOutput(), MSStageWalking::routeOutput(), MSLane::safeInsertionSpeed(), RONet::saveAndRemoveRoutesUntil(), ROPerson::Ride::saveAsXML(), ROVehicle::saveAsXML(), MSLCM_LC2013::saveBlockerLength(), MSLane::saveState(), MESegment::saveState(), MSDevice::saveState(), MSDevice_Battery::saveState(), MSDevice_Routing::saveState(), MSDevice_Transportable::saveState(), MSDevice_Tripinfo::saveState(), MSDevice_Vehroutes::saveState(), MSTransportableDevice_Routing::saveState(), MSSimpleTrafficLightLogic::saveState(), MSStageDriving::saveState(), MSCalibrator::scheduleRemoval(), GUIVehicle::selectBlockingFoes(), MSE2Collector::selectLanes(), MSVehicle::setAngle(), MSLink::setApproaching(), MSVehicle::setApproachingForAllLinks(), NBNodeCont::setAsTLControlled(), GNEJunction::setAttribute(), MSSimpleDriverState::setAwareness(), MSLane::setBidiLane(), MSEdge::setBidiLanes(), NLEdgeControlBuilder::setDefaultStopOffset(), MSBaseVehicle::setDepartAndArrivalEdge(), MSCalibrator::setFlow(), NBEdge::setGeometry(), MSBaseVehicle::setJunctionModelParameter(), MSTransportable::setJunctionModelParameter(), MSAbstractLaneChangeModel::setManeuverDist(), MSLane::setManeuverReservation(), MSDevice_Battery::setMaximumBatteryCapacity(), MSDevice_Battery::setMaximumChargeRate(), NBEdge::setNodeBorder(), MSLane::setOpposite(), MSLCM_SL2015::setOwnState(), MSDevice_ToC::setParameter(), MSActuatedTrafficLightLogic::setParameter(), MSSimpleTrafficLightLogic::setParameter(), NEMALogic::setParameter(), MSCFModel_CACC::setParameter(), MSCFModel_CC::setParameter(), MSLane::setPartialOccupation(), NBEdgePriorityComputer::setPriorityJunctionPriorities(), libsumo::Helper::setRemoteControlled(), MSLink::setRequestInformation(), LIBSUMO_NAMESPACE::Vehicle::setRoute(), LIBSUMO_NAMESPACE::Vehicle::setRouteID(), MSDevice_Battery::setStoppingThreshold(), NBLoadedSUMOTLDef::setTLControllingInformation(), NBLoadedTLDef::setTLControllingInformation(), NBOwnTLDef::setTLControllingInformation(), NBTrafficLightLogicCont::setTLControllingInformation(), MSStageDriving::setVehicle(), MSOverheadWire::setVoltage(), NBEdge::shiftPositionAtNode(), MSLCM_LC2013::slowDownForBlocked(), MSLCM_SL2015::slowDownForBlocked(), MSVehicle::slowDownForSchedule(), MSLane::sortManeuverReservations(), IntermodalNetwork< E, L, N, V >::splitEdge(), MSDispatch_TraCI::splitReservation(), MSLaneChangerSublane::startChangeSublane(), MSStopOut::stopEnded(), MSCFModel_EIDM::stopSpeed(), MSStopOut::stopStarted(), MSLane::succLinkSec(), LIBSUMO_NAMESPACE::TrafficLight::swapConstraints(), MSDevice_ToC::switchHolderType(), GNETLSEditorFrame::TLSDefinition::switchProgram(), GUITrafficLightLogicWrapper::switchTLSLogic(), MSDevice_StationFinder::teleportToChargingStation(), MELoop::teleportVehicle(), MSDevice_ToC::ToCPreparationStep(), libsumo::Helper::TransportableStateListener::transportableStateChanged(), TraCIServer::transportableStateChanged(), MSDevice_ToC::triggerDownwardToC(), MSDevice_ToC::triggerMRM(), MSTriggeredRerouter::triggerRouting(), MSDevice_ToC::triggerUpwardToC(), MSTransportable::tripInfoOutput(), MSPerson::MSPersonStage_Access::tripInfoOutput(), METriggeredCalibrator::tryEmit(), MSPModel_JuPedSim::tryPedestrianInsertion(), MSSOTLTrafficLightLogic::trySwitch(), MSActuatedTrafficLightLogic::trySwitch(), NEMALogic::trySwitch(), MSStopOut::unloadedContainers(), MSStopOut::unloadedPersons(), MSPModel_Interacting::unregisterCrossingApproach(), MSDevice_SSM::update(), MSSimpleDriverState::update(), PolygonDynamics::update(), MSDevice_SSM::updateAndWriteOutput(), MSVehicle::updateBestLanes(), MSLCHelper::updateBlockerLength(), MSLCM_SL2015::updateCFRelated(), MSDevice_StationFinder::updateChargeLimit(), LIBSUMO_NAMESPACE::TrafficLight::updateConstraints(), MSSOTLTrafficLightLogic::updateCTS(), NLEdgeControlBuilder::updateCurrentLaneStopOffset(), MSVehicle::updateDriveItems(), MSRailSignal::updateDriveway(), MSDevice_SSM::updateEncounter(), MSLCM_SL2015::updateExpectedSublaneSpeeds(), MSVehicle::updateFurtherLanes(), MSLCM_SL2015::updateGaps(), GNENetHelper::AttributeCarriers::updateJunctionID(), MSDevice_Taxi::updateMove(), MSSwarmTrafficLightLogic::updatePheromoneLevels(), MSVehicle::Influencer::updateRemoteControlRoute(), MSDispatch::updateReservationFromPos(), MSSwarmTrafficLightLogic::updateSensitivities(), MSAbstractLaneChangeModel::updateShadowLane(), MSVehicle::updateState(), MSAbstractLaneChangeModel::updateTargetLane(), MSDevice_BTreceiver::BTreceiverUpdate::updateVisibility(), MSDevice_SSM::useGeoCoords(), NEMALogic::validate_timing(), NBNodeTypeComputer::validateRailCrossings(), libsumo::Helper::VehicleStateListener::vehicleStateChanged(), MSRailSignalControl::vehicleStateChanged(), TraCIServer::vehicleStateChanged(), MSDynamicShapeUpdater::vehicleStateChanged(), MSLCM_LC2013::wantsChange(), MSLCM_SL2015::wantsChange(), MSLCM_SL2015::wantsChangeSublane(), MSInstantInductLoop::write(), NBParking::write(), MSElecHybridExport::write(), MSFCDExport::write(), MSBatteryExport::write(), MSEmissionExport::write(), MSRailSignalConstraint_Predecessor::write(), MSElecHybridExport::writeAggregated(), MSLink::writeApproaching(), MSRailSignal::writeBlocks(), NWWriter_DlrNavteq::writeConnectedLanes(), NWWriter_SUMO::writeDistrict(), MSMeanData::writeEdge(), NWWriter_SUMO::writeEdge(), MSFullExport::writeEdge(), MSXMLRawOut::writeEdge(), MSRoute::writeEdgeIDs(), NWWriter_XML::writeEdgesAndConnections(), RODFDetector::writeEmitterDefinition(), RODFDetectorCon::writeEmitterPOIs(), RODFDetectorCon::writeEmitters(), RODFDetectorCon::writeEndRerouterDetectors(), NWWriter_OpenDrive::writeInternalEdge(), ROMAAssignments::writeInterval(), NWWriter_SUMO::writeJunction(), MSFullExport::writeLane(), MSQueueExport::writeLane(), MSXMLRawOut::writeLane(), MSDevice_SSM::writeLanesPositions(), NWWriter_DlrNavteq::writeLinksUnsplitted(), NWWriter_OpenDrive::writeNetwork(), NWWriter_XML::writeNodes(), NWWriter_DlrNavteq::writeNodesUnsplitted(), MSTractionSubstation::writeOut(), MSDevice_ToC::writeOutput(), MSNet::writeOutput(), MSDevice_Vehroutes::writeOutput(), MSOverheadWire::writeOverheadWireSegmentOutput(), MSDevice_SSM::writePositions(), NWWriter_OpenDrive::writeRoadObjectPOI(), NWWriter_OpenDrive::writeRoadObjectPoly(), NWWriter_SUMO::writeRoundabout(), NWWriter_OpenDrive::writeSignals(), RODFDetectorCon::writeSpeedTrigger(), NWWriter_SUMO::writeTrafficLight(), NWWriter_DlrNavteq::writeTrafficSignals(), MSFCDExport::writeTransportable(), MSXMLRawOut::writeTransportable(), RODFDetectorCon::writeValidationDetectors(), MSXMLRawOut::writeVehicle(), MSAmitranTrajectories::writeVehicle(), MSFullExport::writeVehicles(), SUMOPolygon::writeXML(), PointOfInterest::writeXML(), MSE2Collector::writeXMLOutput(), MSInductLoop::writeXMLOutput(), MSCalibrator::writeXMLOutput(), MSRouteProbe::writeXMLOutput(), MSLaneChanger::yieldToDeadlockOncoming(), MSLaneChanger::yieldToOppositeWaiting(), MSCalibrator::~MSCalibrator(), MSDevice_Transportable::~MSDevice_Transportable(), MSLaneSpeedTrigger::~MSLaneSpeedTrigger(), MSTriggeredRerouter::~MSTriggeredRerouter(), and RONet::~RONet().

◆ getIDSecure()

template<class T >
static std::string Named::getIDSecure ( const T *  obj,
const std::string &  fallBack = "NULL" 
)
inlinestaticinherited

get an identifier for Named-like object which may be Null

Definition at line 67 of file Named.h.

Referenced by MSLCM_LC2013::_wantsChange(), MSLCM_SL2015::_wantsChangeSublane(), MSLaneChanger::avoidDeadlock(), MSLaneChanger::changeOpposite(), MSLaneChanger::checkChangeOpposite(), MSRailSignal::DriveWay::checkFlanks(), MSVehicle::checkReversal(), MSVehicle::checkRewindLinkLanes(), AStarRouter< E, V >::compute(), DijkstraRouter< E, V >::compute(), NBOwnTLDef::computeLogicAndConts(), MSRailSignal::DriveWay::conflictLaneOccupied(), NBPTLineCont::constructRoute(), MSLaneChanger::continueChange(), MSLane::detectCollisions(), MSVehicle::enterLaneAtLaneChange(), MSVehicle::executeMove(), NBRailwayTopologyAnalyzer::extendDirectionPriority(), MSRailSignal::DriveWay::findProtection(), NBPTLineCont::findWay(), MSCFModel_CACC::followSpeed(), MSCFModel_W99::followSpeed(), MSStopOut::generateOutputForUnfinished(), MSVehicle::getBackPositionOnLane(), NBOwnTLDef::getBestCombination(), NBOwnTLDef::getBestPair(), MSVehicle::getCenterOnEdge(), MSLaneChanger::getColumnleader(), NBEdge::Connection::getDescription(), MSLane::getFollowersOnConsecutive(), GUIVehicle::getLaneID(), LIBSUMO_NAMESPACE::Person::getLaneID(), MSVehicle::getLatOffset(), MSLane::getLeaderOnConsecutive(), MSLaneChanger::getOncomingOppositeVehicle(), MSLaneChanger::getRealLeader(), GUIVehicle::getShadowLaneID(), GUIVehicle::getTargetLaneID(), MSDevice_SSM::getVehiclesOnJunction(), NBEdgeCont::guessRoundabouts(), MSCFModel_IDM::insertionFollowSpeed(), MSLane::isInsertionSuccess(), MESegment::isOpen(), joinNamedToString(), joinNamedToStringSorting(), MSPModel_Striping::PState::moveToNextLane(), LIBSUMO_NAMESPACE::Person::moveToXY(), LIBSUMO_NAMESPACE::Vehicle::moveToXY(), MSPModel_Striping::PState::moveToXY(), libsumo::Helper::moveToXYMap(), libsumo::Helper::moveToXYMap_matchingRoutePosition(), MSDevice_Bluelight::notifyEnter(), MSDevice_Bluelight::notifyLeave(), MSVehicle::Influencer::postProcessRemoteControl(), MSVehicle::processNextStop(), MSBaseVehicle::replaceRoute(), MSStoppingPlaceRerouter::reroute(), MSBaseVehicle::reroute(), MSRailSignal::DriveWay::reserve(), MSLaneChanger::resolveDeadlock(), MSLCM_LC2013::slowDownForBlocked(), MSLCM_SL2015::slowDownForBlocked(), MSLaneChangerSublane::startChangeSublane(), MSLeaderInfo::toString(), MSLeaderDistanceInfo::toString(), MSCriticalFollowerDistanceInfo::toString(), toString(), MSTriggeredRerouter::triggerRouting(), MSVehicle::updateBestLanes(), MSLCHelper::updateBlockerLength(), MSAbstractLaneChangeModel::updateShadowLane(), MSPModel_Striping::PState::walk(), and MSLaneChanger::yieldToDeadlockOncoming().

◆ getIntended()

template<class E , class L , class N , class V >
virtual double IntermodalEdge< E, L, N, V >::getIntended ( const double  ,
std::string &   
) const
inlinevirtualinherited

get intended vehicle id and departure time of next public transport ride

Reimplemented in PublicTransportEdge< E, L, N, V >.

Definition at line 168 of file IntermodalEdge.h.

Referenced by IntermodalRouter< E, L, N, V >::compute(), and IntermodalRouter< E, L, N, V >::loopedLineTransfer().

Here is the caller graph for this function:

◆ getLength()

template<class E , class L , class N , class V >
double IntermodalEdge< E, L, N, V >::getLength ( ) const
inlineinherited

◆ getLengthGeometryFactor()

template<class E , class L , class N , class V >
double IntermodalEdge< E, L, N, V >::getLengthGeometryFactor ( ) const
inlineinherited

Definition at line 225 of file IntermodalEdge.h.

References IntermodalEdge< E, L, N, V >::myEdge.

◆ getLine()

template<class E , class L , class N , class V >
const std::string& IntermodalEdge< E, L, N, V >::getLine ( ) const
inlineinherited

Definition at line 92 of file IntermodalEdge.h.

References IntermodalEdge< E, L, N, V >::myLine.

Referenced by IntermodalRouter< E, L, N, V >::loopedLineTransfer().

Here is the caller graph for this function:

◆ getMinimumTravelTime()

template<class E , class L , class N , class V >
double IntermodalEdge< E, L, N, V >::getMinimumTravelTime ( const IntermodalTrip< E, N, V > *const  trip) const
inlineinherited

◆ getNumericalID()

template<class E , class L , class N , class V >
int IntermodalEdge< E, L, N, V >::getNumericalID ( ) const
inlineinherited

Definition at line 100 of file IntermodalEdge.h.

References IntermodalEdge< E, L, N, V >::myNumericalID.

Referenced by MSNet::adaptIntermodalRouter(), IntermodalNetwork< E, L, N, V >::addEdge(), and IntermodalRouter< E, L, N, V >::getCombined().

Here is the caller graph for this function:

◆ getPartialLength()

template<class E , class L , class N , class V >
virtual double IntermodalEdge< E, L, N, V >::getPartialLength ( const IntermodalTrip< E, N, V > * const  ) const
inlinevirtualinherited

◆ getSpeedLimit()

template<class E , class L , class N , class V >
double IntermodalEdge< E, L, N, V >::getSpeedLimit ( ) const
inlineinherited

Definition at line 220 of file IntermodalEdge.h.

References IntermodalEdge< E, L, N, V >::myEdge.

◆ getStartPos()

template<class E , class L , class N , class V >
virtual double IntermodalEdge< E, L, N, V >::getStartPos ( ) const
inlinevirtualinherited

◆ getSuccessors()

template<class E , class L , class N , class V >
virtual const std::vector<IntermodalEdge*>& IntermodalEdge< E, L, N, V >::getSuccessors ( SUMOVehicleClass  vClass = SVC_IGNORING) const
inlinevirtualinherited

Reimplemented in CarEdge< E, L, N, V >.

Definition at line 133 of file IntermodalEdge.h.

References IntermodalEdge< E, L, N, V >::myFollowingEdges, and UNUSED_PARAMETER.

◆ getTravelTime()

template<class E , class L , class N , class V >
double AccessEdge< E, L, N, V >::getTravelTime ( const IntermodalTrip< E, N, V > *const  trip,
double   
) const
inlinevirtual

◆ getTravelTimeAggregated() [1/2]

template<class E , class L , class N , class V >
static double IntermodalEdge< E, L, N, V >::getTravelTimeAggregated ( const IntermodalEdge< E, L, N, V > *const  edge,
const IntermodalTrip< E, N, V > *const  trip,
double  time 
)
inlinestaticinherited

◆ getTravelTimeAggregated() [2/2]

template<class E , class L , class N , class V >
virtual double IntermodalEdge< E, L, N, V >::getTravelTimeAggregated ( const IntermodalTrip< E, N, V > *const  trip,
double  time 
) const
inlinevirtualinherited

Reimplemented in CarEdge< E, L, N, V >.

Definition at line 163 of file IntermodalEdge.h.

References IntermodalEdge< E, L, N, V >::getTravelTime().

Referenced by IntermodalRouter< E, L, N, V >::createNet(), and IntermodalEdge< E, L, N, V >::getTravelTimeAggregated().

Here is the caller graph for this function:

◆ getTravelTimeStatic()

template<class E , class L , class N , class V >
static double IntermodalEdge< E, L, N, V >::getTravelTimeStatic ( const IntermodalEdge< E, L, N, V > *const  edge,
const IntermodalTrip< E, N, V > *const  trip,
double  time 
)
inlinestaticinherited

Definition at line 172 of file IntermodalEdge.h.

References IntermodalEdge< E, L, N, V >::getTravelTime().

Referenced by IntermodalRouter< E, L, N, V >::createNet(), and PedestrianRouter< E, L, N, V >::PedestrianRouter().

Here is the caller graph for this function:

◆ getTravelTimeStaticRandomized()

template<class E , class L , class N , class V >
static double IntermodalEdge< E, L, N, V >::getTravelTimeStaticRandomized ( const IntermodalEdge< E, L, N, V > *const  edge,
const IntermodalTrip< E, N, V > *const  trip,
double  time 
)
inlinestaticinherited

Definition at line 176 of file IntermodalEdge.h.

References IntermodalEdge< E, L, N, V >::getTravelTime(), gWeightsRandomFactor, and RandHelper::rand().

Referenced by IntermodalRouter< E, L, N, V >::createNet(), and PedestrianRouter< E, L, N, V >::PedestrianRouter().

Here is the caller graph for this function:

◆ getViaSuccessors()

template<class E , class L , class N , class V >
virtual const std::vector<std::pair<const IntermodalEdge*, const IntermodalEdge*> >& IntermodalEdge< E, L, N, V >::getViaSuccessors ( SUMOVehicleClass  vClass = SVC_IGNORING,
bool  ignoreTransientPermissions = false 
) const
inlinevirtualinherited

◆ hasEffort()

template<class E , class L , class N , class V >
virtual bool IntermodalEdge< E, L, N, V >::hasEffort ( ) const
inlinevirtualinherited

Definition at line 207 of file IntermodalEdge.h.

References IntermodalEdge< E, L, N, V >::myEfforts.

Referenced by IntermodalEdge< E, L, N, V >::getEffortStatic().

Here is the caller graph for this function:

◆ includeInRoute()

template<class E , class L , class N , class V >
virtual bool IntermodalEdge< E, L, N, V >::includeInRoute ( bool  ) const
inlinevirtualinherited

◆ isInternal()

template<class E , class L , class N , class V >
bool IntermodalEdge< E, L, N, V >::isInternal ( ) const
inlineinherited

Definition at line 203 of file IntermodalEdge.h.

References IntermodalEdge< E, L, N, V >::myEdge.

◆ prohibits()

template<class E , class L , class N , class V >
bool AccessEdge< E, L, N, V >::prohibits ( const IntermodalTrip< E, N, V > *const  trip) const
inlinevirtual

◆ removeSuccessor()

template<class E , class L , class N , class V >
bool IntermodalEdge< E, L, N, V >::removeSuccessor ( const IntermodalEdge< E, L, N, V > *const  edge)
inlineinherited

Definition at line 116 of file IntermodalEdge.h.

References IntermodalEdge< E, L, N, V >::myFollowingEdges, and IntermodalEdge< E, L, N, V >::myFollowingViaEdges.

Referenced by IntermodalNetwork< E, L, N, V >::addAccess().

Here is the caller graph for this function:

◆ restricts()

template<class E , class L , class N , class V >
virtual bool IntermodalEdge< E, L, N, V >::restricts ( const IntermodalTrip< E, N, V > * const  ) const
inlinevirtualinherited

Definition at line 150 of file IntermodalEdge.h.

◆ setID()

virtual void Named::setID ( const std::string &  newID)
inlinevirtualinherited

resets the id

Parameters
[in]newIDThe new id of this object

Reimplemented in NBLoadedSUMOTLDef, MSTransportable, and MSBaseVehicle.

Definition at line 82 of file Named.h.

References Named::myID.

Referenced by Distribution_Parameterized::parse(), NBLoadedSUMOTLDef::reconstructLogic(), NBEdgeCont::rename(), NBNodeCont::rename(), GNEJunction::setAttribute(), NBLoadedSUMOTLDef::setID(), and IntermodalNetwork< E, L, N, V >::splitEdge().

Here is the caller graph for this function:

◆ setLength()

template<class E , class L , class N , class V >
void IntermodalEdge< E, L, N, V >::setLength ( const double  length)
inlineinherited

Definition at line 198 of file IntermodalEdge.h.

References IntermodalEdge< E, L, N, V >::myLength.

Referenced by IntermodalNetwork< E, L, N, V >::addAccess(), and IntermodalNetwork< E, L, N, V >::splitEdge().

Here is the caller graph for this function:

◆ transferSuccessors()

template<class E , class L , class N , class V >
void IntermodalEdge< E, L, N, V >::transferSuccessors ( IntermodalEdge< E, L, N, V > *  to)
inlineinherited

Definition at line 109 of file IntermodalEdge.h.

References IntermodalEdge< E, L, N, V >::myFollowingEdges, and IntermodalEdge< E, L, N, V >::myFollowingViaEdges.

Referenced by IntermodalNetwork< E, L, N, V >::splitEdge().

Here is the caller graph for this function:

Field Documentation

◆ myEdge

template<class E , class L , class N , class V >
const E* const IntermodalEdge< E, L, N, V >::myEdge
privateinherited

◆ myEfforts

template<class E , class L , class N , class V >
ValueTimeLine<double>* IntermodalEdge< E, L, N, V >::myEfforts
privateinherited

Container for passing effort varying over time for the edge.

Definition at line 265 of file IntermodalEdge.h.

Referenced by IntermodalEdge< E, L, N, V >::hasEffort().

◆ myFollowingEdges

template<class E , class L , class N , class V >
std::vector<IntermodalEdge*> IntermodalEdge< E, L, N, V >::myFollowingEdges
protectedinherited

◆ myFollowingViaEdges

template<class E , class L , class N , class V >
std::vector<std::pair<const IntermodalEdge*, const IntermodalEdge*> > IntermodalEdge< E, L, N, V >::myFollowingViaEdges
protectedinherited

◆ myID

std::string Named::myID
protectedinherited

The name of the object.

Definition at line 125 of file Named.h.

Referenced by MSE2Collector::addDetectorToLanes(), RODFDetector::buildDestinationDistribution(), NGEdge::buildNBEdge(), NGNode::buildNBNode(), MSSOTLTrafficLightLogic::checkPhases(), NBNode::computeNodeShape(), NEMALogic::constructTimingAndPhaseDefs(), MSE2Collector::detectorUpdate(), GNEPOI::getAttribute(), GNEPoly::getAttribute(), MSLane::getCanonicalPredecessorLane(), MSLane::getCanonicalSuccessorLane(), Named::getID(), NBEdge::getLaneID(), NEMALogic::getPhaseObj(), ROEdge::getStoredEffort(), GNEPOI::getSumoBaseObject(), MSLane::getSurroundingVehicles(), ROEdge::getTravelTime(), NBEdge::init(), MSSOTLTrafficLightLogic::init(), MSDelayBasedTrafficLightLogic::init(), NEMALogic::init(), MSLane::isInsertionSuccess(), NBNode::NBNode(), MSE2Collector::notifyEnter(), MSE2Collector::notifyLeave(), MSE2Collector::notifyMove(), MSMeanData::openInterval(), NEMALogic::parseControllerType(), RORouteDef::preComputeCurrentRoute(), NBEdge::reinitNodes(), GNEPOI::setAttribute(), GNEPoly::setAttribute(), NBEdge::setGeometry(), Named::setID(), MSSOTLTrafficLightLogic::setToATargetPhase(), Distribution_Parameterized::toStr(), MSChargingStation::writeAggregatedChargingStationOutput(), MSChargingStation::writeChargingStationOutput(), RODFDetector::writeEmitterDefinition(), MSOverheadWire::writeOverheadWireSegmentOutput(), RODFDetector::writeSingleSpeedTrigger(), MSTractionSubstation::writeTractionSubstationOutput(), MEInductLoop::writeXMLOutput(), and MSE3Collector::writeXMLOutput().

◆ myLength

template<class E , class L , class N , class V >
double IntermodalEdge< E, L, N, V >::myLength
privateinherited

◆ myLine

template<class E , class L , class N , class V >
const std::string IntermodalEdge< E, L, N, V >::myLine
privateinherited

public transport line or ped vs car

Definition at line 259 of file IntermodalEdge.h.

Referenced by IntermodalEdge< E, L, N, V >::getLine().

◆ myModeRestrictions

template<class E , class L , class N , class V >
const SVCPermissions AccessEdge< E, L, N, V >::myModeRestrictions
private

only allow using this edge if the modeSet matches (i.e. entering a taxi)

Definition at line 70 of file AccessEdge.h.

Referenced by AccessEdge< E, L, N, V >::prohibits().

◆ myNumericalID

template<class E , class L , class N , class V >
const int IntermodalEdge< E, L, N, V >::myNumericalID
privateinherited

the index in myEdges

Definition at line 253 of file IntermodalEdge.h.

Referenced by IntermodalEdge< E, L, N, V >::getNumericalID().

◆ myTraveltime

template<class E , class L , class N , class V >
const double AccessEdge< E, L, N, V >::myTraveltime
private

travel time (alternative to length)

Definition at line 68 of file AccessEdge.h.

Referenced by AccessEdge< E, L, N, V >::getTravelTime().

◆ myVehicleRestriction

template<class E , class L , class N , class V >
const SVCPermissions AccessEdge< E, L, N, V >::myVehicleRestriction
private

only allow using this edge if the vehicle class matches (i.e. exiting a taxi)

Definition at line 72 of file AccessEdge.h.

Referenced by AccessEdge< E, L, N, V >::prohibits().


The documentation for this class was generated from the following file: