Eclipse SUMO - Simulation of Urban MObility
Loading...
Searching...
No Matches
StdDefs.h File Reference
#include <config.h>
#include <string>
#include <cmath>
#include <limits>
Include dependency graph for StdDefs.h:

Go to the source code of this file.

Macros

#define DEBUGOUT(cond, msg)   if (cond) {std::ostringstream oss; oss << msg; std::cout << oss.str();}
 
#define FALLTHROUGH   /* do nothing */
 
#define SUMO_MAX_CONNECTIONS   256
 the maximum number of connections across an intersection
 
#define UNUSED_PARAMETER(x)   ((void)(x))
 

Typedefs

typedef std::pair< int, double > MMVersion
 (M)ajor/(M)inor version for written networks and default version for loading
 

Functions

int getScalingQuota (double frac, int loaded)
 Returns the number of instances of the current object that shall be emitted given the number of loaded objects considering that "frac" of all objects shall be emitted overall.
 
template<typename T >
MAX2 (T a, T b)
 
template<typename T >
MAX3 (T a, T b, T c)
 
template<typename T >
MAX4 (T a, T b, T c, T d)
 
template<typename T >
MIN2 (T a, T b)
 
template<typename T >
MIN3 (T a, T b, T c)
 
template<typename T >
MIN4 (T a, T b, T c, T d)
 
const MMVersion NETWORK_VERSION (1, 20)
 
double roundBits (double x, int fractionBits)
 round to the given number of mantissa bits beyond the given number
 
double roundDecimal (double x, int precision)
 round to the given number of decimal digits
 
double roundDecimalToEven (double x, int precision)
 round to the given number of decimal digits (bankers rounding)
 
double truncate (double x, int fractionBits)
 discrds mantissa bits beyond the given number
 

Variables

bool gDebugFlag1
 global utility flags for debugging
 
bool gDebugFlag2
 
bool gDebugFlag3
 
bool gDebugFlag4
 
bool gDebugFlag5
 
bool gDebugFlag6
 
bool gHumanReadableTime
 
bool gIgnoreUnknownVClass
 
std::string gLanguage
 the language for GUI elements and messages
 
bool gLocaleInitialized
 
int gPrecision
 the precision for floating point outputs
 
int gPrecisionEmissions
 
int gPrecisionGeo
 
int gPrecisionRandom
 
bool gRoutingPreferences
 
bool gSimulation
 
int GUIDesignDialogButtonsHeight
 the default height for dialog buttons
 
int GUIDesignHeight
 the default height for GUI elements
 
double gWeightsRandomFactor
 
double gWeightsWalkOppositeFactor
 
const double INVALID_DOUBLE = std::numeric_limits<double>::max()
 invalid double
 
const int INVALID_INT = std::numeric_limits<int>::max()
 invalid int
 
const double SUMO_const_halfLaneWidth = SUMO_const_laneWidth / 2
 
const double SUMO_const_haltingSpeed = (double) 0.1
 the speed threshold at which vehicles are considered as halting
 
const double SUMO_const_laneMarkWidth = 0.1
 
const double SUMO_const_laneWidth = 3.2
 
const double SUMO_const_quarterLaneWidth = SUMO_const_laneWidth / 4
 
const double SUMO_const_waitingContainerDepth = 6.2
 
const double SUMO_const_waitingContainerWidth = 2.5
 
const double SUMO_const_waitingPersonDepth = 0.67
 
const double SUMO_const_waitingPersonWidth = 0.8
 

Detailed Description

Author
Daniel Krajzewicz
Laura Bieker
Michael Behrisch
Jakob Erdmann
Date
Fri, 29.04.2005

Definition in file StdDefs.h.

Macro Definition Documentation

◆ DEBUGOUT

#define DEBUGOUT (   cond,
  msg 
)    if (cond) {std::ostringstream oss; oss << msg; std::cout << oss.str();}

Definition at line 150 of file StdDefs.h.

◆ FALLTHROUGH

#define FALLTHROUGH   /* do nothing */

Definition at line 39 of file StdDefs.h.

◆ SUMO_MAX_CONNECTIONS

#define SUMO_MAX_CONNECTIONS   256

the maximum number of connections across an intersection

Definition at line 45 of file StdDefs.h.

◆ UNUSED_PARAMETER

#define UNUSED_PARAMETER (   x)    ((void)(x))

Definition at line 30 of file StdDefs.h.

Typedef Documentation

◆ MMVersion

typedef std::pair<int, double> MMVersion

(M)ajor/(M)inor version for written networks and default version for loading

Definition at line 71 of file StdDefs.h.

Function Documentation

◆ getScalingQuota()

int getScalingQuota ( double  frac,
int  loaded 
)

Returns the number of instances of the current object that shall be emitted given the number of loaded objects considering that "frac" of all objects shall be emitted overall.

Returns
the number of objects to create (something between 0 and ceil(frac))

Definition at line 72 of file StdDefs.cpp.

Referenced by MSVehicleControl::getQuota(), ROMARouteHandler::myEndElement(), and RONet::saveAndRemoveRoutesUntil().

Here is the caller graph for this function:

◆ MAX2()

template<typename T >
T MAX2 ( a,
b 
)
inline

Definition at line 86 of file StdDefs.h.

Referenced by MSRoutingEngine::_initEdgeWeights(), MSLCM_LC2013::_patchSpeed(), MSLCM_SL2015::_patchSpeed(), MSCFModel_EIDM::_v(), MSCFModel_ACC::_v(), MSCFModel_IDM::_v(), MSCFModel_CACC::_v(), MSCFModel_CC::_v(), MSCFModel_Kerner::_v(), MSCFModel_Wiedemann::_v(), MSLCM_LC2013::_wantsChange(), MSLCM_SL2015::_wantsChangeSublane(), HelpersEnergy::acceleration(), MSCFModel_ACC::accelGapControl(), MSDevice_GLOSA::adaptSpeed(), MSVehicle::adaptToJunctionLeader(), MSVehicle::adaptToLeaders(), MSVehicle::adaptToOncomingLeader(), MSVehicleTransfer::add(), GNEHelpAttributesDialog::addAttributes(), MSPModel_Striping::addCrossingVehs(), NBNode::addedLanesRight(), MSLane::addLeaders(), GUIParkingArea::addLotEntry(), MSLaneChangerSublane::addOutsideLeaders(), PublicTransportEdge< E, L, N, V >::addSchedule(), GUILane::addSecondaryShape(), MSRouteHandler::addStop(), AFCentralizedSPTree< E, N, V >::AFCentralizedSPTree(), AFRouter< E, N, V, M >::AFRouter(), AFRouter< E, N, V, M >::AFRouter(), AFRouter< E, N, V, M >::AFRouter(), MSE2Collector::aggregateOutputValues(), MSLCM_LC2013::anticipateFollowSpeed(), libsumo::Helper::applySubscriptionFilterLanes(), libsumo::Helper::applySubscriptionFilterLateralDistance(), libsumo::Helper::applySubscriptionFilters(), MSCFModel_Wiedemann::approaching(), NBEdge::assignInternalLaneLength(), AStarRouter< E, V, M >::AStarRouter(), AStarRouter< E, V, M >::AStarRouter(), IDSupplier::avoid(), MSLaneChanger::avoidDeadlock(), MSBaseVehicle::basePos(), SUMOVehicleParserHelper::beginVTypeParsing(), NBNode::bezierControlPoints(), MSCFModel_EIDM::brakeGap(), NIVisumTL::build(), GUIViewTraffic::buildColorRainbow(), GNEViewNet::buildColorRainbow(), RODFNet::buildEdgeFlowMap(), NBNode::buildInnerEdges(), NBEdge::buildInnerEdges(), GNETLSEditorFrame::buildInternalLanes(), GUISUMOAbstractView::buildMinMaxRainbow(), buildNetwork(), libsumo::Helper::buildStopParameters(), MSDevice_Routing::buildVehicleDevices(), MSDevice_Taxi::buildVehicleDevices(), NBNode::buildWalkingAreas(), MSBaseVehicle::calculateArrivalParams(), GawronCalculator< R, E, V >::calculateProbabilities(), MSE2Collector::calculateTimeLossAndTimeOnDetector(), NEMAPhase::calcVehicleExtension(), RGBColor::changedAlpha(), RGBColor::changedBrightness(), MSLaneChanger::ChangeElem::ChangeElem(), MSLaneChanger::changeOpposite(), MELoop::changeSegment(), MSPerson::checkAccess(), MSLCM_SL2015::checkBlocking(), MSLCM_SL2015::checkBlockingVehicles(), MELoop::checkCar(), MSLaneChanger::checkChange(), GUIPolygon::checkDraw(), GUIVisualizationSettings::checkDrawEdge(), GUIVisualizationSettings::checkDrawJunction(), GUIVisualizationSettings::checkDrawPOI(), GUIVisualizationSettings::checkDrawPoly(), MSDevice_ToC::checkDynamicToC(), NBEdgeCont::checkGrade(), MSVehicle::checkLinkLeader(), MSLaneChanger::checkOppositeStop(), MSFrame::checkOptions(), MSE2Collector::checkPositioning(), MSVehicle::checkReversal(), MEVehicle::checkStop(), MSTriggeredRerouter::checkStopSwitch(), MSLCM_SL2015::checkStrategicChange(), MSLink::checkWalkingAreaFoe(), GUIParameterTableWindow::closeBuilding(), MSVehicle::collisionStopTime(), MSLCM_SL2015::commitManoeuvre(), Bresenham::compute(), AFRouter< E, N, V, M >::compute(), AStarRouter< E, V, M >::compute(), HelpersHBEFA::compute(), HelpersHBEFA3::compute(), HelpersHBEFA4::compute(), HelpersPHEMlight::compute(), HelpersPHEMlight5::compute(), NBNetBuilder::compute(), NBTrafficLightDefinition::computeBrakingTime(), MSVehicleType::computeChosenSpeedDeviation(), MSDispatch::computeDetourTime(), MSDispatch_Greedy::computeDispatch(), MSDispatch_GreedyClosest::computeDispatch(), MSLink::computeDistToDivergence(), MSPModel_NonInteracting::PState::computeDuration(), MSPModel_NonInteracting::CState::computeDuration(), NBNodeShapeComputer::computeEdgeBoundaries(), NBOwnTLDef::computeEscapeTime(), MSLCM_SL2015::computeGapFactor(), MSDevice_SSM::computeGlobalMeasures(), NBNode::computeLanes2Lanes(), NBOwnTLDef::computeLogicAndConts(), Node2EdgeRouter< E, N, V, M >::computeNode2Edge(), Node2EdgeRouter< E, N, V, M >::computeNode2Edges(), NBNodeShapeComputer::computeNodeShapeDefault(), NBNodeTypeComputer::computeNodeTypes(), MSLaneChanger::computeOvertakingTime(), computeRoutes(), MSLaneChanger::computeSafeOppositeLength(), GUIBaseVehicle::computeSeats(), MSLCM_SL2015::computeSpeedGain(), MSLCM_LC2013::computeSpeedLat(), MSLCM_SL2015::computeSpeedLat(), MSCFModel_W99::computeThresholds(), MSTrainHelper::computeTrainDimensions(), libsumo::Helper::convertCartesianToRoadMap(), MSSOTLTrafficLightLogic::countVehicles(), NGRandomNetBuilder::createNewNode(), GNENet::createRoundabout(), MSCFModel_Daniel1::dawdle(), MSCFModel_KraussOrig1::dawdle(), MSCFModel_SmartSK::dawdle(), MSCFModel_Krauss::dawdle2(), MSCFModel_KraussX::dawdleX(), MSDevice_SSM::determineTTCandDRACandPPETandMDRAC(), MSDispatch_GreedyShared::dispatch(), MSDispatch_RouteExtension::dispatch(), MSCFModel::distAfterTime(), NBNodeShapeComputer::divisionWidth(), GUIBasePersonHelper::drawAction_drawAsCenteredCircle(), GUIBasePersonHelper::drawAction_drawAsCircle(), GUIBaseVehicleHelper::drawAction_drawVehicleAsCircle(), GUIVehicle::drawAction_drawVehicleBlinker(), GUIVehicle::drawBestLanes(), GNELane::drawDirectionIndicators(), GUILane::drawDirectionIndicators(), GUIOverheadWire::drawGL(), GNEVehicle::drawGL(), GUILane::drawGL(), GUILane::drawLinkRule(), GUIBaseVehicle::drawStopLabels(), GUITLLogicPhasesTrackerWindow::drawValues(), MSParkingArea::enter(), MSVehicle::enterLaneAtMove(), MSDevice_StationFinder::estimateConsumption(), MSCFModel::estimateSpeedAfterDistance(), MSVehicle::estimateTimeToNextStop(), MSStoppingPlaceRerouter::evaluateDestination(), METriggeredCalibrator::execute(), MSCalibrator::execute(), MSVehicle::executeMove(), NBEdge::expandableBy(), NBEdge::extendGeometryAtNode(), MSCFModel::finalizeSpeed(), MSCFModel_CC::finalizeSpeed(), MSCFModel_Daniel1::finalizeSpeed(), MSCFModel_EIDM::finalizeSpeed(), NBPTStop::findLaneAndComputeBusStopExtent(), NBEdgeCont::fixSplitCustomLength(), MSCFModel_CACC::followSpeed(), MSCFModel_Krauss::followSpeed(), MSCFModel_KraussOrig1::followSpeed(), MSCFModel_PWag2009::followSpeed(), MSCFModel_Rail::followSpeed(), MSCFModel_SmartSK::followSpeed(), MSCFModel_W99::followSpeed(), MSLCM_SL2015::forecastAverageSpeed(), MSLane::freeInsertion(), MSCFModel_EIDM::freeSpeed(), MSCFModel::freeSpeed(), MSCFModel_Rail::freeSpeed(), MSCFModel_EIDM::freeSpeed(), MSCFModel_IDM::freeSpeed(), RGBColor::fromHSV(), libsumo::Helper::fuseLaneCoverage(), MSVehicle::Influencer::gapControlSpeed(), MSCFModel::gapExtrapolation(), NBEdgeCont::generateStreetSigns(), NBNode::geometryLike(), GUIMessageWindow::getActiveStringObject(), MSPModel_Striping::PState::getAngle(), MSVehicle::getArrivalTime(), MSAbstractLaneChangeModel::getAssumedDecelForLaneChangeDuration(), MSMeanData_Net::MSLaneMeanDataValues::getAttributeValue(), MSDevice_Tripinfo::getAvgDepartDelayWaiting(), MSVehicle::getBackPosition(), MEVehicle::getBoundingBox(), MSVehicle::getBoundingBox(), MSVehicle::getBoundingPoly(), GUIPerson::getCenteringBoundary(), MSLaneChanger::getColumnleader(), MEVehicle::getConservativeSpeed(), MSLane::getCriticalLeader(), GUIBusStop::getCroppedLastFreePos(), MSEdge::getCurrentTravelTime(), SUMOVTypeParameter::getDefaultEmergencyDecel(), NBNodeShapeComputer::getDefaultRadius(), MSStoppingPlace::getDefaultTransportablesAbreast(), MSVehicle::getDeltaPos(), SUMOVehicleParameter::getDepartPos(), SUMOVehicleParameter::getDepartPosLat(), SUMOVehicleParameter::getDepartSpeed(), ROVehicle::getDepartureTime(), NBNodeCont::getDiameter(), MSVehicle::getDistanceToLeaveJunction(), MSDevice_ToC::getDynamicMRMProbability(), MSRoutingEngine::getEffort(), MSRoutingEngine::getEffortBike(), MSE2Collector::getEstimateQueueLength(), GUIVisualizationSizeSettings::getExaggeration(), NBEdge::getFinalLength(), MSLane::getFollowersOnConsecutive(), GUISUMOAbstractView::getFPS(), MSDevice_Tripinfo::getGlobalParameter(), MSBaseVehicle::getImpatience(), MSPerson::getImpatience(), MSPModel_Striping::PState::getImpatience(), MSInductLoop::getIntervalOccupancy(), MSParkingArea::getLastFreePosWithReservation(), MSLane::getLastVehicleInformation(), MSLCM_SL2015::getLateralDrift(), MSSimpleTrafficLightLogic::getLatest(), LIBSUMO_NAMESPACE::Vehicle::getLeader(), MSLink::getLeaderInfo(), MSLane::getLeaderOnConsecutive(), MSLink::getLeaveTime(), GNELane::getLengthGeometryFactor(), MSActuatedTrafficLightLogic::getLinkMinDuration(), PositionVector::getMaxGrade(), NBLoadedSUMOTLDef::getMaxIndex(), MSAbstractLaneChangeModel::getMaxSpeedLat2(), MSStop::getMinDuration(), NIImporter_OpenStreetMap::getNeighboringNodes(), MESegment::getNextInsertionTime(), MSInductLoop::getOccupancy(), MSLaneChanger::getOncomingVehicle(), MSLane::getOppositePos(), PositionVector::getOverlapWith(), MSDevice_SSM::getParameter(), PedestrianEdge< E, L, N, V >::getPartialLength(), MSEdge::getProbableLane(), MSPModel_JuPedSim::getRadius(), NBNode::getReduction(), GUIVehicle::getRightSublaneOnEdge(), MSLCHelper::getRoundaboutDistBonus(), MSCFModel_CACC::getSecureGap(), MSCFModel_IDM::getSecureGap(), MSCFModel_Wiedemann::getSecureGap(), MSCFModel::getSecureGap(), MSCFModel_EIDM::getSecureGap(), NBNodeShapeComputer::getSmoothCorner(), MSPerson::MSPersonStage_Access::getSpeed(), MSCFModel::getSpeedAfterMaxDecel(), MSLCHelper::getSpeedPreservingSecureGap(), MSVehicle::getStopDelay(), MSBaseVehicle::getStopEdges(), LIBSUMO_NAMESPACE::Vehicle::getStops(), MSLeaderInfo::getSubLanes(), MSLane::getSurroundingVehicles(), MESegment::getTauJJ(), MSDevice_Tripinfo::getTotalDepartDelay(), NEMAPhase::getTransitionTime(), MSStoppingPlace::getTransportablesAbreast(), PedestrianEdge< E, L, N, V >::getTravelTime(), ROEdge::getTravelTime(), RailwayRouter< E, V >::getTravelTimeStatic(), MSTrainHelper::getUpscaleLength(), MSPModel_Striping::getVehicleObstacles(), GUIVehicle::getVisualAngle(), MEVehicle::getWaitingTime(), MSLink::getZipperSpeed(), NBLoadedSUMOTLDef::guessMinMaxDuration(), GUIBusStop::GUIBusStop(), GUIJunctionWrapper::GUIJunctionWrapper(), GUITriggeredRerouter::GUITriggeredRerouterEdge::GUITriggeredRerouterEdge(), GUIApplicationWindow::handleEvent_SimulationLoaded(), MSIdling_Stop::idle(), MSVehicle::Influencer::implicitSpeedRemote(), MSEdge::inferEdgeType(), MSVehicle::Influencer::influenceSpeed(), MSLCM_DK2008::informBlocker(), MSLCM_SL2015::informFollower(), MSLCM_LC2013::informFollower(), MSLCM_SL2015::informLeader(), MSLCM_LC2013::informLeader(), RailEdge< E, V >::init(), MSTrafficLightLogic::initMesoTLSPenalties(), ROEdge::initPriorityFactor(), MESegment::initSegment(), NIImporter_OpenStreetMap::insertEdge(), MSCFModel_IDM::insertionFollowSpeed(), MSLane::insertVehicle(), MSCFModel::interactionGap(), MSCFModel_EIDM::interactionGap(), MSCFModel_IDM::interactionGap(), MSCFModel_EIDM::internalsecuregap(), MSCFModel_EIDM::internalspeedlimit(), MSVehicle::interpolateLateralZ(), NIImporter_OpenStreetMap::EdgesHandler::interpretLaneUse(), MSLane::isInsertionSuccess(), NBLoadedSUMOTLDef::joinLogic(), NBEdgeCont::joinTramEdges(), MSLCM_SL2015::keepLatGap(), LandmarkLookupTable< E, V, M >::LandmarkLookupTable(), MSParkingArea::leaveFrom(), MSTransportableControl::loadAnyWaiting(), GUINet::loadEdgeData(), PCLoaderOSM::loadIfSet(), SUMORouteLoaderControl::loadNext(), GUITLLogicPhasesTrackerWindow::loadSettings(), NBHeightMapper::loadTiff(), GUIPersistentWindowPos::loadWindowPos(), LandmarkLookupTable< E, V, M >::lowerBound(), MSE2Collector::makeMoveNotification(), MAX3(), MAX4(), NBOwnTLDef::maxCrossingIndex(), MSCFModel::maximumSafeFollowSpeed(), MSCFModel_EIDM::maximumSafeFollowSpeed(), MSCFModel::maximumSafeStopSpeed(), MSCFModel::maximumSafeStopSpeedBallistic(), MSCFModel_KraussPS::maxNextSpeed(), MSCFModel_Rail::minNextSpeed(), MSCFModel::minNextSpeed(), MSCFModel_CC::minNextSpeed(), MSCFModel_IDM::minNextSpeed(), MSCFModel::minNextSpeedEmergency(), MSPModel_Striping::moveInDirection(), MSPModel_Striping::PState::moveTo(), libsumo::Helper::moveToXYMap(), libsumo::Helper::moveToXYMap_matchingRoutePosition(), MSDevice_ToC::MRMExecutionStep(), RGBColor::multiply(), NIImporter_SUMO::myEndElement(), GUINet::DiscoverAttributes::myStartElement(), NIImporter_OpenDrive::myStartElement(), MESegment::newArrival(), MSE2Collector::notifyLeave(), MSDevice_ElecHybrid::notifyMove(), MSDevice_Transportable::notifyMove(), MSMeanData::MeanDataValues::notifyMove(), MSDevice_StationFinder::notifyMove(), MSMeanData_Net::MSLaneMeanDataValues::notifyMoveInternal(), MSPModel_Striping::numStripes(), NBContHelper::relative_outgoing_edge_sorter::operator()(), NBContHelper::relative_incoming_edge_sorter::operator()(), MSDispatch::time_sorter::operator()(), MSPModel_Striping::PState::otherStripe(), MSPModel_Striping::PState::otherStripe(), MSInductLoop::overrideTimeSinceDetection(), MSLCM_LC2013::overtakeDistance(), MSTriggeredRerouter::overtakingTrain(), StringUtils::padFront(), NLTriggerBuilder::parseAndBuildStoppingPlace(), MSCFModel::passingTime(), NBLoadedSUMOTLDef::patchIfCrossingsAdded(), NBNode::patchOffset_pathAcrossStreet(), NBRampsComputer::patchRampGeometry(), libsumo::Helper::patchShapeDistance(), MSLCM_DK2008::patchSpeed(), MSLCM_LC2013::patchSpeed(), MSLCM_SL2015::patchSpeed(), MSCFModel_Krauss::patchSpeedBeforeLC(), MSCFModel_KraussOrig1::patchSpeedBeforeLC(), MSCFModel_EIDM::patchSpeedBeforeLCEIDM(), MSRoutingEngine::patchSpeedForTurns(), MSVehicle::planMoveInternal(), MSDevice_StationFinder::planOpportunisticCharging(), MESegment::prepareDetectorForWriting(), MSLCM_LC2013::prepareStep(), MSLCM_SL2015::prepareStep(), MSDevice_Taxi::prepareStop(), SUMOVehicleParserHelper::processActionStepLength(), MSE2Collector::processJams(), MSVehicle::processLinkApproaches(), MSVehicle::processNextStop(), NBEdgeCont::processSplits(), MSVehicle::processTraCISpeedControl(), MSDelayBasedTrafficLightLogic::proposeProlongation(), NBNodeCont::pruneLongEdges(), StringUtils::pruneZeros(), MSEdge::recalcCache(), MESegment::receive(), MSLink::recheckSetRequestInformation(), NIImporter_OpenDrive::recomputeWidths(), NIImporter_OpenStreetMap::reconstructLayerElevation(), MSCalibrator::remainingVehicleCapacity(), GNETLSEditorFrame::TLSPhases::removePhase(), RORouteDef::repairCurrentRoute(), NBPTStop::replaceEdge(), NBEdge::replaceInConnections(), MSBaseVehicle::replaceVehicleType(), NIImporter_DlrNavteq::TimeRestrictionsHandler::report(), MSStageTrip::reroute(), MSDevice_StationFinder::rerouteToChargingStation(), NBEdgeCont::retrievePossiblySplit(), MSStageWalking::routeOutput(), NIImporter_OpenDrive::sanitizeWidths(), MSLCM_LC2013::saveBlockerLength(), MSLCM_SL2015::saveBlockerLength(), MSBaseVehicle::saveState(), MSTransportable::saveState(), MSE2Collector::selectLanes(), MESegment::send(), Boundary::set(), MSDevice_ElecHybrid::setActualBatteryCapacity(), MSStageDriving::setArrived(), MSSimpleDriverState::setAwareness(), MSDevice_ToC::setAwareness(), GUIMessageWindow::setCursorPos(), NIImporter_OpenDrive::setLaneAttributes(), MSFrame::setMSGlobals(), GUILane::setMultiColor(), GNELane::setMultiColor(), MSParkingArea::setNumAlternatives(), MSLCM_SL2015::setOwnState(), MSDevice_StationFinder::setParameter(), MSVehicle::setPreviousSpeed(), NBEdgePriorityComputer::setPriorityJunctionPriorities(), MSLink::setRequestInformation(), MSParkingArea::setRoadsideCapacity(), MESegment::setSpeedForQueue(), GUIMainWindow::setWindowSizeAndPos(), GUIViewTraffic::showLaneReachability(), MSVehicle::slowDownForSchedule(), GNEEdge::smoothShape(), NBEdgeCont::splitAt(), IntermodalNetwork< E, L, N, V >::splitEdge(), MSCFModel_PWag2009::stopSpeed(), MSCFModel_SmartSK::stopSpeed(), MSPModel_Striping::PState::stripe(), MELoop::teleportVehicle(), time2string(), NGNet::toNB(), MSTriggeredRerouter::triggerRouting(), MSDelayBasedTrafficLightLogic::trySwitch(), AGFreeTime::typeFromHomeDay(), AGFreeTime::typeFromHomeEvening(), AGFreeTime::typeFromHomeNight(), MSVehicle::unsafeLinkAhead(), NEMAPhase::update(), PolygonDynamics::update(), MSVehicle::updateBestLanes(), MSLCHelper::updateBlockerLength(), MSRailCrossing::updateCurrentPhase(), MSLCM_SL2015::updateGaps(), CHBuilder< E, V >::CHInfo::updateLevel(), MSSwarmTrafficLightLogic::updatePheromoneLevels(), MSSimpleDriverState::updateReactionTime(), MSSwarmTrafficLightLogic::updateSensitivities(), MSVehicle::updateState(), NIImporter_OpenStreetMap::usableType(), MSVehicleControl::vehicleDeparted(), MFXWorkerThread::Pool::waitAll(), MSPModel_Striping::PState::walk(), MSStageWalking::walkDistance(), MSLCM_DK2008::wantsChangeToLeft(), MSLCM_DK2008::wantsChangeToRight(), MSLCM_SL2015::wantsKeepRight(), MSVehicle::workOnMoveReminders(), SUMOVehicleParameter::write(), MSMeanData_Net::MSLaneMeanDataValues::write(), ODMatrix::write(), RODFDetectorCon::writeEmitters(), NWWriter_OpenDrive::writeGeomLines(), NWWriter_OpenDrive::writeGeomPP3(), NWWriter_OpenDrive::writeGeomSmooth(), NWWriter_OpenDrive::writeInternalEdge(), NWWriter_SUMO::writeInternalEdges(), NWWriter_SUMO::writeLane(), MSQueueExport::writeLane(), NWWriter_OpenDrive::writeNormalEdge(), NWWriter_OpenDrive::writeRoadObjectPOI(), NWWriter_OpenDrive::writeRoadObjectPoly(), RODFDetector::writeSingleSpeedTrigger(), MSE2Collector::writeXMLOutput(), MSInductLoop::writeXMLOutput(), and MSDevice_Taxi::~MSDevice_Taxi().

◆ MAX3()

◆ MAX4()

template<typename T >
T MAX4 ( a,
b,
c,
d 
)
inline

Definition at line 114 of file StdDefs.h.

References MAX2().

Referenced by GUIOSGPerspectiveChanger::updateViewport().

Here is the caller graph for this function:

◆ MIN2()

template<typename T >
T MIN2 ( a,
b 
)
inline

Definition at line 80 of file StdDefs.h.

Referenced by RailwayRouter< E, V >::_compute(), MSRoutingEngine::_initEdgeWeights(), MSLCM_LC2013::_patchSpeed(), MSLCM_SL2015::_patchSpeed(), MSCFModel_EIDM::_v(), MSCFModel_Kerner::_v(), MSCFModel_Wiedemann::_v(), MSLCM_LC2013::_wantsChange(), MSLCM_SL2015::_wantsChangeSublane(), MSCFModel_ACC::accelGapControl(), MSVehicle::DriveProcessItem::adaptLeaveSpeed(), MSLCM_LC2013::adaptSpeedToPedestrians(), MSVehicle::DriveProcessItem::adaptStopSpeed(), MSVehicle::adaptToJunctionLeader(), MSVehicle::adaptToLeader(), MSVehicle::adaptToOncomingLeader(), MSPModel_Striping::addCrossingVehs(), NBNode::addedLanesRight(), GNENet::addGreenVergeLane(), MSLeaderDistanceInfo::addLeaders(), MSLaneChangerSublane::addOutsideLeaders(), GNENet::addRestrictedLane(), MSBaseVehicle::addStop(), NBEdge::addStraightConnections(), MSMeanData_Net::MSLaneMeanDataValues::addTo(), MSLCM_LC2013::anticipateFollowSpeed(), MSDevice_ToC::awarenessRecoveryStep(), MSBaseVehicle::basePos(), NBNode::bezierControlPoints(), GUIViewTraffic::buildColorRainbow(), GNEViewNet::buildColorRainbow(), NLDetectorBuilder::buildInductLoop(), NBEdge::buildInnerEdges(), GNETLSEditorFrame::buildInternalLanes(), GUISUMOAbstractView::buildMinMaxRainbow(), NBRampsComputer::buildOffRamp(), NBRampsComputer::buildOnRamp(), NBNode::buildWalkingAreas(), MSBaseVehicle::calculateArrivalParams(), NEMALogic::calculateForceOffs170(), NEMALogic::calculateForceOffsTS2(), GawronCalculator< R, E, V >::calculateProbabilities(), GNEPathManager::PathCalculator::calculateReachability(), MSE2Collector::calculateTimeLossAndTimeOnDetector(), NEMAPhase::calcVehicleExtension(), RGBColor::changedAlpha(), RGBColor::changedBrightness(), MSLaneChanger::changeOpposite(), MSLCM_SL2015::checkBlocking(), MSLCM_SL2015::checkBlockingVehicles(), MELoop::checkCar(), MSLaneChanger::checkChange(), MSLane::checkFailure(), MSVehicleTransfer::checkInsertions(), MSVehicle::checkLinkLeader(), MSE2Collector::checkPositioning(), MSVehicle::checkRewindLinkLanes(), MSLink::checkWalkingAreaFoe(), MSLCM_SL2015::commitFollowSpeed(), Bresenham::compute(), AFRouter< E, N, V, M >::compute(), AStarRouter< E, V, M >::compute(), NBNetBuilder::compute(), NBEdge::computeAngle(), MSVehicle::computeAngle(), MSTrainHelper::computeCarriages(), MSDispatch_GreedyClosest::computeDispatch(), MSDevice_SSM::computeDRAC(), NBEdge::computeEdgeShape(), NBNode::computeLanes2Lanes(), MSParkingArea::computeLastFreePos(), NBOwnTLDef::computeLogicAndConts(), Node2EdgeRouter< E, N, V, M >::computeNode2Edge(), Node2EdgeRouter< E, N, V, M >::computeNode2Edges(), computeRoutes(), MSLaneChanger::computeSafeOppositeLength(), MSLCM_SL2015::computeSpeedGain(), MSLCM_LC2013::computeSpeedLat(), MSLCM_SL2015::computeSpeedLat(), MSTrainHelper::computeTrainDimensions(), GNENet::createRoundabout(), MSTLLogicControl::WAUTSwitchProcedure_Stretch::cutLogic(), MSStoppingPlaceRerouter::determineRerouteOrigin(), MSDevice_SSM::determineTTCandDRACandPPETandMDRAC(), GUIBasePersonHelper::drawAction_drawAsCenteredCircle(), GUIBasePersonHelper::drawAction_drawAsCircle(), GUIVehicle::drawAction_drawCarriageClass(), GUIBaseVehicleHelper::drawAction_drawVehicleAsCircle(), GNELane::drawDirectionIndicators(), GUILane::drawDirectionIndicators(), GUIBusStop::drawGL(), GUIChargingStation::drawGL(), GUIOverheadWire::drawGL(), GUIParkingArea::drawGL(), GNEBusStop::drawGL(), GNEChargingStation::drawGL(), GNEContainerStop::drawGL(), GNEParkingArea::drawGL(), GNEVehicle::drawGL(), GUIInductLoop::MyWrapper::drawGL(), GUILane::drawGL(), GLHelper::drawInverseMarkings(), GUILane::drawJunctionChangeProhibitions(), GUIEdge::drawMesoVehicles(), GUIBaseVehicle::drawOnPos(), GNELane::drawStartEndGeometryPoints(), MSDevice_GLOSA::earliest_arrival(), NEMAPhase::enter(), MSDevice_Battery::estimateChargingDuration(), MSDevice_SSM::estimateConflictTimes(), MSDevice_StationFinder::estimateConsumption(), MEVehicle::estimateLeaveSpeed(), MSCFModel::estimateSpeedAfterDistance(), MSVehicle::estimateTimeToNextStop(), NBNode::ApproachingDivider::execute(), MSPModel_JuPedSim::execute(), MSVehicle::executeMove(), NBEdge::extendGeometryAtNode(), MSCFModel::finalizeSpeed(), MSCFModel_Daniel1::finalizeSpeed(), MSCFModel_EIDM::finalizeSpeed(), LIBSUMO_NAMESPACE::Simulation::findIntermodalRoute(), NBPTStop::findLaneAndComputeBusStopExtent(), NBEdge::firstIntersection(), MSCFModel_ACC::followSpeed(), MSCFModel_CACC::followSpeed(), MSCFModel_Daniel1::followSpeed(), MSCFModel_Kerner::followSpeed(), MSCFModel_Krauss::followSpeed(), MSCFModel_KraussOrig1::followSpeed(), MSCFModel_PWag2009::followSpeed(), MSCFModel_Rail::followSpeed(), MSCFModel_SmartSK::followSpeed(), MSCFModel_W99::followSpeed(), MSLane::freeInsertion(), MSCFModel_IDM::freeSpeed(), RGBColor::fromHSV(), MSCFModel_Wiedemann::fullspeed(), libsumo::Helper::fuseLaneCoverage(), MSActuatedTrafficLightLogic::gapControl(), MSVehicle::Influencer::gapControlSpeed(), MSCFModel::gapExtrapolation(), MSMeanData_Net::MSLaneMeanDataValues::getAttributeValue(), MEVehicle::getAverageSpeed(), MSVehicle::getBackPositionOnLane(), MEVehicle::getBoundingBox(), MSVehicle::getBoundingBox(), MSVehicle::getBoundingPoly(), MSLane::getBruttoOccupancy(), GUIMEVehicle::getCenteringBoundary(), PollutantsInterface::Helper::getCoastingDecel(), GUIBaseVehicle::getContainerPosition(), MSCFModel::getCurrentAccel(), NBNodeShapeComputer::getDefaultRadius(), MSEdge::getDepartLane(), MSEdge::getDepartPosBound(), MSLane::getDepartSpeed(), MSDevice_ToC::getDynamicMRMProbability(), MSSimpleTrafficLightLogic::getEarliest(), MSStageDriving::getEdgePos(), ROEdge::getEffort(), ROEdge::getEmissionEffort(), GNEDemandElementPlan::getEndPosRadius(), MESegment::getEntryBlockTimeSeconds(), GNEEdge::getGeometryPointRadius(), MSBaseVehicle::getImpatience(), MSPerson::getImpatience(), MSPModel_Striping::PState::getImpatience(), MSInductLoop::getIntervalOccupancy(), MSParkingArea::getLastFreePos(), MSStoppingPlace::getLastFreePos(), MSParkingArea::getLastFreePosWithReservation(), MSLane::getLeadersOnConsecutive(), LIBSUMO_NAMESPACE::Lane::getLinks(), MSLane::getMaximumBrakeDist(), MSDevice_Battery::getMaximumChargeRate(), MSBaseVehicle::getMaxSpeed(), MSTransportable::getMaxSpeed(), RORoutable::getMaxSpeed(), GeomHelper::getMinAngleDiff(), MSLeaderDistanceInfo::getMinDistToStopped(), MSActuatedTrafficLightLogic::getMinimumMinDuration(), ROEdge::getMinimumTravelTime(), NBNodesEdgesSorter::crossing_by_junction_angle_sorter::getMinRank(), PositionVector::getMinZ(), HelpersPHEMlight::getModifiedAccel(), HelpersPHEMlight5::getModifiedAccel(), NIImporter_OpenStreetMap::getNeighboringNodes(), LIBSUMO_NAMESPACE::Vehicle::getNextLinks(), ROEdge::getNoiseEffort(), MSInductLoop::getOccupancy(), MSInductLoop::getOccupancyTime(), MSLaneChanger::getOncomingVehicle(), MSDevice_SSM::getParameter(), MSPModel_NonInteracting::CState::getPosition(), MSPModel_Striping::getReserved(), GUIBaseVehicle::getSeatPosition(), MSCFModel::getSecureGap(), MSCFModel_EIDM::getSecureGap(), NBEdge::getShapeEndAngle(), NBEdge::getShapeStartAngle(), MSLeaderInfo::getSublaneBorders(), MSLeaderInfo::getSubLanes(), MSLane::getSurroundingVehicles(), MSCFModel_Rail::TrainParams::getTraction(), PublicTransportEdge< E, L, N, V >::getTravelTime(), ROEdge::getTravelTime(), MSEdge::getTravelTimeAggregated(), MSLane::getVehicleMaxSpeed(), MSPModel_Striping::getVehicleObstacles(), MSLink::getZipperSpeed(), NBNodeCont::guessTLs(), GUITriggeredRerouter::GUITriggeredRerouterEdge::GUITriggeredRerouterEdge(), MSLane::handleCollisionBetween(), MSVehicle::handleCollisionStop(), MSLane::handleIntermodalCollisionBetween(), MSVehicle::hasArrivedInternal(), MESegment::hasSpaceFor(), LIBSUMO_NAMESPACE::POI::highlight(), LIBSUMO_NAMESPACE::Vehicle::highlight(), MSVehicle::Influencer::implicitDeltaPosRemote(), MSVehicle::Influencer::implicitSpeedRemote(), MSVehicle::Influencer::influenceSpeed(), MSLCM_LC2013::informFollower(), MSLCM_SL2015::informLeader(), MSLCM_LC2013::informLeader(), MSLCM_SL2015::informLeaders(), MSActuatedTrafficLightLogic::init(), MSDelayBasedTrafficLightLogic::init(), MSTrafficLightLogic::initMesoTLSPenalties(), ROEdge::initPriorityFactor(), MSCFModel_CACC::insertionFollowSpeed(), MSCFModel::insertionStopSpeed(), MSCFModel_EIDM::insertionStopSpeed(), MSLane::insertVehicle(), MSPModel_Striping::insertWalkArePaths(), MSCFModel::interactionGap(), MSCFModel_EIDM::internalspeedlimit(), MSLCM_SL2015::keepLatGap(), MSVehicle::keepStopping(), MSLane::lastInsertion(), SUMORouteLoaderControl::loadNext(), GUITLLogicPhasesTrackerWindow::loadSettings(), MESegment::loadState(), NBHeightMapper::loadTiff(), GUIPersistentWindowPos::loadWindowPos(), MSE2Collector::makeMoveNotification(), MSCFModel::maximumLaneSpeedCF(), MSCFModel_CACC::maximumLaneSpeedCF(), MSCFModel::maximumSafeFollowSpeed(), MSCFModel_EIDM::maximumSafeFollowSpeed(), MSCFModel::maximumSafeStopSpeed(), MSCFModel::maxNextSpeed(), MSCFModel_KraussPS::maxNextSpeed(), MSCFModel_Rail::maxNextSpeed(), NIImporter_OpenStreetMap::mergeTurnSigns(), MIN3(), MIN4(), MSCFModel_IDM::minNextSpeed(), MSPModel_Striping::moveInDirection(), MSPModel_Striping::PState::moveTo(), LIBSUMO_NAMESPACE::Person::moveToXY(), LIBSUMO_NAMESPACE::Vehicle::moveToXY(), libsumo::Helper::moveToXYMap(), libsumo::Helper::moveToXYMap_matchingRoutePosition(), MSEdgeControl::MSEdgeControl(), RGBColor::multiply(), MSLCM_SL2015::mustOvertakeStopped(), GUINet::DiscoverAttributes::myStartElement(), NIImporter_OpenStreetMap::EdgesHandler::myStartElement(), NBEdge::NBEdge(), MESegment::newArrival(), TraCIServer::nextTargetTime(), MSDevice_GLOSA::notifyEnter(), MSMeanData::MeanDataValues::notifyMove(), MSDevice_Battery::notifyMove(), MSDevice_StationFinder::notifyMove(), MSMeanData_Net::MSLaneMeanDataValues::notifyMoveInternal(), GUIViewTraffic::onGamingClick(), GUISUMOAbstractView::openPopupDialog(), NBContHelper::relative_outgoing_edge_sorter::operator()(), NBContHelper::relative_incoming_edge_sorter::operator()(), NBRequest::oppositeLeftTurnConflict(), MSBaseVehicle::optimizeSkipped(), MSPModel_Striping::PState::otherStripe(), MSInductLoop::overrideTimeSinceDetection(), MSTriggeredRerouter::overtakingTrain(), MapMatcher< E, L, N >::parseGeoEdges(), MSCFModel::passingTime(), NBRampsComputer::patchRampGeometry(), MSLCM_DK2008::patchSpeed(), MSCFModel_Krauss::patchSpeedBeforeLC(), MSCFModel_EIDM::patchSpeedBeforeLCEIDM(), MSVehicle::planMoveInternal(), MSLCM_LC2013::prepareStep(), MSDevice_Taxi::prepareStop(), MSDevice_SSM::processEncounters(), MSVehicle::processLinkApproaches(), ROLoader::processRoutes(), NBNodeCont::pruneClusterFringe(), MSEdge::recalcCache(), MESegment::receive(), MSLink::recheckSetRequestInformation(), NBEdge::reinit(), NBEdge::replaceInConnections(), MSBaseVehicle::replaceVehicleType(), NIImporter_DlrNavteq::TimeRestrictionsHandler::report(), MSStageTrip::reroute(), GUIVehicle::rerouteDRTStop(), MSStoppingPlaceRerouter::rerouteStoppingPlace(), MSDevice_StationFinder::rerouteToChargingStation(), ROMAAssignments::resetFlows(), MSDevice_ToC::responseTimeMean(), MSLane::safeInsertionSpeed(), RONet::saveAndRemoveRoutesUntil(), ROPerson::PersonTrip::saveAsXML(), Boundary::set(), MSDevice_ElecHybrid::setActualBatteryCapacity(), MSStageDriving::setArrived(), MSDevice_ToC::setAwareness(), GUIMessageWindow::setCursorPos(), NIImporter_OpenDrive::setLaneAttributes(), MSLCM_SL2015::setOwnState(), MSDevice_StationFinder::setParameter(), NBEdgePriorityComputer::setPriorityJunctionPriorities(), MSLink::setRequestInformation(), MSParkingArea::setRoadsideCapacity(), MSDevice_ToC::setState(), GUIMainWindow::setWindowSizeAndPos(), NBEdge::shiftPositionAtNode(), NBEdge::shortenGeometryAtNode(), GUIViewTraffic::showLaneReachability(), PositionVector::simplified2(), MSCFModel_EIDM::slowToStartTerm(), PositionVector::smoothedZFront(), GNEEdge::smoothShape(), NBEdgeCont::splitAt(), NBEdge::startShapeAt(), MSCFModel_IDM::stopSpeed(), MSCFModel_Rail::stopSpeed(), MSCFModel_W99::stopSpeed(), MSCFModel_Wiedemann::stopSpeed(), MSCFModel_ACC::stopSpeed(), MSCFModel_CACC::stopSpeed(), MSCFModel_Daniel1::stopSpeed(), MSCFModel_Kerner::stopSpeed(), MSCFModel_Krauss::stopSpeed(), MSCFModel_KraussOrig1::stopSpeed(), MSCFModel_PWag2009::stopSpeed(), MSCFModel_SmartSK::stopSpeed(), MSPModel_Striping::PState::stripe(), MSDevice_StationFinder::teleportToChargingStation(), time2string(), MSActuatedTrafficLightLogic::trySwitch(), MSDelayBasedTrafficLightLogic::trySwitch(), AGFreeTime::typeFromHomeNight(), MSVehicle::updateBestLanes(), MSLink::updateDistToFoePedCrossing(), MSLCM_SL2015::updateExpectedSublaneSpeeds(), MSLCM_SL2015::updateGaps(), MSSwarmTrafficLightLogic::updatePheromoneLevels(), MSSwarmTrafficLightLogic::updateSensitivities(), MSEdge::validateDepartSpeed(), MSVehicleControl::vehicleDeparted(), MSCFModel_KraussOrig1::vsafe(), MFXWorkerThread::Pool::waitAll(), MSPModel_Striping::PState::walk(), MSLCM_DK2008::wantsChangeToLeft(), MSLCM_DK2008::wantsChangeToRight(), MSMeanData_Emissions::MSLaneMeanDataValues::write(), MSMeanData_Harmonoise::MSLaneMeanDataValues::write(), MSMeanData_Net::MSLaneMeanDataValues::write(), NWWriter_OpenDrive::writeGeomSmooth(), NWWriter_SUMO::writeLane(), NWWriter_OpenDrive::writeRoadObjectPOI(), NWWriter_OpenDrive::writeRoadObjectPoly(), MSE3Collector::writeXMLOutput(), MSInductLoop::writeXMLOutput(), and MSMeanData::writeXMLOutput().

◆ MIN3()

◆ MIN4()

template<typename T >
T MIN4 ( a,
b,
c,
d 
)
inline

Definition at line 107 of file StdDefs.h.

References MIN2().

Referenced by MSCFModel_Kerner::_v(), GLHelper::drawBoxLines(), MSMeanData::MeanDataValues::notifyMove(), and GUIOSGPerspectiveChanger::updateViewport().

Here is the caller graph for this function:

◆ NETWORK_VERSION()

const MMVersion NETWORK_VERSION ( ,
20   
)

Referenced by NWWriter_XML::writeEdgesAndConnections(), NWWriter_XML::writeJoinedJunctions(), NWWriter_SUMO::writeNetwork(), NWWriter_XML::writeNodes(), NWWriter_XML::writeTrafficLights(), and NWWriter_XML::writeTypes().

Here is the caller graph for this function:

◆ roundBits()

double roundBits ( double  x,
int  fractionBits 
)

round to the given number of mantissa bits beyond the given number

Definition at line 54 of file StdDefs.cpp.

◆ roundDecimal()

double roundDecimal ( double  x,
int  precision 
)

round to the given number of decimal digits

Definition at line 60 of file StdDefs.cpp.

Referenced by MSVehicleType::computeChosenSpeedDeviation(), MSLane::getDepartPosLat(), MSLane::getDepartSpeed(), and MSLane::insertVehicle().

Here is the caller graph for this function:

◆ roundDecimalToEven()

double roundDecimalToEven ( double  x,
int  precision 
)

round to the given number of decimal digits (bankers rounding)

Definition at line 66 of file StdDefs.cpp.

Referenced by Position::round(), and NBEdge::roundSpeed().

Here is the caller graph for this function:

◆ truncate()

double truncate ( double  x,
int  fractionBits 
)

discrds mantissa bits beyond the given number

Definition at line 50 of file StdDefs.cpp.

Variable Documentation

◆ gDebugFlag1

◆ gDebugFlag2

◆ gDebugFlag3

◆ gDebugFlag4

◆ gDebugFlag5

◆ gDebugFlag6

bool gDebugFlag6
extern

Definition at line 48 of file StdDefs.cpp.

Referenced by MSLink::blockedByFoe(), and MSLink::computeFoeArrivalTimeBraking().

◆ gHumanReadableTime

◆ gIgnoreUnknownVClass

bool gIgnoreUnknownVClass
extern

Definition at line 33 of file StdDefs.cpp.

Referenced by SystemFrame::checkOptions(), and parseVehicleClasses().

◆ gLanguage

std::string gLanguage
extern

the language for GUI elements and messages

Definition at line 38 of file StdDefs.cpp.

Referenced by SystemFrame::addReportOptions(), main(), GUIMainWindow::onCmdChangeLanguage(), and GUIMainWindow::onUpdChangeLanguage().

◆ gLocaleInitialized

bool gLocaleInitialized
extern

Definition at line 34 of file StdDefs.cpp.

Referenced by OptionsCont::localizeDescriptions(), and MsgHandler::setupI18n().

◆ gPrecision

int gPrecision
extern

the precision for floating point outputs

Definition at line 27 of file StdDefs.cpp.

Referenced by MSLCM_LC2013::_patchSpeed(), MSLCM_LC2013::_wantsChange(), MSLCM_SL2015::_wantsChangeSublane(), NBEdge::assignInternalLaneLength(), SystemFrame::checkOptions(), MSVehicle::checkReversal(), MSCFModel::finalizeSpeed(), StringUtils::format(), MSDevice_Emissions::generateOutput(), SUMOVehicleParameter::getDepartPos(), SUMOVehicleParameter::getDepartPosLat(), SUMOVehicleParameter::getDepartSpeed(), MSLane::getLeader(), GUIVehicle::getTypeParameterWindow(), GUIMEVehicle::getTypeParameterWindow(), NBEdge::init(), MSDevice_SSM::makeStringWithNAs(), MSDevice_SSM::makeStringWithNAs(), libsumo::Helper::moveToXYMap(), NIImporter_OpenDrive::myStartElement(), MapMatcher< E, L, N >::parseGeoEdges(), MSVehicle::planMove(), MSNet::postSimStepOutput(), MSDevice_Tripinfo::printStatistics(), NBEdge::roundGeometry(), NBNode::roundGeometry(), NBEdge::roundSpeed(), ROPerson::PersonTrip::saveAsXML(), ROVehicle::saveAsXML(), MSStateHandler::saveState(), MSTransportable::saveState(), NBEdge::shiftPositionAtNode(), time2string(), MSLCM_LC2013::wantsChange(), MSLCM_SL2015::wantsChangeSublane(), MSMeanData_Emissions::MSLaneMeanDataValues::write(), MSXMLRawOut::write(), MSFCDExport::write(), MSEmissionExport::write(), MSEmissionExport::writeEmissions(), NWWriter_OpenDrive::writeInternalEdge(), NWWriter_OpenDrive::writeNormalEdge(), MSDevice_SSM::writeOutConflict(), NWWriter_OpenDrive::writeRoadObjects(), MSDevice_Tripinfo::writeStatistics(), and MSFCDExport::writeTransportable().

◆ gPrecisionEmissions

◆ gPrecisionGeo

◆ gPrecisionRandom

◆ gRoutingPreferences

◆ gSimulation

bool gSimulation
extern

◆ GUIDesignDialogButtonsHeight

int GUIDesignDialogButtonsHeight
extern

the default height for dialog buttons

Definition at line 41 of file StdDefs.cpp.

◆ GUIDesignHeight

◆ gWeightsRandomFactor

◆ gWeightsWalkOppositeFactor

double gWeightsWalkOppositeFactor
extern

◆ INVALID_DOUBLE

const double INVALID_DOUBLE = std::numeric_limits<double>::max()

invalid double

Definition at line 68 of file StdDefs.h.

Referenced by MSDevice_SSM::Encounter::add(), MSMeanData_Net::MSLaneMeanDataValues::addTo(), PositionVector::angleAt2D(), PositionVector::beginEndAngle(), GNEAdditionalHandler::buildAccess(), GNEAdditionalHandler::buildParkingSpace(), GNEStoppingPlace::calculateStoppingPlaceContour(), MSDevice_SSM::checkConflictEntryAndExit(), GNEAdditionalHandler::checkLaneDoublePosition(), MSDevice_SSM::classifyEncounter(), GNEMoveElement::commitMove(), GNEMoveElementLaneDouble::commitMoveShape(), GNEMoveElementVehicle::commitMoveShape(), MSTrainHelper::computeCarriages(), MSDevice_SSM::computeDRAC(), MSDevice_SSM::computeDRAC(), MSDevice_SSM::computeGlobalMeasures(), MSDevice_SSM::computeMDRAC(), MSDevice_SSM::computeSSMs(), MSDevice_SSM::computeTTC(), MSDevice_SSM::createEncounters(), MSDevice_SSM::determinePET(), MSDevice_SSM::determineTTCandDRACandPPETandMDRAC(), GNEStop::drawGeometryPoints(), GNEBusStop::drawGL(), GNEChargingStation::drawGL(), GNEContainerStop::drawGL(), GNELaneAreaDetector::drawGL(), GNEParkingArea::drawGL(), EnergyParams::EnergyParams(), MSCFModel::estimateArrivalTime(), MSDevice_SSM::estimateConflictTimes(), MSVehicle::estimateTimeToNextStop(), MSFrame::fillOptions(), ROFrame::fillOptions(), GNEAdditionalHandler::fixLaneDoublePosition(), GNEMoveElementLaneDouble::fixMovingProblem(), GNEMoveElementLaneSingle::fixMovingProblem(), MSDevice_SSM::flushConflicts(), MSDevice_SSM::flushGlobalMeasures(), MSPModel_Striping::PState::getAngle(), EnergyParams::getAngleDiff(), GNEAccess::getAttribute(), GNEParkingSpace::getAttribute(), GNETAZ::getAttribute(), GNEStop::getAttribute(), GNEParkingSpace::getAttributeDouble(), GNEViewNetHelper::IntervalBar::getBegin(), MSDevice_SSM::getDetectionRange(), EnergyParams::getDoubleOptional(), GNEViewNetHelper::IntervalBar::getEnd(), MSDevice_SSM::getExtraTime(), GNEMoveElementLaneSingle::getFixedPositionOverLane(), GUIPerson::getGUIAngle(), MSLink::getLengthBeforeCrossing(), MSLink::getLengthsBeforeCrossing(), GNEMoveElementLaneDouble::getMoveOperation(), GNEMoveElementLaneSingle::getMoveOperation(), GNEMoveElementVehicle::getMoveOperation(), GNEMoveElementLaneSingle::getMovingAttribute(), GNEMoveElementLaneSingle::getMovingProblem(), GUIPerson::getNaviDegree(), MSDevice_SSM::getParameter(), GNEDemandElementPlan::getPlanAttributeDouble(), MSPModel_Striping::PState::getPosition(), MSCFModel_Rail::TrainParams::getResistance(), GUIPerson::getStageArrivalPos(), MSBaseVehicle::getStopArrivalDelay(), MSVehicle::getStopArrivalDelay(), LIBSUMO_NAMESPACE::Vehicle::getStopArrivalDelay(), MSBaseVehicle::getStopEdges(), LIBSUMO_NAMESPACE::Vehicle::getStopParameter(), GNEStopFrame::getStopParameter(), MSCFModel_Rail::TrainParams::getTraction(), GUIVisualizationSettings::initSumoGuiDefaults(), MSPModel_Striping::insertWalkArePaths(), GNEAccess::isAccessPositionFixed(), GNEStoppingPlace::isAttributeEnabled(), GNEMoveElementLaneSingle::isMoveElementValid(), GNEGenericData::isVisibleInspectDeleteSelect(), main(), GNEMoveElement::moveElement(), MSCFModel_Rail::MSCFModel_Rail(), PositionVector::nearest_offset_to_point25D(), PositionVector::nearest_offset_to_point2D(), MSMeanData_Net::MSLaneMeanDataValues::notifyMoveInternal(), MSTriggeredRerouter::overtakingTrain(), GNEAttributeCarrier::parse(), AdditionalHandler::parseBusStopAttributes(), AdditionalHandler::parseChargingStationAttributes(), AdditionalHandler::parseContainerStopAttributes(), SUMOVehicleParserHelper::parseJMParams(), AdditionalHandler::parseOverheadWire(), AdditionalHandler::parseParkingAreaAttributes(), SUMORouteHandler::parseStop(), RouteHandler::parseStopParameters(), AdditionalHandler::parseTrainStopAttributes(), MSDevice_SSM::processEncounters(), MSVehicle::processNextStop(), MSDevice_SSM::qualifiesAsConflict(), MSBaseVehicle::reroute(), MSMeanData_Net::MSLaneMeanDataValues::reset(), MSVehicle::resumeFromStopping(), PositionVector::rotationAtOffset(), GNEAccess::setAttribute(), GNEParkingSpace::setAttribute(), GNEStop::setAttribute(), GNEVehicle::setAttribute(), GNEMoveElementLaneDouble::setMoveShape(), GNEMoveElementVehicle::setMoveShape(), GNEMoveElementLaneSingle::setMovingAttribute(), GNEMoveElementLaneDouble::setSize(), GUIViewTraffic::showLaneReachability(), PositionVector::slopeDegreeAtOffset(), GNEStoppingPlace::splitEdgeGeometry(), GNEViewNetHelper::IntervalBar::updateIntervalBar(), MSDevice_SSM::updatePassedEncounter(), GNETAZ::updateTAZStatistic(), SUMOVehicleParameter::Stop::write(), MSFCDExport::write(), GNEParkingSpace::writeAdditional(), GNEStop::writeDemandElement(), GNEMoveElementLaneSingle::writeMoveAttributes(), and MSDevice_SSM::writeOutConflict().

◆ INVALID_INT

const int INVALID_INT = std::numeric_limits<int>::max()

invalid int

Definition at line 65 of file StdDefs.h.

Referenced by GNEAttributeCarrier::parse().

◆ SUMO_const_halfLaneWidth

const double SUMO_const_halfLaneWidth = SUMO_const_laneWidth / 2

◆ SUMO_const_haltingSpeed

◆ SUMO_const_laneMarkWidth

◆ SUMO_const_laneWidth

◆ SUMO_const_quarterLaneWidth

const double SUMO_const_quarterLaneWidth = SUMO_const_laneWidth / 4

Definition at line 54 of file StdDefs.h.

◆ SUMO_const_waitingContainerDepth

const double SUMO_const_waitingContainerDepth = 6.2

Definition at line 59 of file StdDefs.h.

◆ SUMO_const_waitingContainerWidth

const double SUMO_const_waitingContainerWidth = 2.5

◆ SUMO_const_waitingPersonDepth

const double SUMO_const_waitingPersonDepth = 0.67

Definition at line 57 of file StdDefs.h.

◆ SUMO_const_waitingPersonWidth

const double SUMO_const_waitingPersonWidth = 0.8