43#define INVALID_SPEED 299792458 + 1
175 void setState(
const std::string& state);
253 bool replaceRoute(
ConstMSRoutePtr route,
const std::string& info,
bool onInit =
false,
int offset = 0,
bool addStops =
true,
bool removeStops =
true, std::string* msgReturn =
nullptr);
748 void setAngle(
double angle,
bool straightenFurther =
false);
1067 std::pair<const MSVehicle* const, double>
getLeader(
double dist = 0)
const;
1077 std::pair<const MSVehicle* const, double>
getFollower(
double dist = 0)
const;
1229 std::vector<double>& furtherLanesPosLat,
1230 const std::vector<MSLane*>& passedLanes);
1403 static std::map<const MSVehicle*, GapControlState*>
refVehMap;
1425 void setSpeedTimeLine(
const std::vector<std::pair<SUMOTime, double> >& speedTimeLine);
1429 void activateGapController(
double originalTau,
double newTimeHeadway,
double newSpaceHeadway,
double duration,
double changeRate,
double maxDecel,
MSVehicle* refVeh =
nullptr);
1438 void setLaneTimeLine(
const std::vector<std::pair<SUMOTime, int> >& laneTimeLine);
1718 SUMOTime arrivalTime,
double arrivalSpeed,
1719 double arrivalSpeedBraking,
1720 double dist,
double leaveSpeed);
1764 void processLaneAdvances(std::vector<MSLane*>& passedLanes, std::string& emergencyReason);
1955 SUMOTime arrivalTime,
double arrivalSpeed,
1956 double arrivalSpeedBraking,
1958 double leaveSpeed) :
2031 void adaptToLeader(
const std::pair<const MSVehicle*, double> leaderInfo,
2034 double& v,
double& vLinkPass)
const;
2042 const MSLane*
const lane,
double& v,
double& vLinkPass,
2043 double distToCrossing = -1)
const;
2047 double& v,
double& vLinkPass)
const;
2068 DriveProcessItem*
const lastLink,
double& v,
double& vLinkPass,
double& vLinkWait,
bool& setRequest,
2069 bool isShadowLink =
false)
const;
2083 const double seen, DriveProcessItem*
const lastLink,
2084 const MSLane*
const lane,
double& v,
double& vLinkPass)
const;
2088 DriveProcessItem*
const lastLink,
2089 double& v,
double& vLinkPass)
const;
2094 DriveProcessItem*
const lastLink,
double& v,
double& vLinkPass,
double& vLinkWait,
bool& setRequest)
const;
std::vector< const MSEdge * > ConstMSEdgeVector
std::shared_ptr< const MSRoute > ConstMSRoutePtr
const double SUMO_const_haltingSpeed
the speed threshold at which vehicles are considered as halting
Interface for lane-change models.
The base class for microscopic and mesoscopic vehicles.
MSVehicleType * myType
This vehicle's type.
void addStops(const bool ignoreStopErrors, MSRouteIterator *searchStart=nullptr, bool addRouteStops=true)
Adds stops to the built vehicle.
const MSVehicleType & getVehicleType() const
Returns the vehicle's type definition.
The car-following model abstraction.
double getMaxAccel() const
Get the vehicle type's maximum acceleration [m/s^2].
The ToC Device controls transition of control between automated and manual driving.
A device which collects info on current friction Coefficient on the road.
Abstract in-vehicle / in-person device.
A road/street connecting two junctions.
static bool gSemiImplicitEulerUpdate
static SUMOTime gWaitingTimeMemory
length of memory for waiting times (in millisecs)
The base class for an intersection.
Performs lane changing of vehicles.
Performs lane changing of vehicles.
Representation of a lane in the micro simulation.
saves leader/follower vehicles and their distances relative to an ego vehicle
Something on a lane to be noticed about vehicle movement.
Notification
Definition of a vehicle state.
Interface for objects listening to vehicle state changes.
VehicleState
Definition of a vehicle state.
Definition of overhead wire segment.
A lane area vehicles can halt at.
Provides an interface to an error whose fluctuation is controlled via the driver's 'awareness',...
A lane area vehicles can halt at.
A static instance of this class in GapControlState deactivates gap control for vehicles whose referen...
void vehicleStateChanged(const SUMOVehicle *const vehicle, MSNet::VehicleState to, const std::string &info="")
Called if a vehicle changes its state.
Changes the wished vehicle speed / lanes.
void setLaneChangeMode(int value)
Sets lane changing behavior.
TraciLaneChangePriority myTraciLaneChangePriority
flags for determining the priority of traci lane change requests
bool getEmergencyBrakeRedLight() const
Returns whether red lights shall be a reason to brake.
SUMOTime getLaneTimeLineEnd()
void adaptLaneTimeLine(int indexShift)
Adapts lane timeline when moving to a new lane and the lane index changes.
void setRemoteControlled(Position xyPos, MSLane *l, double pos, double posLat, double angle, int edgeOffset, const ConstMSEdgeVector &route, SUMOTime t)
bool isRemoteAffected(SUMOTime t) const
int getSpeedMode() const
return the current speed mode
void deactivateGapController()
Deactivates the gap control.
void setSpeedMode(int speedMode)
Sets speed-constraining behaviors.
std::shared_ptr< GapControlState > myGapControlState
The gap control state.
bool considerSafeVelocity() const
Returns whether safe velocities shall be considered.
bool myConsiderMaxDeceleration
Whether the maximum deceleration shall be regarded.
ConstMSEdgeVector myRemoteRoute
void setLaneTimeLine(const std::vector< std::pair< SUMOTime, int > > &laneTimeLine)
Sets a new lane timeline.
bool myRespectJunctionLeaderPriority
Whether the junction priority rules are respected (within)
void setOriginalSpeed(double speed)
Stores the originally longitudinal speed.
double myOriginalSpeed
The velocity before influence.
double getLatDist() const
double implicitDeltaPosRemote(const MSVehicle *veh)
return the change in longitudinal position that is implicit in the new remote position
double implicitSpeedRemote(const MSVehicle *veh, double oldSpeed)
return the speed that is implicit in the new remote position
void postProcessRemoteControl(MSVehicle *v)
update position from remote control
double gapControlSpeed(SUMOTime currentTime, const SUMOVehicle *veh, double speed, double vSafe, double vMin, double vMax)
Applies gap control logic on the speed.
void setSublaneChange(double latDist)
Sets a new sublane-change request.
double getOriginalSpeed() const
Returns the originally longitudinal speed to use.
SUMOTime myLastRemoteAccess
std::vector< std::pair< SUMOTime, int > > myLaneTimeLine
The lane usage time line to apply.
bool getRespectJunctionLeaderPriority() const
Returns whether junction priority rules within the junction shall be respected (concerns vehicles wit...
LaneChangeMode myStrategicLC
lane changing which is necessary to follow the current route
LaneChangeMode mySpeedGainLC
lane changing to travel with higher speed
static void init()
Static initalization.
LaneChangeMode mySublaneLC
changing to the prefered lateral alignment
bool getRespectJunctionPriority() const
Returns whether junction priority rules shall be respected (concerns approaching vehicles outside the...
static void cleanup()
Static cleanup.
int getLaneChangeMode() const
return the current lane change mode
SUMOTime getLaneTimeLineDuration()
double influenceSpeed(SUMOTime currentTime, double speed, double vSafe, double vMin, double vMax)
Applies stored velocity information on the speed to use.
double changeRequestRemainingSeconds(const SUMOTime currentTime) const
Return the remaining number of seconds of the current laneTimeLine assuming one exists.
bool myConsiderSafeVelocity
Whether the safe velocity shall be regarded.
bool mySpeedAdaptationStarted
Whether influencing the speed has already started.
void setSignals(int signals)
double myLatDist
The requested lateral change.
bool myEmergencyBrakeRedLight
Whether red lights are a reason to brake.
LaneChangeMode myRightDriveLC
changing to the rightmost lane
void setSpeedTimeLine(const std::vector< std::pair< SUMOTime, double > > &speedTimeLine)
Sets a new velocity timeline.
void updateRemoteControlRoute(MSVehicle *v)
update route if provided by remote control
std::vector< std::pair< SUMOTime, double > > mySpeedTimeLine
The velocity time line to apply.
SUMOTime getLastAccessTimeStep() const
bool myConsiderMaxAcceleration
Whether the maximum acceleration shall be regarded.
LaneChangeMode myCooperativeLC
lane changing with the intent to help other vehicles
bool isRemoteControlled() const
bool ignoreOverlap() const
bool myRespectJunctionPriority
Whether the junction priority rules are respected (approaching)
int influenceChangeDecision(const SUMOTime currentTime, const MSEdge ¤tEdge, const int currentLaneIndex, int state)
Applies stored LaneChangeMode information and laneTimeLine.
void activateGapController(double originalTau, double newTimeHeadway, double newSpaceHeadway, double duration, double changeRate, double maxDecel, MSVehicle *refVeh=nullptr)
Activates the gap control with the given parameters,.
Container for manouevering time associated with stopping.
SUMOTime myManoeuvreCompleteTime
Time at which this manoeuvre should complete.
MSVehicle::ManoeuvreType getManoeuvreType() const
Accessor (get) for manoeuvre type.
std::string myManoeuvreStop
The name of the stop associated with the Manoeuvre - for debug output.
bool manoeuvreIsComplete() const
Check if any manoeuver is ongoing and whether the completion time is beyond currentTime.
bool configureExitManoeuvre(MSVehicle *veh)
Setup the myManoeuvre for exiting (Sets completion time and manoeuvre type)
void setManoeuvreType(const MSVehicle::ManoeuvreType mType)
Accessor (set) for manoeuvre type.
Manoeuvre & operator=(const Manoeuvre &manoeuvre)
Assignment operator.
std::string myManoeuvreVehicleID
The name of the vehicle associated with the Manoeuvre - for debug output.
ManoeuvreType myManoeuvreType
Manoeuvre type - currently entry, exit or none.
double getGUIIncrement() const
Accessor for GUI rotation step when parking (radians)
SUMOTime myManoeuvreStartTime
Time at which the Manoeuvre for this stop started.
bool operator!=(const Manoeuvre &manoeuvre)
Operator !=.
bool entryManoeuvreIsComplete(MSVehicle *veh)
Configure an entry manoeuvre if nothing is configured - otherwise check if complete.
bool configureEntryManoeuvre(MSVehicle *veh)
Setup the entry manoeuvre for this vehicle (Sets completion time and manoeuvre type)
Container that holds the vehicles driving state (position+speed).
double lastCoveredDist() const
previous Speed of this state
double myPosLat
the stored lateral position
double myPreviousSpeed
the speed at the begin of the previous time step
double myPos
the stored position
bool operator!=(const State &state)
Operator !=.
double mySpeed
the stored speed (should be >=0 at any time)
State & operator=(const State &state)
Assignment operator.
double posLat() const
Lateral Position of this state (m relative to the centerline of the lane).
double pos() const
Position of this state.
double speed() const
Speed of this state.
double backPos() const
back Position of this state
double myBackPos
the stored back position
Stores the waiting intervals over the previous seconds (memory is to be specified in ms....
void passTime(SUMOTime dt, bool waiting)
const std::string getState() const
SUMOTime cumulatedWaitingTime(SUMOTime memory=-1) const
std::deque< std::pair< SUMOTime, SUMOTime > > myWaitingIntervals
void setState(const std::string &state)
SUMOTime myMemorySize
the maximal memory to store
Representation of a vehicle in the micro simulation.
void setManoeuvreType(const MSVehicle::ManoeuvreType mType)
accessor function to myManoeuvre equivalent
TraciLaneChangePriority
modes for prioritizing traci lane change requests
const std::vector< double > & getFurtherLanesPosLat() const
double getRightSideOnEdge(const MSLane *lane=0) const
Get the vehicle's lateral position on the edge of the given lane (or its current edge if lane == 0)
bool wasRemoteControlled(SUMOTime lookBack=DELTA_T) const
Returns the information whether the vehicle is fully controlled via TraCI within the lookBack time.
void processLinkApproaches(double &vSafe, double &vSafeMin, double &vSafeMinDist)
This method iterates through the driveprocess items for the vehicle and adapts the given in/out param...
SUMOTime getTimeSinceStartup() const
Returns the SUMOTime spent driving since startup (speed was larger than 0.1m/s)
const MSLane * getPreviousLane(const MSLane *current, int &furtherIndex) const
void checkLinkLeader(const MSLink *link, const MSLane *lane, double seen, DriveProcessItem *const lastLink, double &v, double &vLinkPass, double &vLinkWait, bool &setRequest, bool isShadowLink=false) const
checks for link leaders on the given link
void checkRewindLinkLanes(const double lengthsInFront, DriveItemVector &lfLinks) const
runs heuristic for keeping the intersection clear in case of downstream jamming
MSVehicle(const MSVehicle &)
invalidated copy constructor
bool willStop() const
Returns whether the vehicle will stop on the current edge.
bool hasDriverState() const
Whether this vehicle is equipped with a MSDriverState.
static int nextLinkPriority(const std::vector< MSLane * > &conts)
get a numerical value for the priority of the upcoming link
double getTimeGapOnLane() const
Returns the time gap in seconds to the leader of the vehicle on the same lane.
void updateBestLanes(bool forceRebuild=false, const MSLane *startLane=0)
computes the best lanes to use in order to continue the route
bool myAmIdling
Whether the vehicle is trying to enter the network (eg after parking so engine is running)
SUMOTime myWaitingTime
The time the vehicle waits (is not faster than 0.1m/s) in seconds.
double getStopDelay() const
Returns the public transport stop delay in seconds.
double computeAngle() const
compute the current vehicle angle
double myTimeLoss
the time loss in seconds due to driving with less than maximum speed
SUMOTime myLastActionTime
Action offset (actions are taken at time myActionOffset + N*getActionStepLength()) Initialized to 0,...
ConstMSEdgeVector::const_iterator getRerouteOrigin() const
Returns the starting point for reroutes (usually the current edge)
bool hasArrivedInternal(bool oppositeTransformed=true) const
Returns whether this vehicle has already arived (reached the arrivalPosition on its final edge) metho...
double getFriction() const
Returns the current friction on the road as perceived by the friction device.
bool ignoreFoe(const SUMOTrafficObject *foe) const
decide whether a given foe object may be ignored
void boardTransportables(MSStop &stop)
board persons and load transportables at the given stop
const std::vector< const MSLane * > getUpcomingLanesUntil(double distance) const
Returns the upcoming (best followed by default 0) sequence of lanes to continue the route starting at...
bool isOnRoad() const
Returns the information whether the vehicle is on a road (is simulated)
void adaptLaneEntering2MoveReminder(const MSLane &enteredLane)
Adapts the vehicle's entering of a new lane.
void addTransportable(MSTransportable *transportable)
Adds a person or container to this vehicle.
SUMOTime myJunctionConflictEntryTime
SUMOTime getLastActionTime() const
Returns the time of the vehicle's last action point.
double getLeftSideOnEdge(const MSLane *lane=0) const
Get the vehicle's lateral position on the edge of the given lane (or its current edge if lane == 0)
PositionVector getBoundingPoly(double offset=0) const
get bounding polygon
void setTentativeLaneAndPosition(MSLane *lane, double pos, double posLat=0)
set tentative lane and position during insertion to ensure that all cfmodels work (some of them requi...
bool brakeForOverlap(const MSLink *link, const MSLane *lane) const
handle with transitions
void workOnMoveReminders(double oldPos, double newPos, double newSpeed)
Processes active move reminder.
bool isStoppedOnLane() const
double getDistanceToPosition(double destPos, const MSLane *destLane) const
bool brokeDown() const
Returns how long the vehicle has been stopped already due to lack of energy.
double myAcceleration
The current acceleration after dawdling in m/s.
void registerInsertionApproach(MSLink *link, double dist)
register approach on insertion
SUMOTime getTimeLoss() const
Returns the SUMOTime lost (speed was lesser maximum speed)
void cleanupFurtherLanes()
remove vehicle from further lanes (on leaving the network)
void adaptToLeaders(const MSLeaderInfo &ahead, double latOffset, const double seen, DriveProcessItem *const lastLink, const MSLane *const lane, double &v, double &vLinkPass) const
bool isActive() const
Returns whether the current simulation step is an action point for the vehicle.
const MSLane * getBackLane() const
Returns the lane the where the rear of the object is currently at.
double getTimeLossSeconds() const
Returns the time loss in seconds.
void enterLaneAtInsertion(MSLane *enteredLane, double pos, double speed, double posLat, MSMoveReminder::Notification notification)
Update when the vehicle enters a new lane in the emit step.
double getBackPositionOnLane() const
Get the vehicle's position relative to its current lane.
void setPreviousSpeed(double prevSpeed, double prevAcceleration)
Sets the influenced previous speed.
const std::pair< double, const MSLink * > & getNextTurn()
Get the distance and direction of the next upcoming turn for the vehicle (within its look-ahead range...
SUMOTime getArrivalTime(SUMOTime t, double seen, double v, double arrivalSpeed) const
double getAccumulatedWaitingSeconds() const
Returns the number of seconds waited (speed was lesser than 0.1m/s) within the last millisecs.
SUMOTime getWaitingTime(const bool accumulated=false) const
Returns the SUMOTime waited (speed was lesser than 0.1m/s)
bool isFrontOnLane(const MSLane *lane) const
Returns the information whether the front of the vehicle is on the given lane.
virtual ~MSVehicle()
Destructor.
double getTimeSinceStartupSeconds() const
void processLaneAdvances(std::vector< MSLane * > &passedLanes, std::string &emergencyReason)
This method checks if the vehicle has advanced over one or several lanes along its route and triggers...
MSAbstractLaneChangeModel & getLaneChangeModel()
void setEmergencyBlueLight(SUMOTime currentTime)
sets the blue flashing light for emergency vehicles
bool isActionStep(SUMOTime t) const
Returns whether the next simulation step will be an action point for the vehicle.
MSAbstractLaneChangeModel * myLaneChangeModel
Position getPositionAlongBestLanes(double offset) const
Return the (x,y)-position, which the vehicle would reach if it continued along its best continuation ...
bool hasValidRouteStart(std::string &msg)
checks wether the vehicle can depart on the first edge
double getLeftSideOnLane() const
Get the lateral position of the vehicles left side on the lane:
std::vector< MSLane * > myFurtherLanes
The information into which lanes the vehicle laps into.
bool signalSet(int which) const
Returns whether the given signal is on.
MSCFModel::VehicleVariables * myCFVariables
The per vehicle variables of the car following model.
bool betterContinuation(const LaneQ *bestConnectedNext, const LaneQ &m) const
comparison between different continuations from the same lane
double getActionStepLengthSecs() const
Returns the vehicle's action step length in secs, i.e. the interval between two action points.
bool addTraciStop(SUMOVehicleParameter::Stop stop, std::string &errorMsg)
void checkLinkLeaderCurrentAndParallel(const MSLink *link, const MSLane *lane, double seen, DriveProcessItem *const lastLink, double &v, double &vLinkPass, double &vLinkWait, bool &setRequest) const
checks for link leaders of the current link as well as the parallel link (if there is one)
void planMoveInternal(const SUMOTime t, MSLeaderInfo ahead, DriveItemVector &lfLinks, double &myStopDist, std::pair< double, const MSLink * > &myNextTurn) const
std::pair< double, const MSLink * > myNextTurn
the upcoming turn for the vehicle
double getDistanceToLeaveJunction() const
get the distance from the start of this lane to the start of the next normal lane (or 0 if this lane ...
int influenceChangeDecision(int state)
allow TraCI to influence a lane change decision
double getMaxSpeedOnLane() const
Returns the maximal speed for the vehicle on its current lane (including speed factor and deviation,...
bool isRemoteControlled() const
Returns the information whether the vehicle is fully controlled via TraCI.
bool myAmOnNet
Whether the vehicle is on the network (not parking, teleported, vaporized, or arrived)
double nextStopDist() const
return the distance to the next stop or doubleMax if there is none.
void enterLaneAtMove(MSLane *enteredLane, bool onTeleporting=false)
Update when the vehicle enters a new lane in the move step.
void adaptBestLanesOccupation(int laneIndex, double density)
update occupation from MSLaneChanger
std::pair< double, double > estimateTimeToNextStop() const
return time (s) and distance to the next stop
double accelThresholdForWaiting() const
maximum acceleration to consider a vehicle as 'waiting' at low speed
void setAngle(double angle, bool straightenFurther=false)
Set a custom vehicle angle in rad, optionally updates furtherLanePosLat.
std::vector< LaneQ >::iterator myCurrentLaneInBestLanes
MSVehicle & operator=(const MSVehicle &)
invalidated assignment operator
double getDeltaPos(const double accel) const
calculates the distance covered in the next integration step given an acceleration and assuming the c...
const MSLane * myLastBestLanesInternalLane
void updateOccupancyAndCurrentBestLane(const MSLane *startLane)
updates LaneQ::nextOccupation and myCurrentLaneInBestLanes
const std::vector< MSLane * > getUpstreamOppositeLanes() const
Returns the sequence of opposite lanes corresponding to past lanes.
WaitingTimeCollector myWaitingTimeCollector
void setRemoteState(Position xyPos)
sets position outside the road network
void fixPosition()
repair errors in vehicle position after changing between internal edges
double getAcceleration() const
Returns the vehicle's acceleration in m/s (this is computed as the last step's mean acceleration in c...
double getSpeedWithoutTraciInfluence() const
Returns the uninfluenced velocity.
PositionVector getBoundingBox(double offset=0) const
get bounding rectangle
ManoeuvreType
flag identifying which, if any, manoeuvre is in progress
@ MANOEUVRE_ENTRY
Manoeuvre into stopping place.
@ MANOEUVRE_NONE
not manouevring
@ MANOEUVRE_EXIT
Manoeuvre out of stopping place.
const MSEdge * getNextEdgePtr() const
returns the next edge (possibly an internal edge)
Position getPosition(const double offset=0) const
Return current position (x/y, cartesian)
void setBrakingSignals(double vNext)
sets the braking lights on/off
const std::vector< MSLane * > & getBestLanesContinuation() const
Returns the best sequence of lanes to continue the route starting at myLane.
const MSEdge * myLastBestLanesEdge
bool ignoreCollision() const
whether this vehicle is except from collision checks
Influencer * myInfluencer
An instance of a velocity/lane influencing instance; built in "getInfluencer".
void saveState(OutputDevice &out)
Saves the states of a vehicle.
void setIdling(bool amIdling)
access function for Idling flag used to record whether vehicle is waiting to enter lane (after parkin...
void onRemovalFromNet(const MSMoveReminder::Notification reason)
Called when the vehicle is removed from the network.
void planMove(const SUMOTime t, const MSLeaderInfo &ahead, const double lengthsInFront)
Compute safe velocities for the upcoming lanes based on positions and speeds from the last time step....
bool resumeFromStopping()
int getBestLaneOffset() const
void adaptToJunctionLeader(const std::pair< const MSVehicle *, double > leaderInfo, const double seen, DriveProcessItem *const lastLink, const MSLane *const lane, double &v, double &vLinkPass, double distToCrossing=-1) const
double lateralDistanceToLane(const int offset) const
Get the minimal lateral distance required to move fully onto the lane at given offset.
double getBackPositionOnLane(const MSLane *lane) const
Get the vehicle's position relative to the given lane.
void leaveLaneBack(const MSMoveReminder::Notification reason, const MSLane *leftLane)
Update of reminders if vehicle back leaves a lane during (during forward movement.
void resetActionOffset(const SUMOTime timeUntilNextAction=0)
Resets the action offset for the vehicle.
std::vector< DriveProcessItem > DriveItemVector
Container for used Links/visited Lanes during planMove() and executeMove.
void interpolateLateralZ(Position &pos, double offset, double posLat) const
perform lateral z interpolation in elevated networks
void setBlinkerInformation()
sets the blue flashing light for emergency vehicles
const MSEdge * getCurrentEdge() const
Returns the edge the vehicle is currently at (possibly an internal edge or nullptr)
void adaptToLeaderDistance(const MSLeaderDistanceInfo &ahead, double latOffset, double seen, DriveProcessItem *const lastLink, double &v, double &vLinkPass) const
DriveItemVector::iterator myNextDriveItem
iterator pointing to the next item in myLFLinkLanes
void leaveLane(const MSMoveReminder::Notification reason, const MSLane *approachedLane=0)
Update of members if vehicle leaves a new lane in the lane change step or at arrival.
bool isIdling() const
Returns whether a sim vehicle is waiting to enter a lane (after parking has completed)
std::shared_ptr< MSSimpleDriverState > getDriverState() const
Returns the vehicle driver's state.
void removeApproachingInformation(const DriveItemVector &lfLinks) const
unregister approach from all upcoming links
void replaceVehicleType(MSVehicleType *type)
Replaces the current vehicle type by the one given.
SUMOTime myJunctionEntryTimeNeverYield
double getLatOffset(const MSLane *lane) const
Get the offset that that must be added to interpret myState.myPosLat for the given lane.
bool rerouteParkingArea(const std::string &parkingAreaID, std::string &errorMsg)
bool hasArrived() const
Returns whether this vehicle has already arived (reached the arrivalPosition on its final edge)
void switchOffSignal(int signal)
Switches the given signal off.
void updateState(double vNext)
updates the vehicles state, given a next value for its speed. This value can be negative in case of t...
double getStopArrivalDelay() const
Returns the estimated public transport stop arrival delay in seconds.
int getSignals() const
Returns the signals.
int mySignals
State of things of the vehicle that can be on or off.
bool setExitManoeuvre()
accessor function to myManoeuvre equivalent
bool isOppositeLane(const MSLane *lane) const
whether the give lane is reverse direction of the current route or not
double myStopDist
distance to the next stop or doubleMax if there is none
Signalling
Some boolean values which describe the state of some vehicle parts.
@ VEH_SIGNAL_EMERGENCY_RED
A red emergency light is on.
@ VEH_SIGNAL_NONE
Everything is switched off.
@ VEH_SIGNAL_FOGLIGHT
The fog lights are on (no visualisation)
@ VEH_SIGNAL_FRONTLIGHT
The front lights are on (no visualisation)
@ VEH_SIGNAL_DOOR_OPEN_LEFT
One of the left doors is opened.
@ VEH_SIGNAL_BLINKER_RIGHT
Right blinker lights are switched on.
@ VEH_SIGNAL_BRAKELIGHT
The brake lights are on.
@ VEH_SIGNAL_BACKDRIVE
The backwards driving lights are on (no visualisation)
@ VEH_SIGNAL_EMERGENCY_BLUE
A blue emergency light is on.
@ VEH_SIGNAL_BLINKER_LEFT
Left blinker lights are switched on.
@ VEH_SIGNAL_DOOR_OPEN_RIGHT
One of the right doors is opened.
@ VEH_SIGNAL_BLINKER_EMERGENCY
Blinker lights on both sides are switched on.
@ VEH_SIGNAL_WIPER
The wipers are on.
@ VEH_SIGNAL_EMERGENCY_YELLOW
A yellow emergency light is on.
@ VEH_SIGNAL_HIGHBEAM
The high beam lights are on (no visualisation)
SUMOTime getActionStepLength() const
Returns the vehicle's action step length in millisecs, i.e. the interval between two action points.
bool myHaveToWaitOnNextLink
SUMOTime collisionStopTime() const
Returns the remaining time a vehicle needs to stop due to a collision. A negative value indicates tha...
const std::vector< const MSLane * > getPastLanesUntil(double distance) const
Returns the sequence of past lanes (right-most on edge) based on the route starting at the current la...
double getBestLaneDist() const
returns the distance that can be driven without lane change
std::pair< const MSVehicle *const, double > getLeader(double dist=0) const
Returns the leader of the vehicle looking for a fixed distance.
double slowDownForSchedule(double vMinComfortable) const
optionally return an upper bound on speed to stay within the schedule
bool executeMove()
Executes planned vehicle movements with regards to right-of-way.
const MSLane * getLane() const
Returns the lane the vehicle is on.
std::pair< const MSVehicle *const, double > getFollower(double dist=0) const
Returns the follower of the vehicle looking for a fixed distance.
double getLastStepDist() const
Get the distance the vehicle covered in the previous timestep.
void invalidateCachedPosition()
ChangeRequest
Requests set via TraCI.
@ REQUEST_HOLD
vehicle want's to keep the current lane
@ REQUEST_LEFT
vehicle want's to change to left lane
@ REQUEST_NONE
vehicle doesn't want to change
@ REQUEST_RIGHT
vehicle want's to change to right lane
bool isLeader(const MSLink *link, const MSVehicle *veh, const double gap) const
whether the given vehicle must be followed at the given junction
void computeFurtherLanes(MSLane *enteredLane, double pos, bool collision=false)
updates myFurtherLanes on lane insertion or after collision
MSLane * getMutableLane() const
Returns the lane the vehicle is on Non const version indicates that something volatile is going on.
std::pair< const MSLane *, double > getLanePosAfterDist(double distance) const
return lane and position along bestlanes at the given distance
SUMOTime myCollisionImmunity
amount of time for which the vehicle is immune from collisions
bool passingMinor() const
decide whether the vehicle is passing a minor link or has comitted to do so
void updateWaitingTime(double vNext)
Updates the vehicle's waiting time counters (accumulated and consecutive)
void enterLaneAtLaneChange(MSLane *enteredLane)
Update when the vehicle enters a new lane in the laneChange step.
BaseInfluencer & getBaseInfluencer()
Returns the velocity/lane influencer.
Influencer & getInfluencer()
bool isBidiOn(const MSLane *lane) const
whether this vehicle is driving against lane
double getRightSideOnLane() const
Get the lateral position of the vehicles right side on the lane:
bool unsafeLinkAhead(const MSLane *lane) const
whether the vehicle may safely move to the given lane with regard to upcoming links
double getCurrentApparentDecel() const
get apparent deceleration based on vType parameters and current acceleration
double updateFurtherLanes(std::vector< MSLane * > &furtherLanes, std::vector< double > &furtherLanesPosLat, const std::vector< MSLane * > &passedLanes)
update a vector of further lanes and return the new backPos
DriveItemVector myLFLinkLanesPrev
planned speeds from the previous step for un-registering from junctions after the new container is fi...
std::vector< std::vector< LaneQ > > myBestLanes
void setActionStepLength(double actionStepLength, bool resetActionOffset=true)
Sets the action steplength of the vehicle.
double getLateralPositionOnLane() const
Get the vehicle's lateral position on the lane.
double getSlope() const
Returns the slope of the road at vehicle's position in degrees.
bool myActionStep
The flag myActionStep indicates whether the current time step is an action point for the vehicle.
const Position getBackPosition() const
void loadState(const SUMOSAXAttributes &attrs, const SUMOTime offset)
Loads the state of this vehicle from the given description.
SUMOTime myTimeSinceStartup
duration of driving (speed > SUMO_const_haltingSpeed) after the last halting episode
double getSpeed() const
Returns the vehicle's current speed.
void setApproachingForAllLinks(const SUMOTime t)
Register junction approaches for all link items in the current plan.
SUMOTime remainingStopDuration() const
Returns the remaining stop duration for a stopped vehicle or 0.
bool keepStopping(bool afterProcessing=false) const
Returns whether the vehicle is stopped and must continue to do so.
void workOnIdleReminders()
cycle through vehicle devices invoking notifyIdle
static std::vector< MSLane * > myEmptyLaneVector
Position myCachedPosition
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.
MSVehicle::ManoeuvreType getManoeuvreType() const
accessor function to myManoeuvre equivalent
double checkReversal(bool &canReverse, double speedThreshold=SUMO_const_haltingSpeed, double seen=0) const
void updateLaneBruttoSum()
Update the lane brutto occupancy after a change in minGap.
void removePassedDriveItems()
Erase passed drive items from myLFLinkLanes (and unregister approaching information for corresponding...
const std::vector< MSLane * > & getFurtherLanes() const
const std::vector< LaneQ > & getBestLanes() const
Returns the description of best lanes to use in order to continue the route.
std::vector< double > myFurtherLanesPosLat
lateral positions on further lanes
bool checkActionStep(const SUMOTime t)
Returns whether the vehicle is supposed to take action in the current simulation step Updates myActio...
const MSCFModel & getCarFollowModel() const
Returns the vehicle's car following model definition.
Position validatePosition(Position result, double offset=0) const
ensure that a vehicle-relative position is not invalid
void loadPreviousApproaching(MSLink *link, bool setRequest, SUMOTime arrivalTime, double arrivalSpeed, double arrivalSpeedBraking, double dist, double leaveSpeed)
bool keepClear(const MSLink *link) const
decide whether the given link must be kept clear
bool manoeuvreIsComplete() const
accessor function to myManoeuvre equivalent
double processNextStop(double currentVelocity)
Processes stops, returns the velocity needed to reach the stop.
double myAngle
the angle in radians (
bool ignoreRed(const MSLink *link, bool canBrake) const
decide whether a red (or yellow light) may be ignored
double getPositionOnLane() const
Get the vehicle's position along the lane.
void updateTimeLoss(double vNext)
Updates the vehicle's time loss.
MSDevice_DriverState * myDriverState
This vehicle's driver state.
bool joinTrainPart(MSVehicle *veh)
try joining the given vehicle to the rear of this one (to resolve joinTriggered)
MSLane * myLane
The lane the vehicle is on.
bool onFurtherEdge(const MSEdge *edge) const
whether this vehicle has its back (and no its front) on the given edge
double processTraCISpeedControl(double vSafe, double vNext)
Check for speed advices from the traci client and adjust the speed vNext in the current (euler) / aft...
double getLateralOverlap() const
return the amount by which the vehicle extends laterally outside it's primary lane
double getAngle() const
Returns the vehicle's direction in radians.
bool handleCollisionStop(MSStop &stop, const double distToStop)
bool hasInfluencer() const
whether the vehicle is individually influenced (via TraCI or special parameters)
MSDevice_Friction * myFrictionDevice
This vehicle's friction perception.
double getPreviousSpeed() const
Returns the vehicle's speed before the previous time step.
MSCFModel::VehicleVariables * getCarFollowVariables() const
Returns the vehicle's car following model variables.
MSVehicle()
invalidated default constructor
bool joinTrainPartFront(MSVehicle *veh)
try joining the given vehicle to the front of this one (to resolve joinTriggered)
void updateActionOffset(const SUMOTime oldActionStepLength, const SUMOTime newActionStepLength)
Process an updated action step length value (only affects the vehicle's action offset,...
double getBrakeGap(bool delayed=false) const
get distance for coming to a stop (used for rerouting checks)
void executeFractionalMove(double dist)
move vehicle forward by the given distance during insertion
LaneChangeMode
modes for resolving conflicts between external control (traci) and vehicle control over lane changing...
virtual void drawOutsideNetwork(bool)
register vehicle for drawing while outside the network
void adaptToOncomingLeader(const std::pair< const MSVehicle *, double > leaderInfo, DriveProcessItem *const lastLink, double &v, double &vLinkPass) const
State myState
This Vehicles driving state (pos and speed)
double getCenterOnEdge(const MSLane *lane=0) const
Get the vehicle's lateral position on the edge of the given lane (or its current edge if lane == 0)
void setLateralPositionOnLane(double posLat)
void adaptToLeader(const std::pair< const MSVehicle *, double > leaderInfo, double seen, DriveProcessItem *const lastLink, double &v, double &vLinkPass) const
void switchOnSignal(int signal)
Switches the given signal on.
static bool overlap(const MSVehicle *veh1, const MSVehicle *veh2)
void updateParkingState()
update state while parking
DriveItemVector myLFLinkLanes
container for the planned speeds in the current step
void updateDriveItems()
Check whether the drive items (myLFLinkLanes) are up to date, and update them if required.
Position getVelocityVector() const
Returns the vehicle's direction in radians.
SUMOTime myJunctionEntryTime
time at which the current junction was entered
The car-following model and parameter.
double getLengthWithGap() const
Get vehicle's length including the minimum gap [m].
double getActionStepLengthSecs() const
Returns this type's default action step length in seconds.
const MSCFModel & getCarFollowModel() const
Returns the vehicle type's car following model definition (const version)
SUMOTime getActionStepLength() const
Returns this type's default action step length.
Static storage of an output device and its base (abstract) implementation.
A point in 2D or 3D with translation and scaling methods.
static const Position INVALID
used to indicate that a position is valid
Encapsulated SAX-Attributes.
Representation of a vehicle, person, or container.
Representation of a vehicle.
Definition of vehicle stop (position and duration)
Structure representing possible vehicle parameter.
Drive process items represent bounds on the safe velocity corresponding to the upcoming links.
void adaptStopSpeed(const double v)
DriveProcessItem(MSLink *link, double vPass, double vWait, bool setRequest, SUMOTime arrivalTime, double arrivalSpeed, double arrivalSpeedBraking, double distance, double leaveSpeed)
double getLeaveSpeed() const
DriveProcessItem(double vWait, double distance, double _availableSpace=0)
constructor if the link shall not be passed
void adaptLeaveSpeed(const double v)
double myArrivalSpeedBraking
Container for state and parameters of the gap control.
bool active
Whether the gap control is active.
static std::map< const MSVehicle *, GapControlState * > refVehMap
stores reference vehicles currently in use by a gapController
SUMOTime lastUpdate
Time of the last update of the gap control.
double changeRate
Rate by which the current time and space headways are changed towards the target value....
double addGapTarget
Target value for the desired space headway.
static GapControlVehStateListener vehStateListener
double timeHeadwayIncrement
cache storage for the headway increments of the current operation
double tauOriginal
Original value for the desired headway (will be reset after duration has expired)
double tauCurrent
Current, interpolated value for the desired time headway.
double remainingDuration
Remaining duration for keeping the target headway.
void activate(double tauOriginal, double tauTarget, double additionalGap, double duration, double changeRate, double maxDecel, const MSVehicle *refVeh)
Start gap control with given params.
double addGapCurrent
Current, interpolated value for the desired space headway.
static void cleanup()
Static cleanup (removes vehicle state listener)
double tauTarget
Target value for the desired time headway.
virtual ~GapControlState()
void deactivate()
Stop gap control.
const MSVehicle * referenceVeh
reference vehicle for the gap - if it is null, the current leader on the ego's lane is used as a refe...
double maxDecel
Maximal deceleration to be applied due to the adapted headway.
bool gapAttained
Whether the desired gap was attained during the current activity phase (induces the remaining duratio...
double spaceHeadwayIncrement
const MSVehicle * prevLeader
The last recognized leader.
static void init()
Static initalization (adds vehicle state listener)
A structure representing the best lanes for continuing the current route starting at 'lane'.
double length
The overall length which may be driven when using this lane without a lane change.
bool allowsContinuation
Whether this lane allows to continue the drive.
double nextOccupation
As occupation, but without the first lane.
std::vector< MSLane * > bestContinuations
MSLane * lane
The described lane.
double currentLength
The length which may be driven on this lane.
int bestLaneOffset
The (signed) number of lanes to be crossed to get to the lane which allows to continue the drive.
double occupation
The overall vehicle sum on consecutive lanes which can be passed without a lane change.