Eclipse SUMO - Simulation of Urban MObility
MSPerson Class Reference

#include <MSPerson.h>

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

Data Structures

class  Influencer
 Changes the wished person speed and position. More...
 
class  MSPersonStage_Access
 

Public Types

typedef std::vector< MSStage * > MSTransportablePlan
 the structure holding the plan of a transportable More...
 
typedef long long int NumericalID
 

Public Member Functions

SUMOTime abortStage (SUMOTime step)
 Abort current stage (used for aborting waiting for a vehicle) More...
 
void addTo (const StoringVisitor &cont) const
 Adds this object to the given container. More...
 
void appendStage (MSStage *stage, int next=-1)
 Appends the given stage to the current plan. More...
 
bool checkAccess (const MSStage *const prior, const bool waitAtStop=true)
 
virtual double getAngle () const
 return the current angle of the transportable More...
 
const MSEdgegetArrivalEdge () const
 returns the final arrival edge More...
 
double getArrivalPos () const
 returns the final arrival pos More...
 
PositionVector getBoundingBox () const
 return the bounding box of the person More...
 
double getChosenSpeedFactor () const
 the current speed factor of the transportable (where applicable) More...
 
MSStagegetCurrentStage () const
 Return the current stage. More...
 
std::string getCurrentStageDescription () const
 Returns the current stage description as a string. More...
 
int getCurrentStageIndex () const
 Return the index of the current stage. More...
 
MSStageType getCurrentStageType () const
 the current stage type of the transportable More...
 
SUMOTime getDeparture () const
 logs depart time of the current stage More...
 
SUMOTime getDesiredDepart () const
 Returns the desired departure time. More...
 
const MSEdgegetDestination () const
 Returns the current destination. More...
 
MSDevicegetDevice (const std::type_info &type) const
 Returns a device of the given type if it exists or nullptr if not. More...
 
const std::vector< MSTransportableDevice * > & getDevices () const
 Returns this vehicle's devices. More...
 
virtual int getDirection () const
 Return the movement directon on the edge. More...
 
const MSEdgegetEdge () const
 Returns the current edge. More...
 
virtual double getEdgePos () const
 Return the position on the edge. More...
 
const MSEdgegetFromEdge () const
 Returns the departure edge. More...
 
const std::string & getID () const
 Returns the id. More...
 
double getImpatience () const
 
InfluencergetInfluencer ()
 Returns the velocity/lane influencer. More...
 
const InfluencergetInfluencer () const
 
const MSLanegetLane () const
 Returns the current lane (may be nullptr) More...
 
const MSEdgegetNextDestination () const
 Returns the destination after the current destination. More...
 
const std::string & getNextEdge () const
 return the list of internal edges if this person is walking and the pedestrian model allows it More...
 
const MSEdgegetNextEdgePtr () const
 returns the next edge ptr if this person is walking and the pedestrian model allows it More...
 
MSStagegetNextStage (int offset) const
 Return the next (or previous) stage denoted by the offset. More...
 
int getNumRemainingStages () const
 Return the number of remaining stages (including the current) More...
 
int getNumStages () const
 Return the total number stages in this person's plan. More...
 
const SUMOVehicleParametergetParameter () const
 Returns the vehicle's parameter (including departure definition) More...
 
virtual Position getPosition () const
 Return the Network coordinate of the transportable. More...
 
const MSEdgegetRerouteDestination () const
 Returns the end point for reroutes (usually the last edge of the route) More...
 
SumoRNGgetRNG () const
 returns the associated RNG More...
 
int getRNGIndex () const
 returns the index of the associated RNG More...
 
int getRoutePosition () const
 return the index of the edge within the route More...
 
virtual int getRoutingMode () const
 return routing mode (configures router choice but also handling of transient permission changes) More...
 
MSVehicleTypegetSingularType ()
 Replaces the current vehicle type with a new one used by this vehicle only. More...
 
virtual double getSpeed () const
 the current speed of the transportable More...
 
std::string getStageSummary (int stageIndex) const
 return textual summary for the given stage More...
 
MSStageType getStageType (int next) const
 the stage type for the nth next stage More...
 
const std::set< NumericalIDgetUpcomingEdgeIDs () const
 returns the numerical IDs of edges to be used (possibly of future stages) More...
 
SUMOVehiclegetVehicle () const
 The vehicle associated with this transportable. More...
 
const MSVehicleTypegetVehicleType () const
 Returns the object's "vehicle" type. More...
 
virtual double getWaitingSeconds () const
 the time this transportable spent waiting in seconds More...
 
bool hasArrived () const
 return whether the person has reached the end of its plan More...
 
bool hasDeparted () const
 return whether the transportable has started its plan More...
 
bool hasInfluencer () const
 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...
 
bool isJammed () const
 whether the person is jammed as defined by the current pedestrian model More...
 
virtual bool isSelected () const
 whether this person is selected in the GUI More...
 
virtual bool isVehicle () const
 Whether it is a vehicle. More...
 
bool isWaiting4Vehicle () const
 Whether the transportable waits for a vehicle. More...
 
bool isWaitingFor (const SUMOVehicle *vehicle) const
 Whether the transportable waits for the given vehicle in the current step. More...
 
void loadState (const std::string &state)
 Reconstructs the current state. More...
 
 MSPerson (const SUMOVehicleParameter *pars, MSVehicleType *vtype, MSTransportable::MSTransportablePlan *plan, const double speedFactor)
 constructor More...
 
virtual bool proceed (MSNet *net, SUMOTime time, const bool vehicleArrived=false)
 
void removeStage (int next, bool stayInSim=true)
 removes the nth next stage More...
 
bool replaceRoute (ConstMSRoutePtr route, const std::string &info, bool onInit=false, int offset=0, bool addStops=true, bool removeStops=true, std::string *msgReturn=nullptr)
 Replaces the current route by the given one. More...
 
void replaceVehicleType (MSVehicleType *type)
 Replaces the current vehicle type by the one given. More...
 
void reroute (const ConstMSEdgeVector &newEdges, double departPos, int firstIndex, int nextIndex)
 set new walk and replace the stages with relative indices in the interval [firstIndex, nextIndex[ More...
 
void rerouteParkingArea (MSStoppingPlace *orig, MSStoppingPlace *replacement)
 adapt plan when the vehicle reroutes and now stops at replacement instead of orig More...
 
void routeOutput (OutputDevice &os, const bool withRouteLength) const
 Called on writing vehroute output. More...
 
void saveState (OutputDevice &out)
 Saves the current state into the given stream. More...
 
void setAbortWaiting (const SUMOTime timeout)
 
void setChosenSpeedFactor (const double factor)
 
void setDeparted (SUMOTime now)
 logs depart time of the current stage More...
 
void setID (const std::string &newID)
 set the id (inherited from Named but forbidden for transportables) More...
 
void setJunctionModelParameter (const std::string &key, const std::string &value)
 set individual junction model paramete (not type related) More...
 
void setRemoteState (Position xyPos)
 sets position outside the road network More...
 
void setSpeed (double speed)
 set the speed for all present and future (walking) stages and modify the vType so that stages added later are also affected More...
 
void tripInfoOutput (OutputDevice &os) const
 Called on writing tripinfo output. More...
 
virtual ~MSPerson ()
 destructor More...
 
inherited from SUMOTrafficObject
bool isPerson () const
 Whether it is a person. More...
 
bool isContainer () const
 Whether it is a container. More...
 
std::string getObjectType ()
 
NumericalID getNumericalID () const
 return the numerical ID which is only for internal usage More...
 
bool isStopped () const
 Returns whether the object is at a stop. More...
 
double getSlope () const
 Returns the slope of the road at object's position in degrees. More...
 
SUMOVehicleClass getVClass () const
 Returns the object's access class. More...
 
double getMaxSpeed () const
 Returns the maximum speed (the minimum of desired and physical maximum speed) More...
 
SUMOTime getWaitingTime (const bool accumulated=false) const
 
double getPreviousSpeed () const
 Returns the object's previous speed. More...
 
double getAcceleration () const
 Returns the object's acceleration. More...
 
double getPositionOnLane () const
 Get the object's position along the lane. More...
 
double getBackPositionOnLane (const MSLane *lane) const
 Get the object's back position along the given lane. More...
 
Position getPosition (const double) const
 Return current position (x/y, cartesian) 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::vector< MSTransportableDevice * > myDevices
 The devices this transportable has. More...
 
std::string myID
 The name of the object. More...
 
const SUMOVehicleParametermyParameter
 the plan of the transportable More...
 
MSTransportablePlanmyPlan
 the plan of the transportable More...
 
MSTransportablePlan::iterator myStep
 the iterator over the route More...
 
MSVehicleTypemyVType
 This transportable's type. (mainly used for drawing related information Note sure if it is really necessary. More...
 
bool myWriteEvents
 Whether events shall be written. More...
 

Private Member Functions

 MSPerson (const MSPerson &)
 Invalidated copy constructor. More...
 
MSPersonoperator= (const MSPerson &)
 Invalidated assignment operator. More...
 

Private Attributes

WrappingCommand< MSTransportable > * myAbortCommand
 
const bool myAmPerson
 
double myChosenSpeedFactor
 
InfluencermyInfluencer
 An instance of a speed/position influencing instance; built in "getInfluencer". More...
 
const NumericalID myNumericalID
 

Static Private Attributes

static NumericalID myCurrentNumericalIndex = 0
 

Detailed Description

The class holds a simulated person together with her movement stages

Definition at line 61 of file MSPerson.h.

Member Typedef Documentation

◆ MSTransportablePlan

typedef std::vector<MSStage*> MSTransportable::MSTransportablePlan
inherited

the structure holding the plan of a transportable

Definition at line 119 of file MSTransportable.h.

◆ NumericalID

typedef long long int SUMOTrafficObject::NumericalID
inherited

Definition at line 54 of file SUMOTrafficObject.h.

Constructor & Destructor Documentation

◆ MSPerson() [1/2]

MSPerson::MSPerson ( const SUMOVehicleParameter pars,
MSVehicleType vtype,
MSTransportable::MSTransportablePlan plan,
const double  speedFactor 
)

constructor

Definition at line 141 of file MSPerson.cpp.

◆ ~MSPerson()

MSPerson::~MSPerson ( )
virtual

destructor

Definition at line 148 of file MSPerson.cpp.

References myInfluencer.

◆ MSPerson() [2/2]

MSPerson::MSPerson ( const MSPerson )
private

Invalidated copy constructor.

Member Function Documentation

◆ abortStage()

SUMOTime MSTransportable::abortStage ( SUMOTime  step)
inherited

Abort current stage (used for aborting waiting for a vehicle)

Definition at line 297 of file MSTransportable.cpp.

References MSTransportableControl::erase(), MSNet::getContainerControl(), Named::getID(), MSNet::getInstance(), MSNet::getPersonControl(), MSTransportable::isPerson(), MSTransportable::proceed(), MSTransportableControl::registerTeleportAbortWait(), time2string(), TL, and WRITE_WARNINGF.

Referenced by MSTransportable::setAbortWaiting().

Here is the caller graph for this function:

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

◆ appendStage()

void MSTransportable::appendStage ( MSStage stage,
int  next = -1 
)
inherited

◆ checkAccess()

◆ getAcceleration()

double MSTransportable::getAcceleration ( ) const
inlinevirtualinherited

Returns the object's acceleration.

Returns
The acceleration

Implements SUMOTrafficObject.

Definition at line 103 of file MSTransportable.h.

◆ getAngle()

double MSTransportable::getAngle ( ) const
virtualinherited

return the current angle of the transportable

Implements SUMOTrafficObject.

Reimplemented in GUIContainer.

Definition at line 195 of file MSTransportable.cpp.

References MSNet::getCurrentTimeStep(), and MSNet::getInstance().

Referenced by GUIContainer::getAngle(), MSTransportable::getBoundingBox(), MSLink::getFuturePosition(), GUIPerson::getGUIAngle(), GUIPerson::getNaviDegree(), MSLink::isOnComingPed(), GUIPerson::setFunctionalColor(), MSFCDExport::writeTransportable(), and MSXMLRawOut::writeTransportable().

Here is the caller graph for this function:

◆ getArrivalEdge()

const MSEdge* MSTransportable::getArrivalEdge ( ) const
inlineinherited

returns the final arrival edge

Definition at line 320 of file MSTransportable.h.

References MSTransportable::myPlan.

Referenced by LIBSUMO_NAMESPACE::Person::appendWaitingStage(), LIBSUMO_NAMESPACE::Person::convertTraCIStage(), and MSTransportable::getRerouteDestination().

Here is the caller graph for this function:

◆ getArrivalPos()

double MSTransportable::getArrivalPos ( ) const
inlineinherited

returns the final arrival pos

Definition at line 315 of file MSTransportable.h.

References MSTransportable::myPlan.

Referenced by LIBSUMO_NAMESPACE::Person::appendWaitingStage(), LIBSUMO_NAMESPACE::Person::appendWalkingStage(), LIBSUMO_NAMESPACE::Person::convertTraCIStage(), and GUIContainer::getParameterWindow().

Here is the caller graph for this function:

◆ getBackPositionOnLane()

double MSTransportable::getBackPositionOnLane ( const MSLane lane) const
virtualinherited

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

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

Implements SUMOTrafficObject.

Definition at line 180 of file MSTransportable.cpp.

References MSTransportable::getEdgePos(), MSVehicleType::getLength(), and MSTransportable::getVehicleType().

◆ getBoundingBox()

◆ getChosenSpeedFactor()

double MSPerson::getChosenSpeedFactor ( ) const
inlinevirtual

the current speed factor of the transportable (where applicable)

Reimplemented from MSTransportable.

Definition at line 154 of file MSPerson.h.

References myChosenSpeedFactor.

Referenced by GUIPerson::getParameterWindow(), and GUISUMOViewParent::onUpdSpeedFactor().

Here is the caller graph for this function:

◆ getCurrentStage()

◆ getCurrentStageDescription()

std::string MSTransportable::getCurrentStageDescription ( ) const
inlineinherited

Returns the current stage description as a string.

Definition at line 227 of file MSTransportable.h.

References MSTransportable::myAmPerson.

Referenced by GUIContainer::getParameterWindow(), GUIPerson::getParameterWindow(), LIBSUMO_NAMESPACE::Person::moveTo(), LIBSUMO_NAMESPACE::Person::moveToXY(), and MSXMLRawOut::writeTransportable().

Here is the caller graph for this function:

◆ getCurrentStageIndex()

int MSTransportable::getCurrentStageIndex ( ) const
inlineinherited

Return the index of the current stage.

Definition at line 257 of file MSTransportable.h.

References MSTransportable::myPlan, and MSTransportable::myStep.

Referenced by MSPModel_JuPedSim::add(), GUIContainer::getParameterWindow(), GUIPerson::getStageIndexDescription(), MSStageDriving::proceed(), and MSStageTrip::setArrived().

Here is the caller graph for this function:

◆ getCurrentStageType()

MSStageType MSTransportable::getCurrentStageType ( ) const
inlineinherited

◆ getDeparture()

SUMOTime MSTransportable::getDeparture ( ) const
inherited

logs depart time of the current stage

Definition at line 164 of file MSTransportable.cpp.

References MSTransportable::myPlan.

Referenced by MSTransportableControl::erase().

Here is the caller graph for this function:

◆ getDesiredDepart()

SUMOTime MSTransportable::getDesiredDepart ( ) const
inherited

Returns the desired departure time.

Definition at line 154 of file MSTransportable.cpp.

References SUMOVehicleParameter::depart, and MSTransportable::myParameter.

Referenced by MSTransportable::tripInfoOutput().

Here is the caller graph for this function:

◆ getDestination()

const MSEdge* MSTransportable::getDestination ( ) const
inlineinherited

Returns the current destination.

Definition at line 164 of file MSTransportable.h.

Referenced by MSStageDriving::canLeaveVehicle(), GUIPerson::getDestinationEdgeID(), GUIContainer::getParameterWindow(), MSDevice_Transportable::notifyLeave(), and MSTransportable::rerouteParkingArea().

Here is the caller graph for this function:

◆ getDevice()

MSDevice * MSTransportable::getDevice ( const std::type_info &  type) const
virtualinherited

Returns a device of the given type if it exists or nullptr if not.

Implements SUMOTrafficObject.

Definition at line 530 of file MSTransportable.cpp.

References MSTransportable::myDevices.

Referenced by MSDevice_FCDReplay::FCDHandler::addTrafficObjects(), MSDevice_BTreceiver::BTreceiverUpdate::execute(), and MSFCDExport::hasOwnOutput().

Here is the caller graph for this function:

◆ getDevices()

const std::vector<MSTransportableDevice*>& MSTransportable::getDevices ( ) const
inlineinherited

Returns this vehicle's devices.

Returns
This vehicle's devices

Definition at line 375 of file MSTransportable.h.

References MSTransportable::myDevices.

◆ getDirection()

int MSTransportable::getDirection ( ) const
virtualinherited

Return the movement directon on the edge.

Reimplemented in GUIPerson, and GUIContainer.

Definition at line 185 of file MSTransportable.cpp.

Referenced by MSE3Collector::enter(), GUIContainer::getDirection(), GUIPerson::getDirection(), MSE3Collector::leave(), and MSE3Collector::MSE3EntryReminder::notifyMove().

Here is the caller graph for this function:

◆ getEdge()

◆ getEdgePos()

◆ getFromEdge()

const MSEdge* MSTransportable::getFromEdge ( ) const
inlineinherited

Returns the departure edge.

Definition at line 184 of file MSTransportable.h.

Referenced by GUIPerson::getFromEdgeID(), and GUIContainer::getParameterWindow().

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(), MSDevice_StationFinder::findChargingStation(), 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_StationFinder::generateOutput(), 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(), 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(), 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_StationFinder::MSDevice_StationFinder(), 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(), reroute(), MSBaseVehicle::reroute(), MSRailSignal::LinkInfo::reroute(), GUIVehicle::rerouteDRTStop(), MSTriggeredRerouter::rerouteParkingArea(), 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(), 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(), 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(), 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().

◆ getImpatience()

double MSPerson::getImpatience ( ) const

◆ getInfluencer() [1/2]

MSPerson::Influencer & MSPerson::getInfluencer ( )

Returns the velocity/lane influencer.

If no influencer was existing before, one is built, first

Returns
Reference to this vehicle's speed influencer

Definition at line 275 of file MSPerson.cpp.

References myInfluencer.

Referenced by MSStageWalking::moveToNextEdge(), and libsumo::Helper::setRemoteControlled().

Here is the caller graph for this function:

◆ getInfluencer() [2/2]

const MSPerson::Influencer * MSPerson::getInfluencer ( ) const

Definition at line 284 of file MSPerson.cpp.

References myInfluencer.

◆ getLane()

const MSLane* MSTransportable::getLane ( ) const
inlinevirtualinherited

Returns the current lane (may be nullptr)

Implements SUMOTrafficObject.

Definition at line 179 of file MSTransportable.h.

Referenced by LIBSUMO_NAMESPACE::TrafficLight::getServedPersonCount(), and MSPerson::MSPersonStage_Access::proceed().

Here is the caller graph for this function:

◆ getMaxSpeed()

double MSTransportable::getMaxSpeed ( ) const
virtualinherited

Returns the maximum speed (the minimum of desired and physical maximum speed)

Returns
The objects's maximum speed

Implements SUMOTrafficObject.

Definition at line 568 of file MSTransportable.cpp.

References MSTransportable::getChosenSpeedFactor(), MSTransportable::getVehicleType(), and MIN2().

Referenced by LIBSUMO_NAMESPACE::Person::appendWalkingStage(), MSLink::checkWalkingAreaFoe(), LIBSUMO_NAMESPACE::Person::convertTraCIStage(), MSPModel_JuPedSim::execute(), MSLink::getFuturePosition(), MSStageWalking::getMaxSpeed(), MSPModel_Striping::nextBlocking(), MSPerson::MSPersonStage_Access::proceed(), LIBSUMO_NAMESPACE::Person::rerouteTraveltime(), MSStageTrip::setArrived(), and MSPModel_JuPedSim::tryPedestrianInsertion().

Here is the caller graph for this function:

◆ getNextDestination()

const MSEdge* MSTransportable::getNextDestination ( ) const
inlineinherited

Returns the destination after the current destination.

Definition at line 169 of file MSTransportable.h.

References MSTransportable::myStep.

◆ getNextEdge()

const std::string & MSPerson::getNextEdge ( ) const

return the list of internal edges if this person is walking and the pedestrian model allows it

Definition at line 215 of file MSPerson.cpp.

References StringUtils::emptyString, Named::getID(), and getNextEdgePtr().

Referenced by LIBSUMO_NAMESPACE::TrafficLight::getServedPersonCount().

Here is the caller graph for this function:

◆ getNextEdgePtr()

const MSEdge * MSPerson::getNextEdgePtr ( ) const
virtual

returns the next edge ptr if this person is walking and the pedestrian model allows it

Reimplemented from MSTransportable.

Definition at line 234 of file MSPerson.cpp.

References MSTransportable::getCurrentStageType(), MSTransportableStateAdapter::getNextEdge(), MSStageMoving::getPState(), and WALKING.

Referenced by getNextEdge(), and MSPedestrianPushButton::isActiveForEdge().

Here is the caller graph for this function:

◆ getNextStage()

MSStage* MSTransportable::getNextStage ( int  offset) const
inlineinherited

Return the next (or previous) stage denoted by the offset.

Definition at line 237 of file MSTransportable.h.

References MSTransportable::myPlan, and MSTransportable::myStep.

Referenced by MSPModel_JuPedSim::add(), LIBSUMO_NAMESPACE::Person::getEdges(), LIBSUMO_NAMESPACE::Person::getStage(), MSStageDriving::init(), MSStageDriving::loadState(), reroute(), LIBSUMO_NAMESPACE::Person::rerouteTraveltime(), MSStageTrip::setArrived(), MSDevice_Transportable::transferAtSplitOrJoin(), and MSDevice_Transportable::willTransferAtJoin().

Here is the caller graph for this function:

◆ getNumericalID()

NumericalID MSTransportable::getNumericalID ( ) const
inlinevirtualinherited

return the numerical ID which is only for internal usage

Implements SUMOTrafficObject.

Definition at line 75 of file MSTransportable.h.

References MSTransportable::myNumericalID.

◆ getNumRemainingStages()

int MSTransportable::getNumRemainingStages ( ) const
inlineinherited

◆ getNumStages()

int MSTransportable::getNumStages ( ) const
inlineinherited

Return the total number stages in this person's plan.

Definition at line 247 of file MSTransportable.h.

References MSTransportable::myPlan.

Referenced by LIBSUMO_NAMESPACE::Person::getEdges(), GUIContainer::getParameterWindow(), LIBSUMO_NAMESPACE::Person::getStage(), GUIPerson::getStageIndexDescription(), GUIContainer::GUIContainerPopupMenu::onCmdShowPlan(), GUIPerson::GUIPersonPopupMenu::onCmdShowPlan(), and MSStageTrip::setArrived().

Here is the caller graph for this function:

◆ getObjectType()

std::string MSTransportable::getObjectType ( )
inlineinherited

Definition at line 71 of file MSTransportable.h.

References MSTransportable::myAmPerson.

Referenced by MSTransportableControl::abortAnyWaitingForVehicle(), and MSTransportable::setJunctionModelParameter().

Here is the caller graph for this function:

◆ getParameter()

◆ getPosition() [1/2]

Position MSTransportable::getPosition ( ) const
virtualinherited

Return the Network coordinate of the transportable.

Reimplemented in GUIPerson, and GUIContainer.

Definition at line 190 of file MSTransportable.cpp.

References MSNet::getCurrentTimeStep(), and MSNet::getInstance().

Referenced by MSTransportable::getBoundingBox(), GUIPerson::getGUIPosition(), GUIContainer::getPosition(), GUIPerson::getPosition(), and MSTransportable::getPosition().

Here is the caller graph for this function:

◆ getPosition() [2/2]

Position MSTransportable::getPosition ( const double  offset) const
inlinevirtualinherited

Return current position (x/y, cartesian)

If the object is not in the net, Position::INVALID.

Parameters
[in]offsetoptional offset in longitudinal direction
Returns
The current position (in cartesian coordinates)
See also
myLane

Implements SUMOTrafficObject.

Definition at line 113 of file MSTransportable.h.

References MSTransportable::getPosition().

Referenced by MSStageWalking::activateEntryReminders(), MSLink::checkWalkingAreaFoe(), MSLink::getFuturePosition(), MSLink::isOnComingPed(), MSPModel_Striping::PState::moveTo(), LIBSUMO_NAMESPACE::Person::moveToXY(), and MSFCDExport::writeTransportable().

Here is the caller graph for this function:

◆ getPositionOnLane()

double MSTransportable::getPositionOnLane ( ) const
inlinevirtualinherited

Get the object's position along the lane.

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

Implements SUMOTrafficObject.

Definition at line 107 of file MSTransportable.h.

References MSTransportable::getEdgePos().

Referenced by MSDevice_BTreceiver::BTreceiverUpdate::execute(), MSStageWalking::moveToNextEdge(), and MSTransportable::replaceRoute().

Here is the caller graph for this function:

◆ getPreviousSpeed()

double MSTransportable::getPreviousSpeed ( ) const
inlinevirtualinherited

Returns the object's previous speed.

Returns
The object's previous speed

Implements SUMOTrafficObject.

Definition at line 99 of file MSTransportable.h.

References MSTransportable::getSpeed().

◆ getRerouteDestination()

const MSEdge* MSTransportable::getRerouteDestination ( ) const
inlinevirtualinherited

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

Returns
The rerouting end point

Implements SUMOTrafficObject.

Definition at line 328 of file MSTransportable.h.

References MSTransportable::getArrivalEdge().

◆ getRNG()

SumoRNG * MSTransportable::getRNG ( ) const
virtualinherited

returns the associated RNG

Implements SUMOTrafficObject.

Definition at line 91 of file MSTransportable.cpp.

References MSTransportable::getEdge(), and MSEdge::getLanes().

◆ getRNGIndex()

int MSTransportable::getRNGIndex ( ) const
virtualinherited

returns the index of the associated RNG

Implements SUMOTrafficObject.

Definition at line 96 of file MSTransportable.cpp.

References MSTransportable::getEdge(), and MSEdge::getLanes().

◆ getRoutePosition()

int MSTransportable::getRoutePosition ( ) const
inlinevirtualinherited

return the index of the edge within the route

Implements SUMOTrafficObject.

Definition at line 262 of file MSTransportable.h.

Referenced by MSDetectorFileOutput::vehicleApplies().

Here is the caller graph for this function:

◆ getRoutingMode()

int MSTransportable::getRoutingMode ( ) const
virtualinherited

return routing mode (configures router choice but also handling of transient permission changes)

Todo:
: allow configuring routing mode

Implements SUMOTrafficObject.

Definition at line 580 of file MSTransportable.cpp.

References libsumo::ROUTING_MODE_DEFAULT.

◆ getSingularType()

MSVehicleType & MSTransportable::getSingularType ( )
inherited

Replaces the current vehicle type with a new one used by this vehicle only.

If the currently used vehicle type is already marked as being used by this vehicle only, no new type is created.

Returns
The new modifiable vehicle type
See also
MSTransportable::myVType

Definition at line 386 of file MSTransportable.cpp.

References MSVehicleType::buildSingularType(), MSVehicleType::getID(), Named::getID(), MSVehicleType::isVehicleSpecific(), MSTransportable::myVType, and MSTransportable::replaceVehicleType().

Referenced by MSDevice_FCDReplay::FCDHandler::addTrafficObjects(), TraCIServerAPI_Person::processSet(), and MSTransportable::setSpeed().

Here is the caller graph for this function:

◆ getSlope()

double MSTransportable::getSlope ( ) const
virtualinherited

Returns the slope of the road at object's position in degrees.

Returns
The slope

Implements SUMOTrafficObject.

Definition at line 553 of file MSTransportable.cpp.

References MSTransportable::getEdge(), MSTransportable::getEdgePos(), and MSEdge::getLanes().

◆ getSpeed()

double MSTransportable::getSpeed ( ) const
virtualinherited

the current speed of the transportable

Implements SUMOTrafficObject.

Reimplemented in GUIPerson, and GUIContainer.

Definition at line 205 of file MSTransportable.cpp.

Referenced by MSDevice_BTreceiver::BTreceiverUpdate::execute(), MSTransportable::getPreviousSpeed(), GUIContainer::getSpeed(), GUIPerson::getSpeed(), MSE2Collector::notifyMovePerson(), MSInductLoop::notifyMovePerson(), MSE3Collector::notifyMovePerson(), and MSFCDExport::writeTransportable().

Here is the caller graph for this function:

◆ getStageSummary()

std::string MSTransportable::getStageSummary ( int  stageIndex) const
inherited

return textual summary for the given stage

Definition at line 415 of file MSTransportable.cpp.

References MSTransportable::myAmPerson, and MSTransportable::myPlan.

Referenced by GUIContainer::GUIContainerPopupMenu::onCmdShowPlan(), and GUIPerson::GUIPersonPopupMenu::onCmdShowPlan().

Here is the caller graph for this function:

◆ getStageType()

MSStageType MSTransportable::getStageType ( int  next) const
inlineinherited

the stage type for the nth next stage

Definition at line 217 of file MSTransportable.h.

References MSTransportable::myPlan, and MSTransportable::myStep.

Referenced by GUIPerson::getStopDuration(), LIBSUMO_NAMESPACE::Person::moveTo(), LIBSUMO_NAMESPACE::Person::moveToXY(), MSPerson::Influencer::postProcessRemoteControl(), and LIBSUMO_NAMESPACE::Person::rerouteTraveltime().

Here is the caller graph for this function:

◆ getUpcomingEdgeIDs()

const std::set< SUMOTrafficObject::NumericalID > MSTransportable::getUpcomingEdgeIDs ( ) const
virtualinherited

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

Implements SUMOTrafficObject.

Definition at line 423 of file MSTransportable.cpp.

References MSTransportable::myPlan, and MSTransportable::myStep.

◆ getVClass()

SUMOVehicleClass MSTransportable::getVClass ( ) const
virtualinherited

Returns the object's access class.

Returns
The object's access class

Implements SUMOTrafficObject.

Definition at line 574 of file MSTransportable.cpp.

References MSVehicleType::getVehicleClass(), and MSTransportable::getVehicleType().

Referenced by MSPModel_Striping::add(), MSPModel_JuPedSim::execute(), MSPModel_Striping::getNextLane(), LIBSUMO_NAMESPACE::Person::moveToXY(), and MSPModel_Striping::PState::moveToXY().

Here is the caller graph for this function:

◆ getVehicle()

SUMOVehicle* MSTransportable::getVehicle ( ) const
inlineinherited

The vehicle associated with this transportable.

Definition at line 301 of file MSTransportable.h.

Referenced by MSDetectorFileOutput::personApplies().

Here is the caller graph for this function:

◆ getVehicleType()

◆ getWaitingSeconds()

double MSTransportable::getWaitingSeconds ( ) const
virtualinherited

the time this transportable spent waiting in seconds

Reimplemented in GUIPerson, and GUIContainer.

Definition at line 200 of file MSTransportable.cpp.

References MSNet::getCurrentTimeStep(), MSNet::getInstance(), and STEPS2TIME.

Referenced by GUIContainer::getWaitingSeconds(), GUIPerson::getWaitingSeconds(), and MSPedestrianPushButton::isActiveForEdge().

Here is the caller graph for this function:

◆ getWaitingTime()

SUMOTime MSTransportable::getWaitingTime ( const bool  accumulated = false) const
virtualinherited

Implements SUMOTrafficObject.

Definition at line 562 of file MSTransportable.cpp.

References MSNet::getCurrentTimeStep(), and MSNet::getInstance().

◆ hasArrived()

◆ hasDeparted()

bool MSTransportable::hasDeparted ( ) const
inherited

return whether the transportable has started its plan

Definition at line 440 of file MSTransportable.cpp.

References MSTransportable::myPlan, and MSTransportable::myStep.

Referenced by MSTransportableControl::fixLoadCount(), and MSTransportableDevice_FCDReplay::move().

Here is the caller graph for this function:

◆ hasInfluencer()

bool MSPerson::hasInfluencer ( ) const
inlinevirtual

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

Reimplemented from MSTransportable.

Definition at line 219 of file MSPerson.h.

References myInfluencer.

Referenced by MSStageWalking::moveToNextEdge().

Here is the caller graph for this function:

◆ ignoreTransientPermissions()

virtual bool SUMOTrafficObject::ignoreTransientPermissions ( ) const
inlinevirtualinherited

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

bool MSTransportable::isContainer ( ) const
inlinevirtualinherited

Whether it is a container.

Returns
true for containers, false otherwise

Reimplemented from SUMOTrafficObject.

Definition at line 67 of file MSTransportable.h.

References MSTransportable::myAmPerson.

Referenced by MSTransportable::routeOutput().

Here is the caller graph for this function:

◆ isJammed()

bool MSPerson::isJammed ( ) const
virtual

whether the person is jammed as defined by the current pedestrian model

Reimplemented from MSTransportable.

Definition at line 185 of file MSStageWalking.cpp.

References MSTransportable::getCurrentStage(), MSStageMoving::getPState(), and MSTransportableStateAdapter::isJammed().

Referenced by GUIPerson::getColorValue().

Here is the caller graph for this function:

◆ isPerson()

◆ isSelected()

virtual bool MSPerson::isSelected ( ) const
inlinevirtual

whether this person is selected in the GUI

Reimplemented from MSTransportable.

Reimplemented in GUIPerson.

Definition at line 150 of file MSPerson.h.

◆ isStopped()

bool MSTransportable::isStopped ( ) const
inlinevirtualinherited

Returns whether the object is at a stop.

Returns
Whether it has stopped

Implements SUMOTrafficObject.

Definition at line 79 of file MSTransportable.h.

References MSTransportable::getCurrentStageType(), and WAITING.

◆ isVehicle()

◆ isWaiting4Vehicle()

bool MSTransportable::isWaiting4Vehicle ( ) const
inlineinherited

Whether the transportable waits for a vehicle.

Definition at line 291 of file MSTransportable.h.

Referenced by GUIContainer::drawGL(), GUIContainer::getColorValue(), GUIPerson::getColorValue(), GUIPerson::getGUIAngle(), and GUIPerson::getGUIPosition().

Here is the caller graph for this function:

◆ isWaitingFor()

bool MSTransportable::isWaitingFor ( const SUMOVehicle vehicle) const
inlineinherited

Whether the transportable waits for the given vehicle in the current step.

Definition at line 286 of file MSTransportable.h.

Referenced by MSEdge::getWaitingVehicle(), MSTransportableControl::hasAnyWaiting(), and MSTransportableControl::loadAnyWaiting().

Here is the caller graph for this function:

◆ loadState()

void MSTransportable::loadState ( const std::string &  state)
inherited

Reconstructs the current state.

Definition at line 616 of file MSTransportable.cpp.

References MSTransportable::myParameter, MSTransportable::myPlan, MSTransportable::myStep, and SUMOVehicleParameter::parametersSet.

Referenced by MSStateHandler::myEndElement().

Here is the caller graph for this function:

◆ operator=()

MSPerson& MSPerson::operator= ( const MSPerson )
private

Invalidated assignment operator.

◆ proceed()

◆ removeStage()

void MSTransportable::removeStage ( int  next,
bool  stayInSim = true 
)
inherited

◆ replaceRoute()

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

Replaces the current route by the given one.

Implements SUMOTrafficObject.

Definition at line 360 of file MSTransportable.cpp.

References MSTransportable::getPositionOnLane(), and MSTransportable::isPerson().

◆ replaceVehicleType()

void MSTransportable::replaceVehicleType ( MSVehicleType type)
virtualinherited

Replaces the current vehicle type by the one given.

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

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

Implements SUMOTrafficObject.

Definition at line 370 of file MSTransportable.cpp.

References MSVehicleType::getID(), Named::getID(), MSNet::getInstance(), MSVehicleType::getParameter(), MSVehicleType::getVehicleClass(), MSNet::getVehicleControl(), MSTransportable::isPerson(), MSVehicleType::isVehicleSpecific(), MSTransportable::myVType, MSVehicleControl::removeVType(), SVC_PEDESTRIAN, TL, toString(), VTYPEPARS_VEHICLECLASS_SET, SUMOVTypeParameter::wasSet(), and WRITE_WARNINGF.

Referenced by MSTransportable::getSingularType().

Here is the caller graph for this function:

◆ reroute()

void MSPerson::reroute ( const ConstMSEdgeVector newEdges,
double  departPos,
int  firstIndex,
int  nextIndex 
)

set new walk and replace the stages with relative indices in the interval [firstIndex, nextIndex[

Definition at line 246 of file MSPerson.cpp.

References MSTransportable::appendStage(), MSStage::getArrivalPos(), MSStage::getDestination(), MSStage::getDestinationStop(), Named::getID(), MSTransportable::getNextStage(), MSTransportable::removeStage(), and MSPModel::UNSPECIFIED_POS_LAT.

Referenced by LIBSUMO_NAMESPACE::Person::rerouteTraveltime().

Here is the caller graph for this function:

◆ rerouteParkingArea()

◆ routeOutput()

void MSTransportable::routeOutput ( OutputDevice os,
const bool  withRouteLength 
) const
inherited

◆ saveState()

◆ setAbortWaiting()

void MSTransportable::setAbortWaiting ( const SUMOTime  timeout)
inherited

Definition at line 285 of file MSTransportable.cpp.

References MSTransportable::abortStage(), MSEventControl::addEvent(), WrappingCommand< T >::deschedule(), MSNet::getBeginOfTimestepEvents(), MSNet::getInstance(), MSTransportable::myAbortCommand, and SIMSTEP.

Referenced by MSTransportableControl::abortAnyWaitingForVehicle(), MSTransportableControl::addWaiting(), and MSTransportableControl::loadAnyWaiting().

Here is the caller graph for this function:

◆ setChosenSpeedFactor()

void MSPerson::setChosenSpeedFactor ( const double  factor)
inline

Definition at line 158 of file MSPerson.h.

References myChosenSpeedFactor.

◆ setDeparted()

void MSTransportable::setDeparted ( SUMOTime  now)
inherited

logs depart time of the current stage

Definition at line 159 of file MSTransportable.cpp.

◆ setID()

void MSTransportable::setID ( const std::string &  newID)
virtualinherited

set the id (inherited from Named but forbidden for transportables)

Reimplemented from Named.

Definition at line 149 of file MSTransportable.cpp.

References TL.

◆ setJunctionModelParameter()

void MSTransportable::setJunctionModelParameter ( const std::string &  key,
const std::string &  value 
)
inherited

◆ setRemoteState()

void MSPerson::setRemoteState ( Position  xyPos)

sets position outside the road network

◆ setSpeed()

void MSTransportable::setSpeed ( double  speed)
inherited

set the speed for all present and future (walking) stages and modify the vType so that stages added later are also affected

Definition at line 351 of file MSTransportable.cpp.

References MSTransportable::getSingularType(), MSTransportable::myPlan, MSTransportable::myStep, and MSVehicleType::setMaxSpeed().

◆ tripInfoOutput()

void MSTransportable::tripInfoOutput ( OutputDevice os) const
inherited

Called on writing tripinfo output.

Parameters
[in]osThe stream to write the information into
Exceptions
IOErrornot yet implemented

Definition at line 211 of file MSTransportable.cpp.

References OutputDevice::closeTag(), MSTransportable::getChosenSpeedFactor(), MSTransportable::getDesiredDepart(), Named::getID(), MSTransportable::getVehicleType(), MSTransportable::isPerson(), MSTransportable::myPlan, OutputDevice::openTag(), SUMO_ATTR_DEPART, SUMO_ATTR_DURATION, SUMO_ATTR_ID, SUMO_ATTR_SPEEDFACTOR, SUMO_ATTR_TIMELOSS, SUMO_ATTR_TRAVELTIME, SUMO_ATTR_TYPE, SUMO_ATTR_WAITINGTIME, SUMOTime_MAX, time2string(), and OutputDevice::writeAttr().

Referenced by MSTransportableControl::erase().

Here is the caller graph for this function:

Field Documentation

◆ myAbortCommand

WrappingCommand<MSTransportable>* MSTransportable::myAbortCommand
privateinherited

Definition at line 424 of file MSTransportable.h.

Referenced by MSTransportable::setAbortWaiting().

◆ myAmPerson

◆ myChosenSpeedFactor

double MSPerson::myChosenSpeedFactor
private

Definition at line 230 of file MSPerson.h.

Referenced by getChosenSpeedFactor(), and setChosenSpeedFactor().

◆ myCurrentNumericalIndex

SUMOTrafficObject::NumericalID MSTransportable::myCurrentNumericalIndex = 0
staticprivateinherited

Definition at line 426 of file MSTransportable.h.

◆ myDevices

std::vector<MSTransportableDevice*> MSTransportable::myDevices
protectedinherited

◆ myID

std::string Named::myID
protectedinherited

◆ myInfluencer

Influencer* MSPerson::myInfluencer
private

An instance of a speed/position influencing instance; built in "getInfluencer".

Definition at line 228 of file MSPerson.h.

Referenced by getInfluencer(), hasInfluencer(), and ~MSPerson().

◆ myNumericalID

const NumericalID MSTransportable::myNumericalID
privateinherited

Definition at line 422 of file MSTransportable.h.

Referenced by MSTransportable::getNumericalID().

◆ myParameter

◆ myPlan

◆ myStep

◆ myVType

MSVehicleType* MSTransportable::myVType
protectedinherited

This transportable's type. (mainly used for drawing related information Note sure if it is really necessary.

Definition at line 405 of file MSTransportable.h.

Referenced by MSTransportable::getSingularType(), GUIContainer::getTypeParameterWindow(), GUIPerson::getTypeParameterWindow(), MSTransportable::getVehicleType(), MSTransportable::replaceVehicleType(), and MSTransportable::~MSTransportable().

◆ myWriteEvents

bool MSTransportable::myWriteEvents
protectedinherited

Whether events shall be written.

Definition at line 408 of file MSTransportable.h.


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