Eclipse SUMO - Simulation of Urban MObility
SUMOTrafficObject Class Referenceabstract

Representation of a vehicle, person, or container. More...

#include <SUMOTrafficObject.h>

Inheritance diagram for SUMOTrafficObject:
[legend]
Collaboration diagram for SUMOTrafficObject:
[legend]

Public Types

typedef long long int NumericalID
 

Public Member Functions

void addTo (const StoringVisitor &cont) const
 Adds this object to the given container. More...
 
virtual double getAcceleration () const =0
 Returns the object's acceleration. More...
 
virtual double getAngle () const =0
 Returns the object's angle in degrees. More...
 
virtual double getBackPositionOnLane (const MSLane *lane) const =0
 Get the object's back position along the given lane. More...
 
virtual double getChosenSpeedFactor () const =0
 
virtual MSDevicegetDevice (const std::type_info &type) const =0
 Returns a device of the given type if it exists or nullptr if not. More...
 
virtual const MSEdgegetEdge () const =0
 Returns the edge the object is currently at. More...
 
const std::string & getID () const
 Returns the id. More...
 
virtual const MSLanegetLane () const =0
 Returns the lane the object is currently at. More...
 
virtual double getMaxSpeed () const =0
 Returns the object's maximum speed (minimum of technical and desired maximum speed) More...
 
virtual const MSEdgegetNextEdgePtr () const =0
 returns the next edge (possibly an internal edge) More...
 
virtual NumericalID getNumericalID () const =0
 return the numerical ID which is only for internal usage More...
 
virtual const SUMOVehicleParametergetParameter () const =0
 Returns the vehicle's parameter (including departure definition) More...
 
virtual Position getPosition (const double offset=0) const =0
 Return current position (x/y, cartesian) More...
 
virtual double getPositionOnLane () const =0
 Get the object's position along the lane. More...
 
virtual double getPreviousSpeed () const =0
 Returns the object's previous speed. More...
 
virtual const MSEdgegetRerouteDestination () const =0
 Returns the end point for reroutes (usually the last edge of the route) More...
 
virtual SumoRNGgetRNG () const =0
 Returns the associated RNG for this object. More...
 
virtual int getRNGIndex () const =0
 
virtual int getRoutePosition () const =0
 return index of edge within route More...
 
virtual int getRoutingMode () const =0
 
virtual double getSlope () const =0
 Returns the slope of the road at object's position in degrees. More...
 
virtual double getSpeed () const =0
 Returns the object's current speed. More...
 
virtual const std::set< NumericalIDgetUpcomingEdgeIDs () const =0
 returns the numerical IDs of edges to be used (possibly of future stages) More...
 
virtual SUMOVehicleClass getVClass () const =0
 Returns the object's access class. More...
 
virtual const MSVehicleTypegetVehicleType () const =0
 Returns the object's "vehicle" type. More...
 
virtual SUMOTime getWaitingTime (const bool accumulated=false) const =0
 
virtual bool hasArrived () const =0
 Returns whether this object has arrived. More...
 
virtual bool hasInfluencer () const =0
 whether the vehicle is individually influenced (via TraCI or special parameters) More...
 
virtual bool ignoreTransientPermissions () const
 Returns whether this object is ignoring transient permission changes (during routing) More...
 
virtual bool isContainer () const
 Whether it is a container. More...
 
virtual bool isPerson () const
 Whether it is a person. More...
 
virtual bool isSelected () const =0
 whether this object is selected in the GUI More...
 
virtual bool isStopped () const =0
 Returns whether the object is at a stop. More...
 
virtual bool isVehicle () const
 Whether it is a vehicle. More...
 
virtual bool replaceRoute (ConstMSRoutePtr route, const std::string &info, bool onInit=false, int offset=0, bool addStops=true, bool removeStops=true, std::string *msgReturn=nullptr)=0
 Replaces the current route by the given one. More...
 
virtual void replaceVehicleType (MSVehicleType *type)=0
 Replaces the current vehicle type by the one given. More...
 
virtual void setID (const std::string &newID)
 resets the id More...
 
 SUMOTrafficObject (const std::string &id)
 Constructor. More...
 
virtual ~SUMOTrafficObject ()
 Destructor. More...
 

Static Public Member Functions

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...
 

Protected Attributes

std::string myID
 The name of the object. More...
 

Detailed Description

Representation of a vehicle, person, or container.

Definition at line 52 of file SUMOTrafficObject.h.

Member Typedef Documentation

◆ NumericalID

typedef long long int SUMOTrafficObject::NumericalID

Definition at line 54 of file SUMOTrafficObject.h.

Constructor & Destructor Documentation

◆ SUMOTrafficObject()

SUMOTrafficObject::SUMOTrafficObject ( const std::string &  id)
inline

Constructor.

Definition at line 57 of file SUMOTrafficObject.h.

◆ ~SUMOTrafficObject()

virtual SUMOTrafficObject::~SUMOTrafficObject ( )
inlinevirtual

Destructor.

Definition at line 60 of file SUMOTrafficObject.h.

Member Function Documentation

◆ 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().

◆ getAcceleration()

virtual double SUMOTrafficObject::getAcceleration ( ) const
pure virtual

◆ getAngle()

virtual double SUMOTrafficObject::getAngle ( ) const
pure virtual

Returns the object's angle in degrees.

Implemented in GUIContainer, SUMOVehicle, MSTransportable, MSVehicle, MEVehicle, GUIMEVehicle, and GUIVehicle.

Referenced by PolygonDynamics::initTrackedPosition(), and PolygonDynamics::update().

Here is the caller graph for this function:

◆ getBackPositionOnLane()

virtual double SUMOTrafficObject::getBackPositionOnLane ( const MSLane lane) const
pure virtual

Get the object's back position along the given lane.

Returns
The position of the object (in m from the given lane's begin)

Implemented in MSTransportable, MSVehicle, and MEVehicle.

Referenced by MSE2Collector::notifyEnter(), MSE3Collector::MSE3EntryReminder::notifyEnter(), MSE3Collector::MSE3LeaveReminder::notifyEnter(), and MSInductLoop::notifyEnter().

Here is the caller graph for this function:

◆ getChosenSpeedFactor()

virtual double SUMOTrafficObject::getChosenSpeedFactor ( ) const
pure virtual

Implemented in MSTransportable, MSPerson, and MSBaseVehicle.

Referenced by MSDevice_Tripinfo::generateOutput(), MSLane::getVehicleMaxSpeed(), MSRoutingEngine::initRouter(), MSEdge::validateDepartSpeed(), MSVehicleControl::vehicleDeparted(), and MSDevice_Vehroutes::writeOutput().

Here is the caller graph for this function:

◆ getDevice()

virtual MSDevice* SUMOTrafficObject::getDevice ( const std::type_info &  type) const
pure virtual

◆ getEdge()

virtual const MSEdge* SUMOTrafficObject::getEdge ( ) const
pure virtual

Returns the edge the object is currently at.

Returns
The current edge in the object's route

Implemented in MSTransportable, and MSBaseVehicle.

Referenced by MSStageDriving::abort(), MSTriggeredRerouter::addParkValues(), MSDevice_Vehroutes::addRoute(), MSStageDriving::canLeaveVehicle(), MSInsertionControl::checkCandidates(), MSDispatch::computePickupTime(), libsumo::Helper::debugPrint(), MSDevice_Taxi::dispatchShared(), LIBSUMO_NAMESPACE::TrafficLight::findConstraintsDeadLocks(), MSDevice_SSM::findFoeConflictLane(), MSDevice_Tripinfo::generateOutput(), MSStopOut::generateOutputForUnfinished(), MSStageDriving::getEdge(), MSStop::getEndPos(), MSDevice_BTsender::getLocation(), MSVehicleControl::getVehicleMeanSpeeds(), MSFCDExport::hasOwnOutput(), MSDevice_ElecHybrid::notifyEnter(), MSDevice_BTreceiver::notifyEnter(), MSDevice_BTsender::notifyEnter(), MSDevice_Example::notifyEnter(), MSDevice_Vehroutes::notifyEnter(), MSDevice_ElecHybrid::notifyLeave(), MSDevice_Example::notifyLeave(), MSDevice_Transportable::notifyLeave(), MSDevice_Tripinfo::notifyLeave(), MSDevice_Vehroutes::notifyLeave(), MSDevice_ElecHybrid::notifyMove(), MSDevice_StationFinder::notifyMove(), MSDevice_Transportable::notifyMoveInternal(), MSDevice_Tripinfo::notifyMoveInternal(), MSMeanData_Net::MSLaneMeanDataValues::notifyMoveInternal(), MSTriggeredRerouter::rerouteParkingArea(), MSStageDriving::setArrived(), MSStopOut::stopEnded(), MSStopOut::stopStarted(), MSTriggeredRerouter::triggerRouting(), MSInsertionControl::tryInsert(), MSFCDExport::write(), and MSEmissionExport::write().

Here is the caller graph for this function:

◆ 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(), MSTriggeredRerouter::addParkValues(), 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(), 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_Striping::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(), 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(), 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(), MSStopOut::generateOutputForUnfinished(), GUITrafficLightLogicWrapper::getActiveTLLogic(), RODFDetectorCon::getAggFlowFor(), RODFDetectorCon::getAnyDetectorForEdge(), MSPModel_Striping::getArbitraryPath(), MSVehicle::getBackPosition(), MSVehicle::getBackPositionOnLane(), LIBSUMO_NAMESPACE::Vehicle::getBestLanes(), MSLaneChanger::getBestLanesOpposite(), NBOwnTLDef::getBestPair(), MSDevice::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(), MSDevice::getFloatParam(), MSBaseVehicle::getFlowID(), MSLane::getFollower(), MSLane::getFollowersOnConsecutive(), GUIPerson::getFromEdgeID(), 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_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(), MSDevice::getStringParam(), MSLane::getSurroundingVehicles(), MSActuatedTrafficLightLogic::getTarget(), LIBSUMO_NAMESPACE::Vehicle::getTeleportingIDList(), MSDevice::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(), MSDevice_SSM::getVehiclesOnJunction(), MSRailSignalConstraint::getVehID(), MSStageDriving::getWaitingDescription(), MSEdge::getWaitingVehicle(), 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(), MSDelayBasedTrafficLightLogic::init(), MSDeterministicHiLevelTrafficLightLogic::init(), MSSOTLTrafficLightLogic::init(), MSSwarmTrafficLightLogic::init(), MSTrafficLightLogic::init(), MSActuatedTrafficLightLogic::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(), 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(), MSPModel_Striping::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(), MSDevice_StationFinder::notifyMove(), MSE2Collector::notifyMove(), MSInductLoop::notifyMove(), MSMeanData::MeanDataValues::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(), MSRailSignalControl::registerProtectedDriveway(), MSLink::removeApproaching(), 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(), NIImporter_DlrNavteq::TrafficlightsHandler::report(), NLEdgeControlBuilder::reportCurrentEdgeOrLane(), MSDevice_SSM::requestsTrajectories(), MSDevice_ToC::requestToC(), MSPerson::reroute(), MSBaseVehicle::reroute(), MSRailSignal::LinkInfo::reroute(), GUIVehicle::rerouteDRTStop(), MSTriggeredRerouter::rerouteParkingArea(), MSVehicle::rerouteParkingArea(), MSTransportable::rerouteParkingArea(), 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(), MSTransportable::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(), MSStageTrip::setArrived(), NBNodeCont::setAsTLControlled(), 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(), 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(), 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(), MSDevice_SSM::update(), MSSimpleDriverState::update(), PolygonDynamics::update(), MSDevice_SSM::updateAndWriteOutput(), MSVehicle::updateBestLanes(), MSLCHelper::updateBlockerLength(), MSLCM_SL2015::updateCFRelated(), 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(), 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(), MSBaseVehicle::reroute(), MSTriggeredRerouter::rerouteParkingArea(), 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().

◆ getLane()

virtual const MSLane* SUMOTrafficObject::getLane ( ) const
pure virtual

Returns the lane the object is currently at.

Returns
The current lane or nullptr if the object is not on a lane

Implemented in MSTransportable, MSVehicle, and MEVehicle.

Referenced by MSStageDriving::abort(), MSBaseVehicle::addStop(), libsumo::Helper::applySubscriptionFilters(), MSE2Collector::calculateTimeLossAndTimeOnDetector(), GUIBaseVehicle::drawOnPos(), Command_RouteReplacement::execute(), MSStopOut::generateOutputForUnfinished(), LIBSUMO_NAMESPACE::Vehicle::getDrivingDistance(), LIBSUMO_NAMESPACE::Vehicle::getDrivingDistance2D(), MSStageDriving::getEdge(), MSStageDriving::getLane(), MSStoppingPlace::getLastFreePos(), MSParkingArea::getLastFreePosWithReservation(), LIBSUMO_NAMESPACE::Vehicle::getLeader(), MSDevice_BTsender::getLocation(), MSBaseVehicle::getRNG(), MSBaseVehicle::getRNGIndex(), MSBaseVehicle::haveValidStopEdges(), MSBaseVehicle::insertStop(), LIBSUMO_NAMESPACE::Vehicle::isOnInit(), MSE2Collector::notifyEnter(), MSDevice_SSM::notifyEnter(), MSDevice_SSM::notifyLeave(), MSDevice_ElecHybrid::notifyMove(), MSDevice_Battery::notifyMove(), MSDevice_Friction::notifyMove(), MSDevice_ToC::notifyMove(), MSMeanData_Net::MSLaneMeanDataValues::notifyMoveInternal(), MSDevice_Taxi::prepareStop(), LIBSUMO_NAMESPACE::Vehicle::remove(), MSBaseVehicle::replaceRoute(), MSBaseVehicle::replaceStop(), MSDevice_ToC::requestToC(), MSBaseVehicle::reroute(), MSBaseVehicle::rerouteBetweenStops(), MSStageDriving::setArrived(), LIBSUMO_NAMESPACE::Vehicle::setRoute(), LIBSUMO_NAMESPACE::Vehicle::setRouteID(), MSDevice_ToC::triggerDownwardToC(), MSDevice_ToC::triggerMRM(), MSDevice_ToC::triggerUpwardToC(), and MSFCDExport::write().

Here is the caller graph for this function:

◆ getMaxSpeed()

virtual double SUMOTrafficObject::getMaxSpeed ( ) const
pure virtual

Returns the object's maximum speed (minimum of technical and desired maximum speed)

Returns
The object's maximum speed

Implemented in MSTransportable, and MSBaseVehicle.

Referenced by MSEdge::getTravelTimeAggregated(), MSLane::getVehicleMaxSpeed(), and MSTriggeredRerouter::triggerRouting().

Here is the caller graph for this function:

◆ getNextEdgePtr()

virtual const MSEdge* SUMOTrafficObject::getNextEdgePtr ( ) const
pure virtual

returns the next edge (possibly an internal edge)

Implemented in MSTransportable, MSPerson, MSVehicle, and MSBaseVehicle.

Referenced by MSDetectorFileOutput::vehicleApplies().

Here is the caller graph for this function:

◆ getNumericalID()

virtual NumericalID SUMOTrafficObject::getNumericalID ( ) const
pure virtual

return the numerical ID which is only for internal usage

Implemented in MSTransportable, and MSBaseVehicle.

Referenced by LIBSUMO_NAMESPACE::TrafficLight::findConstraintsDeadLocks(), MSVehicleDevice::getNumericalID(), MSVehicleDevice::ComparatorNumericalVehicleIdLess::operator()(), and MSDevice_Vehroutes::writeOutput().

Here is the caller graph for this function:

◆ getParameter()

virtual const SUMOVehicleParameter& SUMOTrafficObject::getParameter ( ) const
pure virtual

Returns the vehicle's parameter (including departure definition)

Returns
The vehicle's parameter

Implemented in MSTransportable, and MSBaseVehicle.

Referenced by MSVehicleControl::abortWaiting(), MSVehicleContainer::add(), MSRouteHandler::addRideOrTransport(), MSVehicleControl::addVehicle(), MSDevice_ElecHybrid::buildVehicleDevices(), MSDevice_Example::buildVehicleDevices(), MSDevice_Routing::buildVehicleDevices(), MSDevice_Taxi::buildVehicleDevices(), MSDevice_Vehroutes::buildVehicleDevices(), MSRouteHandler::closeVehicle(), MSDevice_Taxi::compatibleLine(), MSRailSignal::constraintsAllow(), MSParkingArea::enter(), MSDevice_SSM::filterByConflictType(), LIBSUMO_NAMESPACE::TrafficLight::findConstraintsDeadLocks(), MSDevice_Tripinfo::generateOutput(), MSDevice_Tripinfo::generateOutputForUnfinished(), MSEdge::getDepartLaneMeso(), MSDevice_SSM::getDetectionRange(), MSDevice_SSM::getExtraTime(), MSDevice_SSM::getMDRAC_PRT(), MSDevice_SSM::getMeasuresAndThresholds(), MSDevice_ToC::getOutputFilename(), MSDevice_SSM::getOutputFilename(), MSDevice::getStringParam(), LIBSUMO_NAMESPACE::TrafficLight::getVehicleByTripId(), MSRailSignalConstraint::getVehID(), MSTriggeredRerouter::getWeight(), MSVehicleControl::handleTriggeredDepart(), MSLink::ignoreFoe(), MSRailSignal::initDriveWays(), MSEdge::insertVehicle(), MSStageDriving::isWaitingFor(), MSDevice_Routing::MSDevice_Routing(), MSDevice_Taxi::MSDevice_Taxi(), MSDevice_Vehroutes::notifyEnter(), MSRailSignalConstraint_Predecessor::PassedTracker::notifyEnter(), MSCalibrator::VehicleRemover::notifyEnter(), MSDevice_Routing::preInsertionReroute(), MSStageDriving::proceed(), MSDevice_Battery::readParameterValue(), MSVehicleContainer::remove(), MSDevice_SSM::requestsTrajectories(), MSStageTrip::setArrived(), MSDevice_Taxi::setParameter(), MSStageDriving::setVehicle(), MSDevice_ToC::setVehicleColor(), MSTriggeredRerouter::triggerRouting(), MSInsertionControl::tryInsert(), MSDevice_SSM::useGeoCoords(), MSEdge::validateDepartSpeed(), MSVehicleControl::vehicleDeparted(), MSDevice_SSM::writeLanesPositions(), MSDevice_Vehroutes::writeOutput(), MSDevice_SSM::writePositions(), and MSDevice_Vehroutes::writeXMLRoute().

◆ getPosition()

virtual Position SUMOTrafficObject::getPosition ( const double  offset = 0) const
pure virtual

◆ getPositionOnLane()

virtual double SUMOTrafficObject::getPositionOnLane ( ) const
pure virtual

Get the object's position along the lane.

Returns
The position of the object (in m from the lane's begin)

Implemented in MSTransportable, MSVehicle, and MEVehicle.

Referenced by MSTriggeredRerouter::addParkValues(), MSBaseVehicle::addStop(), MSDispatch::computePickupTime(), MSDevice_Taxi::dispatchShared(), GUIBaseVehicle::drawStopLabels(), MSParkingArea::enter(), MSStoppingPlace::enter(), MSVTypeProbe::execute(), LIBSUMO_NAMESPACE::TrafficLight::findConstraintsDeadLocks(), MSDevice_Tripinfo::generateOutput(), LIBSUMO_NAMESPACE::Vehicle::getDrivingDistance(), LIBSUMO_NAMESPACE::Vehicle::getDrivingDistance2D(), MSStageDriving::getEdgePos(), MSStop::getEndPos(), LIBSUMO_NAMESPACE::Vehicle::getLanePosition(), MSStoppingPlace::getLastFreePos(), MSParkingArea::getLotIndex(), MSBaseVehicle::getOdometer(), MSBaseVehicle::haveValidStopEdges(), MSIdling_Stop::idle(), MSIdling_RandomCircling::idle(), MSBaseVehicle::insertStop(), MSE2Collector::makeVehicleInfo(), LIBSUMO_NAMESPACE::Vehicle::moveToXY(), MSDevice_BTreceiver::notifyEnter(), MSDevice_BTsender::notifyEnter(), MSDevice_Tripinfo::notifyEnter(), MSDevice_Vehroutes::notifyEnter(), MSInductLoop::notifyEnter(), MSDevice_BTreceiver::notifyLeave(), MSDevice_BTsender::notifyLeave(), MSDevice_Tripinfo::notifyLeave(), MSDevice_ElecHybrid::notifyMove(), MSDevice_Battery::notifyMove(), MSDevice_StationFinder::notifyMove(), MSDevice_ToC::notifyMove(), MSDevice_Battery::notifyParking(), MSBaseVehicle::onDepart(), MSOverheadWire::vehicle_position_sorter::operator()(), MSBaseVehicle::replaceRoute(), MSBaseVehicle::replaceStop(), MSDevice_ToC::requestToC(), MSBaseVehicle::reroute(), MSBaseVehicle::rerouteBetweenStops(), MSTriggeredRerouter::rerouteParkingArea(), MSStageDriving::setArrived(), MSStopOut::stopEnded(), MSDevice_ToC::triggerDownwardToC(), MSDevice_ToC::triggerMRM(), MSTriggeredRerouter::triggerRouting(), MSDevice_ToC::triggerUpwardToC(), MSElecHybridExport::write(), MSFCDExport::write(), MSEmissionExport::write(), MSElecHybridExport::writeAggregated(), MSDevice_Vehroutes::writeOutput(), MSXMLRawOut::writeVehicle(), and MSFullExport::writeVehicles().

◆ getPreviousSpeed()

virtual double SUMOTrafficObject::getPreviousSpeed ( ) const
pure virtual

Returns the object's previous speed.

Returns
The object's previous speed

Implemented in MSTransportable, MSVehicle, and MSBaseVehicle.

Referenced by MSE2Collector::calculateTimeLossAndTimeOnDetector(), LIBSUMO_NAMESPACE::Vehicle::getJunctionFoes(), MSInductLoop::notifyMove(), MSInstantInductLoop::notifyMove(), MSMeanData::MeanDataValues::notifyMove(), MSE3Collector::MSE3LeaveReminder::notifyMove(), and MSE3Collector::MSE3EntryReminder::notifyMove().

Here is the caller graph for this function:

◆ getRerouteDestination()

virtual const MSEdge* SUMOTrafficObject::getRerouteDestination ( ) const
pure virtual

Returns the end point for reroutes (usually the last edge of the route)

Returns
The rerouting end point

Implemented in MSTransportable, and MSBaseVehicle.

Referenced by MSTriggeredRerouter::triggerRouting().

Here is the caller graph for this function:

◆ getRNG()

virtual SumoRNG* SUMOTrafficObject::getRNG ( ) const
pure virtual

Returns the associated RNG for this object.

Returns
The vehicle's associated RNG

Implemented in MSTransportable, and MSBaseVehicle.

Referenced by MSLink::blockedAtTime(), MSIdling_RandomCircling::idle(), MSDevice_Friction::notifyMove(), MSTriggeredRerouter::rerouteParkingArea(), and MSTriggeredRerouter::triggerRouting().

Here is the caller graph for this function:

◆ getRNGIndex()

virtual int SUMOTrafficObject::getRNGIndex ( ) const
pure virtual
Returns
The index of the associated RNG

Implemented in MSTransportable, and MSBaseVehicle.

Referenced by MSDevice_Taxi::dispatchShared(), MSDevice_Routing::notifyEnter(), MSDevice_StationFinder::notifyMove(), MSDevice_Taxi::prepareStop(), MSTriggeredRerouter::rerouteParkingArea(), and MSTriggeredRerouter::triggerRouting().

Here is the caller graph for this function:

◆ getRoutePosition()

◆ getRoutingMode()

virtual int SUMOTrafficObject::getRoutingMode ( ) const
pure virtual

Implemented in MSTransportable, and MSBaseVehicle.

◆ getSlope()

virtual double SUMOTrafficObject::getSlope ( ) const
pure virtual

◆ getSpeed()

virtual double SUMOTrafficObject::getSpeed ( ) const
pure virtual

Returns the object's current speed.

Returns
The object's speed

Implemented in GUIPerson, GUIContainer, MSTransportable, MSVehicle, and MEVehicle.

Referenced by MSChargingStation::addChargeValueForOutput(), MSE2Collector::calculateTimeLossAndTimeOnDetector(), MSInductLoop::collectVehiclesOnDet(), MSE3Collector::detectorUpdate(), GUIBaseVehicle::drawOnPos(), MSE3Collector::enter(), MSVTypeProbe::execute(), MSVehicle::Influencer::gapControlSpeed(), MSRailSignal::LinkInfo::getDriveWay(), MSBaseVehicle::getEmissions(), MSVehicleControl::getHaltingVehicleNo(), MSBaseVehicle::getHarmonoise_NoiseEmissions(), LIBSUMO_NAMESPACE::Vehicle::getJunctionFoes(), MSStoppingPlace::getLastFreePos(), MSCFModel_CC::getRadarMeasurements(), GUIBaseVehicle::getScaleValue(), MSStageDriving::getSpeed(), LIBSUMO_NAMESPACE::Vehicle::getSpeed(), LIBSUMO_NAMESPACE::Vehicle::getSpeedWithoutTraCI(), MSVehicleControl::getVehicleMeanSpeeds(), MSRailSignal::hasOncomingRailTraffic(), MSBaseVehicle::isParking(), MSE3Collector::leave(), MSDevice_BTreceiver::notifyEnter(), MSDevice_BTsender::notifyEnter(), MSDevice_Tripinfo::notifyEnter(), MSDevice_Vehroutes::notifyEnter(), MSDevice_BTreceiver::notifyLeave(), MSDevice_BTsender::notifyLeave(), MSDevice_Tripinfo::notifyLeave(), MSInstantInductLoop::notifyLeave(), MSDevice_ElecHybrid::notifyMove(), MSDevice_Battery::notifyMove(), MSDevice_Bluelight::notifyMove(), MSDevice_Battery::notifyParking(), MSNet::registerCollision(), MSLink::setApproaching(), MSElecHybridExport::write(), MSFCDExport::write(), MSEmissionExport::write(), MSElecHybridExport::writeAggregated(), MSXMLRawOut::writeVehicle(), MSAmitranTrajectories::writeVehicle(), and MSFullExport::writeVehicles().

Here is the caller graph for this function:

◆ getUpcomingEdgeIDs()

virtual const std::set<NumericalID> SUMOTrafficObject::getUpcomingEdgeIDs ( ) const
pure virtual

returns the numerical IDs of edges to be used (possibly of future stages)

Implemented in MSTransportable, and MSBaseVehicle.

Referenced by MSTriggeredRerouter::getCurrentReroute(), and MSTriggeredRerouter::triggerRouting().

Here is the caller graph for this function:

◆ getVClass()

◆ getVehicleType()

virtual const MSVehicleType& SUMOTrafficObject::getVehicleType ( ) const
pure virtual

Returns the object's "vehicle" type.

Returns
The vehicle's type

Implemented in MSTransportable, and MSBaseVehicle.

Referenced by MSChargingStation::addChargeValueForOutput(), MSOverheadWire::addChargeValueForOutput(), MSTriggeredRerouter::applies(), MSLink::blockedAtTime(), MSLink::blockedByFoe(), MSDevice_ElecHybrid::buildVehicleDevices(), MSDevice_Example::buildVehicleDevices(), MSDevice_Taxi::buildVehicleDevices(), MSLink::computeFoeArrivalTimeBraking(), MSDevice_SSM::computeGlobalMeasures(), MSParkingArea::enter(), MSStoppingPlace::enter(), MSVTypeProbe::execute(), MSDevice_SSM::filterByConflictType(), MSStoppingPlace::fits(), MSDevice_Tripinfo::generateOutput(), MSEdge::getDepartLaneMeso(), MSDevice_SSM::getDetectionRange(), MSDevice_SSM::getExtraTime(), MSParkingArea::getLastFreePos(), MSStoppingPlace::getLastFreePos(), MSParkingArea::getLastFreePosWithReservation(), MSDevice_SSM::getMDRAC_PRT(), MSDevice_SSM::getMeasuresAndThresholds(), MSDevice_ToC::getOutputFilename(), MSDevice_SSM::getOutputFilename(), MSDevice::getStringParam(), MSTriggeredRerouter::getWeight(), MSIdling_Stop::idle(), MSIdling_TaxiStand::idle(), MSLink::ignoreFoe(), MSVehicle::ignoreFoe(), MSEdge::insertVehicle(), MSTransportableControl::loadAnyWaiting(), MSE2Collector::makeVehicleInfo(), MSDevice_Battery::MSDevice_Battery(), MSDevice_ElecHybrid::MSDevice_ElecHybrid(), MSDevice_ToC::MSDevice_ToC(), MSMeanData_Amitran::MSLaneMeanDataValues::notifyEnter(), MSCalibrator::VehicleRemover::notifyEnter(), MSE3Collector::MSE3EntryReminder::notifyEnter(), MSDevice_Emissions::notifyIdle(), MSMeanData_Emissions::MSLaneMeanDataValues::notifyIdle(), MSDevice_Battery::notifyMove(), MSDevice_Bluelight::notifyMove(), MSDevice_Emissions::notifyMove(), MSDevice_Transportable::notifyMove(), MSE2Collector::notifyMove(), MSInductLoop::notifyMove(), MSInstantInductLoop::notifyMove(), MSMeanData::MeanDataValues::notifyMove(), MSE3Collector::MSE3LeaveReminder::notifyMove(), MSDevice_Emissions::notifyMoveInternal(), MSMeanData_Net::MSLaneMeanDataValues::notifyMoveInternal(), MSMeanData_Harmonoise::MSLaneMeanDataValues::notifyMoveInternal(), MSMeanData_Amitran::MSLaneMeanDataValues::notifyMoveInternal(), MSMeanData_Emissions::MSLaneMeanDataValues::notifyMoveInternal(), MSLink::opened(), MSDevice_Taxi::prepareStop(), MSDevice_Battery::readParameterValue(), MSNet::registerCollision(), MSDispatch::remainingCapacity(), MSDevice_SSM::requestsTrajectories(), MSLink::setApproaching(), MSStageDriving::setVehicle(), MSStopOut::stopEnded(), MSLane::succLinkSec(), MSDevice_SSM::useGeoCoords(), MSEdge::validateDepartSpeed(), MSDetectorFileOutput::vehicleApplies(), MSVehicleControl::vehicleDeparted(), MSInstantInductLoop::write(), MSFCDExport::write(), MSEmissionExport::write(), MSElecHybridExport::writeAggregated(), MSDevice_SSM::writeLanesPositions(), MSDevice_Vehroutes::writeOutput(), MSDevice_SSM::writePositions(), MSAmitranTrajectories::writeVehicle(), and MSFullExport::writeVehicles().

◆ getWaitingTime()

virtual SUMOTime SUMOTrafficObject::getWaitingTime ( const bool  accumulated = false) const
pure virtual

Implemented in MSTransportable, MSVehicle, and MEVehicle.

Referenced by MSBaseVehicle::getImpatience(), MSBaseVehicle::getWaitingSeconds(), MSDevice_Tripinfo::notifyMoveInternal(), and MSTriggeredRerouter::triggerRouting().

Here is the caller graph for this function:

◆ hasArrived()

virtual bool SUMOTrafficObject::hasArrived ( ) const
pure virtual

Returns whether this object has arrived.

Implemented in MSTransportable, MSVehicle, MSBaseVehicle, and MEVehicle.

Referenced by MSMeanData::MeanDataValues::notifyMove().

Here is the caller graph for this function:

◆ hasInfluencer()

virtual bool SUMOTrafficObject::hasInfluencer ( ) const
pure virtual

whether the vehicle is individually influenced (via TraCI or special parameters)

Implemented in MSBaseVehicle, MSTransportable, MSPerson, MSVehicle, and MEVehicle.

◆ ignoreTransientPermissions()

virtual bool SUMOTrafficObject::ignoreTransientPermissions ( ) const
inlinevirtual

Returns whether this object is ignoring transient permission changes (during routing)

Reimplemented in MSBaseVehicle.

Definition at line 168 of file SUMOTrafficObject.h.

Referenced by MSEdge::prohibits().

Here is the caller graph for this function:

◆ isContainer()

virtual bool SUMOTrafficObject::isContainer ( ) const
inlinevirtual

Whether it is a container.

Returns
true for containers, false otherwise

Reimplemented in MSTransportable.

Definition at line 79 of file SUMOTrafficObject.h.

◆ isPerson()

virtual bool SUMOTrafficObject::isPerson ( ) const
inlinevirtual

Whether it is a person.

Returns
true for persons, false otherwise

Reimplemented in MSTransportable.

Definition at line 72 of file SUMOTrafficObject.h.

Referenced by MSE3Collector::enter(), MSE3Collector::leave(), MSE3Collector::leaveFront(), MSE2Collector::notifyEnter(), MSInductLoop::notifyEnter(), MSE2Collector::notifyLeave(), MSInductLoop::notifyLeave(), MSE2Collector::notifyMove(), MSInductLoop::notifyMove(), MSE3Collector::MSE3EntryReminder::notifyMove(), and MSDetectorFileOutput::vehicleApplies().

Here is the caller graph for this function:

◆ isSelected()

virtual bool SUMOTrafficObject::isSelected ( ) const
pure virtual

whether this object is selected in the GUI

Implemented in GUIPerson, GUIContainer, MSTransportable, MSPerson, MSBaseVehicle, and GUIVehicle.

Referenced by MSLink::blockedByFoe().

Here is the caller graph for this function:

◆ isStopped()

virtual bool SUMOTrafficObject::isStopped ( ) const
pure virtual

Returns whether the object is at a stop.

Returns
Whether it has stopped

Implemented in MSTransportable, and MSBaseVehicle.

Referenced by MSVehicleControl::getVehicleMeanSpeeds(), MSDevice_Transportable::notifyMove(), MSDevice_Tripinfo::notifyMove(), MSMeanData_Net::MSLaneMeanDataValues::notifyMoveInternal(), MSDevice_Transportable::removeTransportable(), MSDevice_Taxi::updateMove(), and MSDevice_Routing::wrappedRerouteCommandExecute().

Here is the caller graph for this function:

◆ isVehicle()

◆ replaceRoute()

virtual bool SUMOTrafficObject::replaceRoute ( ConstMSRoutePtr  route,
const std::string &  info,
bool  onInit = false,
int  offset = 0,
bool  addStops = true,
bool  removeStops = true,
std::string *  msgReturn = nullptr 
)
pure virtual

Replaces the current route by the given one.

Implemented in MSTransportable, MSVehicle, MSBaseVehicle, and MEVehicle.

Referenced by Command_RouteReplacement::execute(), MSDevice_Routing::preInsertionReroute(), and MSTriggeredRerouter::triggerRouting().

Here is the caller graph for this function:

◆ replaceVehicleType()

virtual void SUMOTrafficObject::replaceVehicleType ( MSVehicleType type)
pure virtual

Replaces the current vehicle type by the one given.

If the currently used vehicle type is marked as being used by this object only, it is deleted, first. The new, given type is then assigned to "myVType".

Parameters
[in]typeThe new vehicle type
See also
MSTransportable::myVType

Implemented in MSTransportable, MSVehicle, and MSBaseVehicle.

Referenced by MSCalibrator::VehicleRemover::notifyEnter().

Here is the caller graph for this function:

◆ 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:

Field Documentation

◆ myID

std::string Named::myID
protectedinherited

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