/****************************************************************************/1// Eclipse SUMO, Simulation of Urban MObility; see https://eclipse.dev/sumo2// Copyright (C) 2010-2025 German Aerospace Center (DLR) and others.3// This program and the accompanying materials are made available under the4// terms of the Eclipse Public License 2.0 which is available at5// https://www.eclipse.org/legal/epl-2.0/6// This Source Code may also be made available under the following Secondary7// Licenses when the conditions for such availability set forth in the Eclipse8// Public License 2.0 are satisfied: GNU General Public License, version 29// or later which is available at10// https://www.gnu.org/licenses/old-licenses/gpl-2.0-standalone.html11// SPDX-License-Identifier: EPL-2.0 OR GPL-2.0-or-later12/****************************************************************************/13/// @file MSBaseVehicle.h14/// @author Daniel Krajzewicz15/// @author Michael Behrisch16/// @author Jakob Erdmann17/// @date Mon, 8 Nov 201018///19// A base class for vehicle implementations20/****************************************************************************/21#pragma once22#include <config.h>2324#include <iostream>25#include <vector>26#include <set>27#include <utils/common/StdDefs.h>28#include <utils/emissions/EnergyParams.h>29#include <utils/emissions/PollutantsInterface.h>30#include <utils/vehicle/SUMOVehicle.h>31#include "MSRoute.h"32#include "MSMoveReminder.h"33#include "MSVehicleType.h"343536// ===========================================================================37// class declarations38// ===========================================================================39class MSLane;40class MSStop;41class MSDevice_Transportable;42class MSDevice_Emissions;43class MSVehicleDevice;44class MSEdgeWeightsStorage;45class MSChargingStation;46class StoppingPlaceMemory;474849// ===========================================================================50// class definitions51// ===========================================================================52/**53* @class MSBaseVehicle54* @brief The base class for microscopic and mesoscopic vehicles55*/56class MSBaseVehicle : public SUMOVehicle {57public:58// XXX: This definition was introduced to make the MSVehicle's previousSpeed59// available in the context of MSMoveReminder::notifyMove(). Another solution60// would be to modify notifyMove()'s interface to work with MSVehicle instead61// of SUMOVehicle (it is only called with MSVehicles!). Refs. #257962/** @brief Returns the vehicle's previous speed63* @return The vehicle's speed64*/65double getPreviousSpeed() const;6667friend class GUIBaseVehicle;6869/** @enum RouteValidity70*/71enum RouteValidity {72ROUTE_VALID = 0,73ROUTE_UNCHECKED = 1 << 0,74/// route was checked and is valid75ROUTE_INVALID = 1 << 1,76// starting edge permissions invalid (could change)77ROUTE_START_INVALID_PERMISSIONS = 1 << 2,78// insertion lane does not exist79ROUTE_START_INVALID_LANE = 1 << 380};8182/** @brief Constructor83* @param[in] pars The vehicle description84* @param[in] route The vehicle's route85* @param[in] type The vehicle's type86* @param[in] speedFactor The factor for driven lane's speed limits87* @exception ProcessError If a value is wrong88*/89MSBaseVehicle(SUMOVehicleParameter* pars, ConstMSRoutePtr route,90MSVehicleType* type, const double speedFactor);919293/// @brief Destructor94virtual ~MSBaseVehicle();9596virtual void initDevices();9798bool isVehicle() const {99return true;100}101102/// @brief set the id (inherited from Named but forbidden for vehicles)103void setID(const std::string& newID);104105/** @brief Returns the vehicle's parameter (including departure definition)106*107* @return The vehicle's parameter108*/109const SUMOVehicleParameter& getParameter() const;110111/// @brief retrieve parameters of devices, models and the vehicle itself112std::string getPrefixedParameter(const std::string& key, std::string& error) const;113114/// @brief replace the vehicle parameter (deleting the old one)115void replaceParameter(const SUMOVehicleParameter* newParameter);116117/// @brief check whether the vehicle is equiped with a device of the given name118bool hasDevice(const std::string& deviceName) const;119120/// @brief create device of the given type121void createDevice(const std::string& deviceName);122123/// @brief try to retrieve the given parameter from any of the vehicles devices, raise InvalidArgument if no device parameter by that name exists124std::string getDeviceParameter(const std::string& deviceName, const std::string& key) const;125126/// @brief try to set the given parameter from any of the vehicles devices, raise InvalidArgument if no device parameter by that name exists127void setDeviceParameter(const std::string& deviceName, const std::string& key, const std::string& value);128129/// @brief set individual junction model paramete (not type related)130void setJunctionModelParameter(const std::string& key, const std::string& value);131132/// @brief set individual carFollow model parameters (not type related)133void setCarFollowModelParameter(const std::string& key, const std::string& value);134135/** @brief Returns the current route136* @return The route the vehicle uses137*/138inline const MSRoute& getRoute() const {139return *myRoute;140}141142/** @brief Returns the current route143* @return The route the vehicle uses144*/145inline ConstMSRoutePtr getRoutePtr() const {146return myRoute;147}148149/** @brief Returns the vehicle's type definition150* @return The vehicle's type definition151*/152inline const MSVehicleType& getVehicleType() const {153return *myType;154}155156/** @brief Returns the vehicle's type parameter157* @return The vehicle's type parameter158*/159inline const SUMOVTypeParameter& getVTypeParameter() const {160return myType->getParameter();161}162163/** @brief Returns the vehicle's access class164* @return The vehicle's access class165*/166inline SUMOVehicleClass getVClass() const {167return myType->getParameter().vehicleClass;168}169170/** @brief Returns whether this object is ignoring transient permission171* changes (during routing)172*/173bool ignoreTransientPermissions() const;174175/** @brief Returns the maximum speed (the minimum of desired and technical maximum speed)176* @return The vehicle's maximum speed177*/178double getMaxSpeed() const;179180/** @brief Returns the nSuccs'th successor of edge the vehicle is currently at181*182* If the rest of the route (counted from the current edge) has less than nSuccs edges,183* 0 is returned.184* @param[in] nSuccs The number of edge to look forward185* @return The nSuccs'th following edge in the vehicle's route186*/187const MSEdge* succEdge(int nSuccs) const;188189/** @brief Returns the edge the vehicle is currently at190*191* @return The current edge in the vehicle's route192*/193const MSEdge* getEdge() const;194195/** @brief Returns the edge the vehicle is currently at (possibly an196* internal edge)197*/198virtual const MSEdge* getCurrentEdge() const {199return getEdge();200}201202/// @brief returns the numerical ids of edges to travel203const std::set<SUMOTrafficObject::NumericalID> getUpcomingEdgeIDs() const;204205/** @brief Returns whether the vehicle stops at the given stopping place */206bool stopsAt(MSStoppingPlace* stop) const;207208/** @brief Returns whether the vehicle stops at the given edge */209bool stopsAtEdge(const MSEdge* edge) const;210211/// @brief returns the next edge (possibly an internal edge)212virtual const MSEdge* getNextEdgePtr() const {213return nullptr;214}215216/** @brief Returns the information whether the vehicle is on a road (is simulated)217* @return Whether the vehicle is simulated218*/219virtual bool isOnRoad() const {220return true;221}222223/** @brief Returns the information whether the vehicle is fully controlled224* via TraCI225* @return Whether the vehicle is remote-controlled226*/227virtual bool isRemoteControlled() const {228return false;229}230231virtual bool wasRemoteControlled(SUMOTime lookBack = DELTA_T) const {232UNUSED_PARAMETER(lookBack);233return false;234}235236/** @brief Returns the information whether the front of the vehhicle is on the given lane237* @return Whether the vehicle's front is on that lane238*/239virtual bool isFrontOnLane(const MSLane*) const {240return true;241}242243/** @brief Get the vehicle's lateral position on the lane244* @return The lateral position of the vehicle (in m relative to the245* centerline of the lane)246*/247virtual double getLateralPositionOnLane() const {248return 0;249}250251/** @brief Get the vehicle's lateral position on the edge of the given lane252* (or its current edge if lane == 0)253* @return The lateral position of the vehicle (in m distance between right254* side of vehicle and ride side of edge255*/256virtual double getRightSideOnEdge(const MSLane* lane = 0) const {257UNUSED_PARAMETER(lane);258return 0;259}260261/** @brief Returns the starting point for reroutes (usually the current edge)262*263* This differs from *myCurrEdge only if the vehicle is on an internal edge264* @return The rerouting start point265*/266virtual ConstMSEdgeVector::const_iterator getRerouteOrigin() const {267return myCurrEdge;268}269270/** @brief Returns the end point for reroutes (usually the last edge of the route)271*272* @return The rerouting end point273*/274virtual const MSEdge* getRerouteDestination() const {275return myRoute->getLastEdge();276}277278/** @brief Returns the time loss in seconds279*/280virtual double getTimeLossSeconds() const {281// better timeLoss for meso?282return 0;283}284285/** @brief Returns the number of seconds waited (speed was lesser than 0.1m/s)286*287* The value is reset if the vehicle moves faster than 0.1m/s288* Intentional stopping does not count towards this time.289* @return The time the vehicle is standing290*/291double getWaitingSeconds() const {292return STEPS2TIME(getWaitingTime());293}294295296297/** @brief Returns an iterator pointing to the current edge in this vehicles route298* @return The current route pointer299*/300const MSRouteIterator& getCurrentRouteEdge() const {301return myCurrEdge;302}303304305/** @brief Performs a rerouting using the given router306*307* Tries to find a new route between the current edge and the destination edge, first.308* Tries to replace the current route by the new one using replaceRoute.309*310* @param[in] t The time for which the route is computed311* @param[in] router The router to use312* @param[in] sink (optionally) a new destination edge313* @see replaceRoute314*/315bool reroute(SUMOTime t, const std::string& info, SUMOAbstractRouter<MSEdge, SUMOVehicle>& router, const bool onInit = false, const bool withTaz = false, const bool silent = false, const MSEdge* sink = nullptr);316317318/** @brief Replaces the current route by the given edges319*320* It is possible that the new route is not accepted, if a) it does not321* contain the vehicle's current edge, or b) something fails on insertion322* into the routes container (see in-line comments).323*324* @param[in] edges The new list of edges to pass325* @param[in] onInit Whether the vehicle starts with this route326* @param[in] check Whether the route should be checked for validity327* @param[in] removeStops Whether stops should be removed if they do not fit onto the new route328* @return Whether the new route was accepted329*/330bool replaceRouteEdges(ConstMSEdgeVector& edges, double cost, double savings, const std::string& info, bool onInit = false, bool check = false, bool removeStops = true,331std::string* msgReturn = nullptr);332333/** @brief Replaces the current route by the given one334*335* It is possible that the new route is not accepted, if it does not336* contain the vehicle's current edge.337*338* @param[in] route The new route to pass339* @param[in] info Information regarding the replacement340* @param[in] addRouteStops Whether stops from the replacement route should be added341* @param[in] removeStops Whether stops should be removed if they do not fit onto the new route342* @return Whether the new route was accepted343*/344virtual bool replaceRoute(ConstMSRoutePtr route, const std::string& info, bool onInit = false, int offset = 0, bool addRouteStops = true, bool removeStops = true,345std::string* msgReturn = nullptr);346347/** @brief Returns the vehicle's acceleration348*349* This default implementation returns always 0.350* @return The acceleration351*/352virtual double getAcceleration() const;353354/** @brief Called when the vehicle is inserted into the network355*356* Sets optional information about departure time, informs the vehicle357* control about a further running vehicle.358*/359void onDepart();360361/** @brief Returns this vehicle's real departure time362* @return This vehicle's real departure time363*/364inline SUMOTime getDeparture() const {365return myDeparture;366}367368/** @brief Returns the depart delay */369SUMOTime getDepartDelay() const;370371/** @brief Returns the estimated public transport stop (departure) delay in seconds372*/373virtual double getStopDelay() const {374/// @todo implement for meso375return -1;376}377378/** @brief Returns the estimated public transport stop arrival delay in seconds379*/380virtual double getStopArrivalDelay() const {381/// @todo implement for meso382return INVALID_DOUBLE;383}384385/// @brief return time (s) and distance to the next stop386virtual std::pair<double, double> estimateTimeToNextStop() const {387return std::make_pair(-1, -1);388}389390/** @brief Returns this vehicle's real departure position391* @return This vehicle's real departure position392*/393inline double getDepartPos() const {394return myDepartPos;395}396397/** @brief Returns this vehicle's desired arrivalPos for its current route398* (may change on reroute)399* @return This vehicle's real arrivalPos400*/401virtual double getArrivalPos() const {402return myArrivalPos;403}404405virtual int getArrivalLane() const {406return myArrivalLane;407}408409/** @brief Sets this vehicle's desired arrivalPos for its current route410*/411virtual void setArrivalPos(double arrivalPos) {412myArrivalPos = arrivalPos;413}414415/** @brief Called when the vehicle is removed from the network.416*417* Moves along work reminders and418* informs all devices about quitting. Calls "leaveLane" then.419*420* @param[in] reason why the vehicle leaves (reached its destination, parking, teleport)421*/422virtual void onRemovalFromNet(const MSMoveReminder::Notification /*reason*/) {}423424/** @brief Returns whether this vehicle has already departed425*/426inline bool hasDeparted() const {427return myDeparture != NOT_YET_DEPARTED;428}429430/** @brief Returns whether this vehicle has already arived431* (by default this is true if the vehicle has reached its final edge)432*/433virtual bool hasArrived() const;434435/// @brief return index of edge within route436int getRoutePosition() const;437438/// @brief return the number of edges remaining in the route (include the current)439int getNumRemainingEdges() const;440441int getArrivalIndex() const {442return myParameter->arrivalEdge;443}444445/// @brief reset index of edge within route446void resetRoutePosition(int index, DepartLaneDefinition departLaneProcedure);447448/** @brief Returns the distance that was already driven by this vehicle449* @return the distance driven [m]450*/451double getOdometer() const;452453/// @brief Manipulate the odometer454void addToOdometer(double value) {455myOdometer += value;456}457458/** @brief Returns the number of new routes this vehicle got459* @return the number of new routes this vehicle got460*/461inline int getNumberReroutes() const {462return myNumberReroutes;463}464465/// @brief Returns this vehicles impatience466double getImpatience() const;467468/** @brief Returns the number of persons469* @return The number of passengers on-board470*/471int getPersonNumber() const;472473/** @brief Returns the number of leaving persons474* @return The number of leaving passengers475*/476int getLeavingPersonNumber() const;477478/** @brief Returns the list of persons479* @return The list of passengers on-board480*/481std::vector<std::string> getPersonIDList() const;482483/** @brief Returns the number of containers484* @return The number of contaiers on-board485*/486int getContainerNumber() const;487488489/** @brief Returns this vehicle's devices490* @return This vehicle's devices491*/492inline const std::vector<MSVehicleDevice*>& getDevices() const {493return myDevices;494}495496/// @brief whether the given transportable is allowed to board this vehicle497bool allowsBoarding(const MSTransportable* t) const;498499/** @brief Adds a person or container to this vehicle500*501* @param[in] transportable The person/container to add502*/503virtual void addTransportable(MSTransportable* transportable);504505/// @brief removes a person or container506void removeTransportable(MSTransportable* t);507508/// @brief removes a person or containers mass509void removeTransportableMass(MSTransportable* t);510511/// @brief retrieve riding persons512const std::vector<MSTransportable*>& getPersons() const;513514/// @brief retrieve riding containers515const std::vector<MSTransportable*>& getContainers() const;516517/// @brief returns whether the vehicle serves a public transport line that serves the given stop518bool isLineStop(double position) const;519520/// @brief check wether the vehicle has jump at the given part of its route521bool hasJump(const MSRouteIterator& it) const;522523/** @brief Validates the current or given route524* @param[out] msg Description why the route is not valid (if it is the case)525* @param[in] route The route to check (or 0 if the current route shall be checked)526* @return Whether the vehicle's current route is valid527*/528bool hasValidRoute(std::string& msg, ConstMSRoutePtr route = 0) const;529530bool hasValidRoute(std::string& msg, MSRouteIterator start, MSRouteIterator last, bool checkJumps) const;531532/// @brief checks wether the vehicle can depart on the first edge533virtual bool hasValidRouteStart(std::string& msg);534535/// @brief check for route validity at first insertion attempt536int getRouteValidity(bool update = true, bool silent = false, std::string* msgReturn = nullptr);537538/// @brief Checks whether the vehilce has the given MoveReminder539bool hasReminder(MSMoveReminder* rem) const;540541/** @brief Adds a MoveReminder dynamically542*543* @param[in] rem the reminder to add544* @see MSMoveReminder545*/546void addReminder(MSMoveReminder* rem, double pos = 0);547548/** @brief Removes a MoveReminder dynamically549*550* @param[in] rem the reminder to remove551* @see MSMoveReminder552*/553void removeReminder(MSMoveReminder* rem);554555/** @brief "Activates" all current move reminder556*557* For all move reminder stored in "myMoveReminders", their method558* "MSMoveReminder::notifyEnter" is called.559*560* @param[in] reason The reason for changing the reminders' states561* @param[in] enteredLane The lane, which is entered (if applicable)562* @see MSMoveReminder563* @see MSMoveReminder::notifyEnter564* @see MSMoveReminder::Notification565*/566virtual void activateReminders(const MSMoveReminder::Notification reason, const MSLane* enteredLane = 0);567568569/** @brief Returns the vehicle's length570* @return vehicle's length571*/572inline double getLength() const {573return myType->getLength();574}575576/* @brief Return whether this vehicle must be treated like a railway vehicle577* either due to its vClass or the vClass of it's edge */578bool isRail() const;579580/** @brief Returns the vehicle's width581* @return vehicle's width582*/583inline double getWidth() const {584return myType->getWidth();585}586587588/** @brief Returns the precomputed factor by which the driver wants to be faster than the speed limit589* @return Speed limit factor590*/591inline double getChosenSpeedFactor() const {592return myChosenSpeedFactor;593}594595inline double getDesiredMaxSpeed() const {596return myType->getDesiredMaxSpeed() * myChosenSpeedFactor;597}598599/** @brief Returns the precomputed factor by which the driver wants to be faster than the speed limit600* @return Speed limit factor601*/602inline void setChosenSpeedFactor(const double factor) {603myChosenSpeedFactor = factor;604}605606/// @brief Returns a device of the given type if it exists, nullptr otherwise607MSDevice* getDevice(const std::type_info& type) const;608609610/** @brief Replaces the current vehicle type by the one given611*612* If the currently used vehicle type is marked as being used by this vehicle613* only, it is deleted, first. The new, given type is then assigned to614* "myType".615* @param[in] type The new vehicle type616* @see MSBaseVehicle::myType617*/618virtual void replaceVehicleType(const MSVehicleType* type);619620621/** @brief Replaces the current vehicle type with a new one used by this vehicle only622*623* If the currently used vehicle type is already marked as being used by this vehicle624* only, no new type is created.625* @return The new modifiable vehicle type626* @see MSBaseVehicle::myType627*/628MSVehicleType& getSingularType();629630/// @name state io631//@{632633/// Saves the (common) state of a vehicle634virtual void saveState(OutputDevice& out);635636//@}637638virtual bool handleCollisionStop(MSStop& stop, const double distToStop);639640/** @brief Returns whether the vehicle is at a stop641* @return Whether the vehicle has stopped642*/643bool isStopped() const;644645/** @brief Returns whether the vehicle is parking646* @return whether the vehicle is parking647*/648bool isParking() const;649650/** @brief Returns whether the vehicle is perform a jump651* @return whether the vehicle is starting to jump652*/653bool isJumping() const;654655/** @brief Returns whether the logical state of the vehicle is reversed - for drawing656* @return whether the logical state of the vehicle is reversed657*/658inline bool isReversed() const {659return myAmReversed;660}661662/** @brief Returns whether the vehicle is on a triggered stop663* @return whether the vehicle is on a triggered stop664*/665bool isStoppedTriggered() const;666667/** @brief Returns whether the vehicle is on a parking stop668* @return whether the vehicle is on a parking stop669*/670bool isStoppedParking() const;671672/** @brief return whether the given position is within range of the current stop673*/674bool isStoppedInRange(const double pos, const double tolerance, bool checkFuture = false) const;675676/** @brief Returns whether the vehicle has to stop somewhere677* @return Whether the vehicle has to stop somewhere678*/679bool hasStops() const {680return !myStops.empty();681}682683/** @brief replace the current parking area stop with a new stop with merge duration684*/685bool replaceParkingArea(MSParkingArea* parkingArea, std::string& errorMsg);686687/** @brief get the upcoming parking area stop or nullptr688*/689MSParkingArea* getNextParkingArea();690691/** @brief get the current parking area stop or nullptr */692MSParkingArea* getCurrentParkingArea();693694/// @brief get the valid parking access rights (vehicle settings override vehicle type settings)695const std::vector<std::string>& getParkingBadges() const;696697/// @brief departure position where the vehicle fits fully onto the edge (if possible)698double basePos(const MSEdge* edge) const;699700/** @brief Adds a stop701*702* The stop is put into the sorted list.703* @param[in] stop The stop to add704* @return Whether the stop could be added705*/706bool addStop(const SUMOVehicleParameter::Stop& stopPar, std::string& errorMsg, SUMOTime untilOffset = 0,707MSRouteIterator* searchStart = nullptr);708709/** @brief Adds stops to the built vehicle710*711* This code needs to be separated from the MSBaseVehicle constructor712* since it is not allowed to call virtual functions from a constructor713*714* @param[in] ignoreStopErrors whether invalid stops trigger a warning only715*/716void addStops(const bool ignoreStopErrors, MSRouteIterator* searchStart = nullptr, bool addRouteStops = true);717718/// @brief check whether all stop.edge MSRouteIterators are valid and in order719bool haveValidStopEdges(bool silent = false) const;720721/// @brief return list of route indices for the remaining stops722std::vector<std::pair<int, double> > getStopIndices() const;723724/**725* returns the list of stops not yet reached in the stop queue726* @return the list of upcoming stops727*/728inline const std::list<MSStop>& getStops() const {729return myStops;730}731732inline const StopParVector& getPastStops() const {733return myPastStops;734}735736/**737* returns the next imminent stop in the stop queue738* @return the upcoming stop739*/740const MSStop& getNextStop() const;741742/**743* returns the next imminent stop in the stop queue744* @return the upcoming stop745*/746MSStop& getNextStopMutable();747748/// @brief get remaining stop duration or 0 if the vehicle isn't stopped749SUMOTime getStopDuration() const;750751/**752* returns the upcoming stop with the given index in the stop queue753* @return an upcoming stop754*/755MSStop& getStop(int nextStopIndex);756757/// @brief return parameters for the next stop (SUMOVehicle Interface)758const SUMOVehicleParameter::Stop* getNextStopParameter() const;759760/**761* schedule a new stop for the vehicle; each time a stop is reached, the vehicle762* will wait for the given duration before continuing on its route763* @param[in] stop Stop parameters764* @param[out] errorMsg returned error message765*/766virtual bool addTraciStop(SUMOVehicleParameter::Stop stop, std::string& errorMsg);767768/**769* resumes a vehicle from stopping770* @return true on success, the resuming fails if the vehicle wasn't parking in the first place771*/772virtual bool resumeFromStopping() = 0;773774/// @brief mark vehicle as active775void unregisterWaiting();776777/// @brief deletes the next stop at the given index if it exists778bool abortNextStop(int nextStopIndex = 0);779780/**781* replace the next stop at the given index with the given stop parameters782* will wait for the given duration before continuing on its route783* The route between start other stops and destination will be kept unchanged and784* only the part around the replacement index will be adapted according to the new stop location785* @param[in] nextStopIndex The replacement index786* @param[in] stop Stop parameters787* @param[in] info The rerouting info788* @param[in] teleport Whether to cover the route to the replacement stop via teleporting789* @param[out] errorMsg returned error message790*/791bool replaceStop(int nextStopIndex, SUMOVehicleParameter::Stop stop, const std::string& info, bool teleport, std::string& errorMsg);792793/**794* reroute between stops nextStopIndex - 1 and nextStopIndex (defaults to current position / final edge) if the respective stops do not exist795* @param[in] nextStopIndex The replacement index796* @param[in] info The rerouting info797* @param[in] teleport Whether to cover the route between stops via teleporting798* @param[out] errorMsg returned error message799*/800bool rerouteBetweenStops(int nextStopIndex, const std::string& info, bool teleport, std::string& errorMsg);801802/**803* insert stop at the given index with the given stop parameters804* will wait for the given duration before continuing on its route805* The route will be adapted to pass the new stop edge but only from the previous stop (or start) to the new stop and only up to the next stop (or end).806* @param[in] nextStopIndex The replacement index807* @param[in] stop Stop parameters808* @param[in] info The rerouting info809* @param[in] teleport Whether to cover the route to the new stop via teleporting810* @param[out] errorMsg returned error message811*/812bool insertStop(int nextStopIndex, SUMOVehicleParameter::Stop stop, const std::string& info, bool teleport, std::string& errorMsg);813814815/// @brief whether this vehicle is selected in the GUI816virtual bool isSelected() const {817return false;818}819820/// @brief @return The index of the vehicle's associated RNG821int getRNGIndex() const;822823/// @brief @return The vehicle's associated RNG824SumoRNG* getRNG() const;825826inline NumericalID getNumericalID() const {827return myNumericalID;828}829830/// @brief return vehicle-specific random number831long long int getRandomSeed() const {832return myRandomSeed;833}834835const MSDevice_Transportable* getPersonDevice() const {836return myPersonDevice;837}838839const MSDevice_Transportable* getContainerDevice() const {840return myContainerDevice;841}842843/// @brief retrieve parameters for the energy consumption model844inline EnergyParams* getEmissionParameters() const {845if (myEnergyParams == nullptr) {846myEnergyParams = new EnergyParams(getVehicleType().getEmissionParameters());847}848return myEnergyParams;849}850851/// @name Emission retrieval852//@{853854/** @brief Returns emissions of the current state855* The value is always per 1s, so multiply by step length if necessary.856* @return The current emission857*/858template<PollutantsInterface::EmissionType ET>859double getEmissions() const {860if (isOnRoad() || isIdling()) {861return PollutantsInterface::compute(myType->getEmissionClass(), ET, getSpeed(), getAcceleration(), getSlope(), getEmissionParameters());862}863return 0.;864}865866/** @brief Returns actual state of charge of battery (Wh)867* RICE_CHECK: This may be a misnomer, SOC is typically percentage of the maximum battery capacity.868* @return The actual battery state of charge869*/870double getStateOfCharge() const;871872/** @brief Returns actual relative state of charge of battery (-)873* @return The actual relative battery state of charge, normalised to the maximum battery capacity.874*/875double getRelativeStateOfCharge() const;876877/** @brief Returns the energy charged to the battery in the current time step (Wh)878* @return The energy charged to the battery in the current time step.879*/880double getChargedEnergy() const;881882/** @brief Returns the maximum charge rate allowed by the battery in the current time step (W)883* @return The maximum charge rate in the current time step.884*/885double getMaxChargeRate() const;886887/** @brief Returns actual current (A) of ElecHybrid device888* RICE_CHECK: Is this the current consumed from the overhead wire or the current driving the powertrain of the vehicle?889* RICE_REV_JS: It is the current drawn from the overhead wire (value if the vehicle is not connected to overhead wire?)890* @return The current of ElecHybrid device891*/892double getElecHybridCurrent() const;893894/** @brief Returns noise emissions of the current state895* @return The noise produced896*/897double getHarmonoise_NoiseEmissions() const;898//@}899900/** @class Influencer901* @brief Changes the wished vehicle speed / lanes902*903* The class is used for passing velocities or velocity profiles obtained via TraCI to the vehicle.904* The speed adaptation is controlled by the stored speedTimeLine905* Additionally, the variables myConsiderSafeVelocity, myConsiderMaxAcceleration, and myConsiderMaxDeceleration906* control whether the safe velocity, the maximum acceleration, and the maximum deceleration907* have to be regarded.908*909* Furthermore this class is used to affect lane changing decisions according to910* LaneChangeMode and any given laneTimeLine911*/912class BaseInfluencer {913public:914/// @brief Constructor915BaseInfluencer();916917/// @brief Destructor918virtual ~BaseInfluencer() {}919920/// @brief Static initalization921static void init();922/// @brief Static cleanup923static void cleanup();924925926/// @brief return the current routing mode927double getExtraImpatience() const {928return myExtraImpatience;929}930931/** @brief Sets routing behavior932* @param[in] value an enum value controlling the different modes933*/934void setExtraImpatience(double value) {935myExtraImpatience = value;936}937938protected:939/// @brief dynamic impatience offset940double myExtraImpatience = 0;941942};943944945946/** @brief Returns the velocity/lane influencer947*948* If no influencer was existing before, one is built, first949* @return Reference to this vehicle's speed influencer950*/951virtual BaseInfluencer& getBaseInfluencer() = 0;952953virtual const BaseInfluencer* getBaseInfluencer() const = 0;954955virtual bool hasInfluencer() const = 0;956957/// @brief return routing mode (configures router choice but also handling of transient permission changes)958int getRoutingMode() const {959return myRoutingMode;960}961962/** @brief Sets routing behavior963* @param[in] value an enum value controlling the different modes964*/965void setRoutingMode(int value) {966myRoutingMode = value;967}968969970SUMOAbstractRouter<MSEdge, SUMOVehicle>& getRouterTT() const;971972/** @brief Returns the vehicle's internal edge travel times/efforts container973*974* If the vehicle does not have such a container, it is built.975* @return The vehicle's knowledge about edge weights976*/977const MSEdgeWeightsStorage& getWeightsStorage() const;978MSEdgeWeightsStorage& getWeightsStorage();979980/** @brief Returns the leader of the vehicle looking for a fixed distance.981*982* If the distance is not given it is calculated from the brake gap.983* The gap returned does not include the minGap.984* @param dist up to which distance to look at least for a leader985* @param considerCrossingFoes Whether vehicles on crossing foe links should be considered986* @return The leading vehicle together with the gap; (0, -1) if no leader was found.987*/988virtual std::pair<const MSVehicle* const, double> getLeader(double dist = 0, bool considerCrossingFoes = true) const {989UNUSED_PARAMETER(dist);990UNUSED_PARAMETER(considerCrossingFoes);991WRITE_WARNING(TL("getLeader not yet implemented for meso"));992return std::make_pair(nullptr, -1);993}994995/** @brief Returns the follower of the vehicle looking for a fixed distance.996*997* If the distance is not given it is set to the value of MSCFModel::brakeGap(2*roadSpeed, 4.5, 0)998* The gap returned does not include the minGap.999* If there are multiple followers, the one that maximizes the term (getSecureGap - gap) is returned.1000* @param dist up to which distance to look at least for a leader1001* @return The leading vehicle together with the gap; (0, -1) if no leader was found.1002*/1003virtual std::pair<const MSVehicle* const, double> getFollower(double dist = 0) const {1004UNUSED_PARAMETER(dist);1005WRITE_WARNING(TL("getFollower not yet implemented for meso"));1006return std::make_pair(nullptr, -1);1007}10081009/** @brief (Re-)Calculates the arrival position and lane from the vehicle parameters1010*/1011void calculateArrivalParams(bool onInit);10121013/// @brief apply departEdge and arrivalEdge attributes1014void setDepartAndArrivalEdge();10151016int getDepartEdge() const;10171018int getInsertionChecks() const;10191020/// @brief interpret stop lane on opposite side of the road1021static MSLane* interpretOppositeStop(SUMOVehicleParameter::Stop& stop);10221023/// @name state io1024//@{1025void rememberBlockedParkingArea(const MSStoppingPlace* pa, bool local);1026SUMOTime sawBlockedParkingArea(const MSStoppingPlace* pa, bool local) const;1027void rememberBlockedChargingStation(const MSStoppingPlace* cs, bool local);1028SUMOTime sawBlockedChargingStation(const MSStoppingPlace* cs, bool local) const;10291030/// @brief score only needed when running with gui1031void rememberParkingAreaScore(const MSStoppingPlace* pa, const std::string& score);1032void resetParkingAreaScores();1033void rememberChargingStationScore(const MSStoppingPlace* cs, const std::string& score);1034void resetChargingStationScores();10351036int getNumberParkingReroutes() const {1037return myNumberParkingReroutes;1038}1039void setNumberParkingReroutes(int value) {1040myNumberParkingReroutes = value;1041}10421043const StoppingPlaceMemory* getParkingMemory() const {1044return myParkingMemory;1045}10461047const StoppingPlaceMemory* getChargingMemory() const {1048return myChargingMemory;1049}1050//@}10511052struct StopEdgeInfo {10531054StopEdgeInfo(const MSEdge* _edge, double _priority, SUMOTime _arrival, double _pos, bool _isSink = false):1055edge(_edge), pos(_pos),1056priority(_priority),1057arrival(_arrival),1058isSink(_isSink) {}10591060const MSEdge* edge;1061double pos;1062double priority;1063SUMOTime arrival;1064bool isSink;1065const SUMOVehicleParameter::Stop* stopPar = nullptr;1066/// @brief values set during routing and used during optimization1067int routeIndex = -1;1068bool skipped = false;1069bool backtracked = false;1070SUMOTime delay = 0;1071/// @brief optional info about stopping place1072std::pair<std::string, SumoXMLTag> nameTag;1073/// @brief set when replacing stop with an alternative1074const MSEdge* origEdge = nullptr;10751076bool operator==(const StopEdgeInfo& o) const {1077return edge == o.edge;1078}1079bool operator!=(const StopEdgeInfo& o) const {1080return !(*this == o);1081}1082};10831084protected:1085/// @brief reset rail signal approach information1086virtual void resetApproachOnReroute() {};10871088/** @brief Returns the list of still pending stop edges1089* also returns the first and last stop position1090*/1091std::vector<StopEdgeInfo> getStopEdges(double& firstPos, double& lastPos, std::set<int>& jumps) const;10921093static double addStopPriority(double p1, double p2);10941095/// @brief replace stop with a same-name alternative that is on the route and return success1096bool replaceWithAlternative(std::list<MSStop>::iterator iter, const MSRouteIterator searchStart, const MSRouteIterator end);10971098protected:1099/// @brief This vehicle's parameter.1100const SUMOVehicleParameter* myParameter;11011102/// @brief This vehicle's route.1103ConstMSRoutePtr myRoute;11041105/// @brief This vehicle's type.1106const MSVehicleType* myType;11071108/// @brief Iterator to current route-edge1109MSRouteIterator myCurrEdge;11101111/// @brief A precomputed factor by which the driver wants to be faster than the speed limit1112double myChosenSpeedFactor;11131114/// @brief The vehicle's list of stops1115std::list<MSStop> myStops;11161117/// @brief The list of stops that the vehicle has already reached1118StopParVector myPastStops;11191120/// @name Move reminder structures1121/// @{11221123/// @brief Definition of a move reminder container1124// The double value holds the relative position offset, i.e.,1125// offset + vehicle-position - moveReminder-position = distance,1126// i.e. the offset is counted up when the vehicle continues to a1127// succeeding lane.1128typedef std::vector< std::pair<MSMoveReminder*, double> > MoveReminderCont;11291130/// @brief Currently relevant move reminders1131MoveReminderCont myMoveReminders;1132/// @}11331134/// @brief The devices this vehicle has1135std::vector<MSVehicleDevice*> myDevices;11361137/// @brief The passengers this vehicle may have1138MSDevice_Transportable* myPersonDevice;11391140/// @brief The containers this vehicle may have1141MSDevice_Transportable* myContainerDevice;11421143/// @brief The emission parameters this vehicle may have1144mutable EnergyParams* myEnergyParams;11451146/// @brief The real departure time1147SUMOTime myDeparture;11481149/// @brief The real depart position1150double myDepartPos;11511152/// @brief The position on the destination lane where the vehicle stops1153double myArrivalPos;11541155/// @brief The destination lane where the vehicle stops1156int myArrivalLane;11571158/// @brief The number of reroutings1159int myNumberReroutes;11601161/// @brief The offset when adding route stops with 'until' on route replacement1162SUMOTime myStopUntilOffset;11631164/// @brief A simple odometer to keep track of the length of the route already driven1165double myOdometer;11661167/// @brief status of the current vehicle route1168int myRouteValidity;11691170/// memory for parking search1171StoppingPlaceMemory* myParkingMemory = nullptr;1172StoppingPlaceMemory* myChargingMemory = nullptr;1173int myNumberParkingReroutes = 0;11741175/// @brief Whether this vehicle is registered as waiting for a person or container (for deadlock-recognition)1176bool myAmRegisteredAsWaiting = false;11771178/* @brief magic value for undeparted vehicles1179* @note: in previous versions this was -11180*/1181static const SUMOTime NOT_YET_DEPARTED;11821183static std::vector<MSTransportable*> myEmptyTransportableVector;11841185/* @brief The logical 'reversed' state of the vehicle - intended to be used by drawing functions1186* @note: only set by vClass rail reversing at the moment1187*/1188bool myAmReversed = false;11891190///@brief routing mode (see TraCIConstants.h)1191int myRoutingMode;11921193private:1194const NumericalID myNumericalID;11951196const long long int myRandomSeed;11971198/* @brief The vehicle's knowledge about edge efforts/travel times; @see MSEdgeWeightsStorage1199* @note member is initialized on first access */1200mutable MSEdgeWeightsStorage* myEdgeWeights;12011202MSEdgeWeightsStorage& _getWeightsStorage() const;12031204static NumericalID myCurrentNumericalIndex;12051206/// @brief init model parameters from generic params1207void initTransientModelParams();12081209/// @brief reconstruct flow id from vehicle id1210std::string getFlowID() const;12111212/// @brief remove route at the end of the simulation1213void checkRouteRemoval();12141215/// @brief helper function1216bool insertJump(int nextStopIndex, MSRouteIterator itStart, std::string& errorMsg);12171218/// @brief patch stop.pars.index to record the number of skipped candidate edges before stop.edge (in a looped route)1219void setSkips(MSStop& stop, int prevActiveStops);12201221/// @brief remove outdated driveways on reroute1222SUMOTime activateRemindersOnReroute(SUMOTime currentTime);12231224private:1225/// invalidated assignment operator1226MSBaseVehicle& operator=(const MSBaseVehicle& s) = delete;12271228#ifdef _DEBUG1229public:1230static void initMoveReminderOutput(const OptionsCont& oc);12311232protected:1233/// @brief optionally generate movereminder-output for this vehicle1234void traceMoveReminder(const std::string& type, MSMoveReminder* rem, double pos, bool keep) const;12351236/// @brief whether this vehicle shall trace its moveReminders1237const bool myTraceMoveReminders;1238private:1239/// @brief vehicles which shall trace their move reminders1240static std::set<std::string> myShallTraceMoveReminders;1241#endif124212431244};124512461247