44#define DEBUG_COND (veh->isSelected())
48#define DEBUG_COND2 (gDebugFlag1)
63 myHeadwayTime(vtype->getParameter().getCFParam(
SUMO_ATTR_TAU, 1.0)),
83 return speed * (headwayTime + 0.5 * speed / decel);
94 const int steps = int(speed / speedReduction);
95 return SPEED2DIST(steps * speed - speedReduction * steps * (steps + 1) / 2) + speed * headwayTime;
100MSCFModel::freeSpeed(
const double currentSpeed,
const double decel,
const double dist,
const double targetSpeed,
const bool onInsertion,
const double actionStepLength) {
116 const double y =
MAX2(0.0, ((sqrt((b + 2.0 * v) * (b + 2.0 * v) + 8.0 * b * dist) - b) * 0.5 - v) / b);
117 const double yFull = floor(y);
118 const double exactGap = (yFull * yFull + yFull) * 0.5 * b + yFull * v + (y > yFull ? v : 0.0);
119 const double fullSpeedGain = (yFull + (onInsertion ? 1. : 0.)) *
ACCEL2SPEED(decel);
120 return DIST2SPEED(
MAX2(0.0, dist - exactGap) / (yFull + 1)) + fullSpeedGain + targetSpeed;
135 assert(currentSpeed >= 0);
136 assert(targetSpeed >= 0);
138 const double dt = onInsertion ? 0 : actionStepLength;
139 const double v0 = currentSpeed;
140 const double vT = targetSpeed;
141 const double b = decel;
142 const double d = dist - NUMERICAL_EPS;
152 if (0.5 * (v0 + vT)*dt >= d) {
154 return v0 +
TS * (vT - v0) / actionStepLength;
156 const double q = ((dt * v0 - 2 * d) * b - vT * vT);
157 const double p = 0.5 * b * dt;
158 const double vN = -p + sqrt(p * p - q);
159 return v0 +
TS * (vN - v0) / actionStepLength;
170 const double maxDecel =
MAX2(
myDecel, leaderMaxDecel);
171 const double bgLeader =
brakeGap(leaderSpeed, maxDecel, 0);
189 const double oldV = veh->
getSpeed();
198 const double factor = fric == 1. ? 1. : -0.3491 * fric * fric + 0.8922 * fric + 0.4493;
213#ifdef DEBUG_FINALIZE_SPEED
215 std::cout <<
"\n" <<
SIMTIME <<
" FINALIZE_SPEED\n";
219 vMax =
MAX2(vMin, vMax);
221#ifdef DEBUG_FINALIZE_SPEED
222 double vDawdle = vNext;
224 assert(vNext >= vMin);
225 assert(vNext <= vMax);
228#ifdef DEBUG_FINALIZE_SPEED
229 double vPatchLC = vNext;
234 assert(vNext >= vMinEmergency);
235 assert(vNext <= vMax);
237#ifdef DEBUG_FINALIZE_SPEED
240 <<
"veh '" << veh->
getID() <<
"' oldV=" << oldV
245 <<
" vStop=" << vStop
246 <<
" vDawdle=" << vDawdle
247 <<
" vPatchLC=" << vPatchLC
248 <<
" vNext=" << vNext
264 if (remainingDelay >=
DELTA_T) {
269 return (
double)(
DELTA_T - remainingDelay) / (
double)
DELTA_T * vMax;
282 const double gap = (vNext - vL) *
355 double leaderMinDist = gap2pred +
distAfterTime(duration, predSpeed, -predMaxDecel);
360 const int a = (int)ceil(duration /
TS -
TS);
366 if (
gDebugFlag2) std::cout <<
" followSpeedTransient"
367 <<
" duration=" << duration
368 <<
" gap=" << gap2pred
369 <<
" leaderMinDist=" << leaderMinDist
374 <<
" x=" << (b + leaderMinDist) / duration
376 return (b + leaderMinDist) / duration;
381 while (bg < leaderMinDist) {
390 const double fullBrakingSeconds = sqrt(leaderMinDist * 2 /
myDecel);
391 if (fullBrakingSeconds >= duration) {
395 return leaderMinDist / duration + duration *
getMaxDecel() / 2;
397 return fullBrakingSeconds *
myDecel;
405 return (speed + 0.5 * accel * t) * t;
407 const double decel = -accel;
408 if (speed <= decel * t) {
422 const double speed2 = speed - t * decel;
423 return 0.5 * (speed + speed2) * t;
436 const double accelTime = accel == 0. ? 0. : (arrivalSpeed - currentSpeed) / accel;
437 const double accelWay = accelTime * (arrivalSpeed + currentSpeed) * 0.5;
438 if (dist >= accelWay) {
439 const double nonAccelWay = dist - accelWay;
441 return TIME2STEPS(accelTime + nonAccelWay / nonAccelSpeed);
445 return TIME2STEPS(-(currentSpeed - sqrt(currentSpeed * currentSpeed + 2 * accel * dist)) / accel);
454 if (dist < NUMERICAL_EPS) {
458 if ((accel < 0. && -0.5 * speed * speed / accel < dist) || (accel <= 0. && speed == 0.)) {
463 if (fabs(accel) < NUMERICAL_EPS) {
467 double p = speed / accel;
471 return (-p - sqrt(p * p + 2 * dist / accel));
476 double t1 = (maxSpeed - speed) / accel;
478 double d1 = speed * t1 + 0.5 * accel * t1 * t1;
481 return (-p + sqrt(p * p + 2 * dist / accel));
483 return (-p + sqrt(p * p + 2 * d1 / accel)) + (dist - d1) / maxSpeed;
497 assert(accel == decel);
499 assert(initialSpeed == 0);
500 assert(arrivalSpeed == 0);
501 assert(maxSpeed > 0);
504 double accelTime = (maxSpeed - initialSpeed) / accel;
506 double accelDist = accelTime * (initialSpeed + 0.5 * (maxSpeed - initialSpeed));
508 if (accelDist >= dist * 0.5) {
510 arrivalTime = 4 * sqrt(dist / accel);
513 const double constSpeedTime = (dist - accelDist * 2) / maxSpeed;
514 arrivalTime = accelTime + constSpeedTime;
522 assert(time > 0 || dist == 0);
525 }
else if (time * speed > 2 * dist) {
528 return - 0.5 * speed * speed / dist;
532 return 2 * (dist / time - speed) / time;
546 double arrivalSpeedBraking;
549 if (dist < currentSpeed) {
557 return arrivalSpeedBraking;
564MSCFModel::gapExtrapolation(
const double duration,
const double currentGap,
double v1,
double v2,
double a1,
double a2,
const double maxV1,
const double maxV2) {
566 double newGap = currentGap;
569 for (
unsigned int steps = 1; steps *
TS <= duration; ++steps) {
570 v1 =
MIN2(
MAX2(v1 + a1, 0.), maxV1);
571 v2 =
MIN2(
MAX2(v2 + a2, 0.), maxV2);
572 newGap +=
TS * (v1 - v2);
577 double t1 = 0, t2 = 0, t3 = 0, t4 = 0;
580 if (a1 < 0 && v1 > 0) {
581 const double leaderStopTime = - v1 / a1;
582 t1 =
MIN2(leaderStopTime, duration);
583 }
else if (a1 >= 0) {
587 if (a2 < 0 && v2 > 0) {
588 const double followerStopTime = -v2 / a2;
589 t2 =
MIN2(followerStopTime, duration);
590 }
else if (a2 >= 0) {
594 if (a1 > 0 && v1 < maxV1) {
595 const double leaderMaxSpeedTime = (maxV1 - v1) / a1;
596 t3 =
MIN2(leaderMaxSpeedTime, duration);
597 }
else if (a1 <= 0) {
601 if (a2 > 0 && v2 < maxV2) {
602 const double followerMaxSpeedTime = (maxV2 - v2) / a2;
603 t4 =
MIN2(followerMaxSpeedTime, duration);
604 }
else if (a2 <= 0) {
616 std::list<double>::const_iterator i;
618 for (i = l.begin(); i != l.end(); ++i) {
620 double dt =
MIN2(*i, duration) - tLast;
623 newGap += dv * dt + da * dt * dt / 2.;
627 if (*i == t1 || *i == t3) {
632 if (*i == t2 || *i == t4) {
637 tLast =
MIN2(*i, duration);
638 if (tLast == duration) {
643 if (duration != tLast) {
645 assert(a1 == 0. && a2 == 0.);
646 double dt = duration - tLast;
658MSCFModel::passingTime(
const double lastPos,
const double passedPos,
const double currentPos,
const double lastSpeed,
const double currentSpeed) {
660 assert(passedPos <= currentPos);
661 assert(passedPos >= lastPos);
662 assert(currentPos > lastPos);
663 assert(currentSpeed >= 0);
665 if (passedPos > currentPos || passedPos < lastPos) {
666 std::stringstream ss;
670 ss <<
"passingTime(): given argument passedPos = " << passedPos <<
" doesn't lie within [lastPos, currentPos] = [" << lastPos <<
", " << currentPos <<
"]\nExtrapolating...";
671 std::cout << ss.str() <<
"\n";
674 const double lastCoveredDist = currentPos - lastPos;
675 const double extrapolated = passedPos > currentPos ?
TS * (passedPos - lastPos) / lastCoveredDist :
TS * (currentPos - passedPos) / lastCoveredDist;
677 }
else if (currentSpeed < 0) {
678 WRITE_ERROR(
"passingTime(): given argument 'currentSpeed' is negative. This case is not handled yet.");
682 const double distanceOldToPassed = passedPos - lastPos;
686 if (currentSpeed == 0) {
689 const double t = distanceOldToPassed / currentSpeed;
697 if (currentSpeed > 0) {
702 assert(currentSpeed == 0 && lastSpeed != 0);
706 a = lastSpeed * lastSpeed / (2 * (lastPos - currentPos));
713 if (fabs(a) < NUMERICAL_EPS) {
715 const double t = 2 * distanceOldToPassed / (lastSpeed + currentSpeed);
719 const double va = lastSpeed / a;
720 const double t = -va + sqrt(va * va + 2 * distanceOldToPassed / a);
721 assert(t < 1 && t >= 0);
725 const double va = lastSpeed / a;
726 const double t = -va - sqrt(va * va + 2 * distanceOldToPassed / a);
738 assert(t >= 0 && t <=
TS);
746 if (dist <
TS * v0 / 2) {
749 const double accel = - v0 * v0 / (2 * dist);
751 return v0 + accel * t;
754 const double accel = 2 * (dist /
TS - v0) /
TS;
756 return v0 + accel * t;
768 (
double)sqrt(
MAX2(0., 2 * dist * accel + v * v)));
783#ifdef DEBUG_EMERGENCYDECEL
785 std::cout <<
SIMTIME <<
" maximumSafeStopSpeed()"
787 <<
" v=" << currentSpeed
788 <<
" initial vsafe=" << vsafe <<
"(decel=" <<
SPEED2ACCEL(v - vsafe) <<
")" << std::endl;
792 double origSafeDecel =
SPEED2ACCEL(currentSpeed - vsafe);
793 if (origSafeDecel >
myDecel + NUMERICAL_EPS) {
796#ifdef DEBUG_EMERGENCYDECEL
798 std::cout <<
SIMTIME <<
" maximumSafeStopSpeed() results in emergency deceleration "
799 <<
"initial vsafe=" << vsafe <<
" egoSpeed=" << v <<
"(decel=" <<
SPEED2ACCEL(v - vsafe) <<
")" << std::endl;
807 safeDecel =
MIN2(safeDecel, origSafeDecel);
810 vsafe =
MAX2(vsafe, 0.);
813#ifdef DEBUG_EMERGENCYDECEL
815 std::cout <<
" -> corrected emergency deceleration: " <<
SPEED2ACCEL(v - vsafe) << std::endl;
829 const double g = gap - NUMERICAL_EPS;
841 const double n = floor(.5 - ((t + (sqrt(((s * s) + (4.0 * ((s * (2.0 * g / b - t)) + (t * t))))) * -0.5)) / s));
842 const double h = 0.5 * n * (n - 1) * b * s + n * b * t;
843 assert(h <= g + NUMERICAL_EPS);
846 const double r = (g - h) / (n * s + t);
847 const double x = n * b + r;
857 const double g =
MAX2(0., gap - NUMERICAL_EPS);
873 const double btau = decel * headway;
874 const double v0 = -btau + sqrt(btau * btau + 2 * decel * g);
883 const double tau = headway == 0 ?
TS : headway;
884 const double v0 =
MAX2(0., currentSpeed);
886 if (v0 * tau >= 2 * g) {
898 const double a = -v0 * v0 / (2 * g);
913 const double btau2 = decel * tau / 2;
914 const double v1 = -btau2 + sqrt(btau2 * btau2 + decel * (2 * g - tau * v0));
915 const double a = (v1 - v0) / tau;
962 if (origSafeDecel >
myDecel + NUMERICAL_EPS) {
969#ifdef DEBUG_EMERGENCYDECEL
971 std::cout <<
SIMTIME <<
" initial vsafe=" << x
972 <<
" egoSpeed=" << egoSpeed <<
" (origSafeDecel=" << origSafeDecel <<
")"
973 <<
" predSpeed=" << predSpeed <<
" (predDecel=" << predMaxDecel <<
")"
974 <<
" safeDecel=" << safeDecel
981 safeDecel =
MIN2(safeDecel, origSafeDecel);
987#ifdef DEBUG_EMERGENCYDECEL
989 std::cout <<
" -> corrected emergency deceleration: " << safeDecel <<
" newVSafe=" << x << std::endl;
996 assert(!std::isnan(x));
1011 const double predBrakeDist = 0.5 * predSpeed * predSpeed / predMaxDecel;
1013 const double b1 = 0.5 * egoSpeed * egoSpeed / (gap + predBrakeDist);
1015#ifdef DEBUG_EMERGENCYDECEL
1017 std::cout <<
SIMTIME <<
" calculateEmergencyDeceleration()"
1018 <<
" gap=" << gap <<
" egoSpeed=" << egoSpeed <<
" predSpeed=" << predSpeed
1019 <<
" predBrakeDist=" << predBrakeDist
1025 if (b1 <= predMaxDecel) {
1027#ifdef DEBUG_EMERGENCYDECEL
1029 std::cout <<
" case 1 ..." << std::endl;
1034#ifdef DEBUG_EMERGENCYDECEL
1036 std::cout <<
" case 2 ...";
1042 const double b2 = 0.5 * (egoSpeed * egoSpeed - predSpeed * predSpeed) / gap;
1044#ifdef DEBUG_EMERGENCYDECEL
1046 std::cout <<
" b2=" << b2 << std::endl;
1071 const double perceivedGap = veh->
getDriverState()->getPerceivedHeadway(gap, pred);
1072 const double perceivedSpeedDifference = veh->
getDriverState()->getPerceivedSpeedDifference(predSpeed - speed, gap, pred);
1074#ifdef DEBUG_DRIVER_ERRORS
1078 std::cout <<
SIMTIME <<
" veh '" << veh->
getID() <<
"' -> MSCFModel_Krauss::applyHeadwayAndSpeedDifferencePerceptionErrors()\n"
1079 <<
" speed=" << speed <<
" gap=" << gap <<
" leaderSpeed=" << predSpeed
1080 <<
"\n perceivedGap=" << perceivedGap <<
" perceivedLeaderSpeed=" << speed + perceivedSpeedDifference
1081 <<
" perceivedSpeedDifference=" << perceivedSpeedDifference
1084 const double errorFollowSpeed =
followSpeed(veh, speed, perceivedGap, speed + perceivedSpeedDifference, predMaxDecel, pred,
CalcReason::FUTURE);
1085 const double accelError =
SPEED2ACCEL(errorFollowSpeed - exactFollowSpeed);
1086 std::cout <<
" gapError=" << perceivedGap - gap <<
" dvError=" << perceivedSpeedDifference - (predSpeed - speed)
1087 <<
"\n resulting accelError: " << accelError << std::endl;
1094 predSpeed = speed + perceivedSpeedDifference;
1109 const double perceivedGap = veh->
getDriverState()->getPerceivedHeadway(gap);
1111#ifdef DEBUG_DRIVER_ERRORS
1115 std::cout <<
SIMTIME <<
" veh '" << veh->
getID() <<
"' -> MSCFModel_Krauss::applyHeadwayPerceptionError()\n"
1116 <<
" speed=" << speed <<
" gap=" << gap <<
"\n perceivedGap=" << perceivedGap << std::endl;
1119 const double accelError =
SPEED2ACCEL(errorStopSpeed - exactStopSpeed);
1120 std::cout <<
" gapError=" << perceivedGap - gap <<
"\n resulting accelError: " << accelError << std::endl;
#define EMERGENCY_DECEL_AMPLIFIER
@ SUMO_ATTR_STARTUP_DELAY
@ SUMO_ATTR_APPARENTDECEL
@ SUMO_ATTR_EMERGENCYDECEL
@ SUMO_ATTR_COLLISION_MINGAP_FACTOR
int gPrecision
the precision for floating point outputs
const double INVALID_DOUBLE
invalid double
#define UNUSED_PARAMETER(x)
const double SUMO_const_haltingSpeed
the speed threshold at which vehicles are considered as halting
virtual double getSafetyFactor() const
return factor for modifying the safety constraints of the car-following model
virtual double patchSpeed(const double min, const double wanted, const double max, const MSCFModel &cfModel)=0
Called to adapt the speed in order to allow a lane change. It uses information on LC-related desired ...
virtual ~VehicleVariables()
double estimateSpeedAfterDistance(const double dist, const double v, const double accel) const
virtual double maxNextSpeed(double speed, const MSVehicle *const veh) const
Returns the maximum speed given the current speed.
static double gapExtrapolation(const double duration, const double currentGap, double v1, double v2, double a1=0, double a2=0, const double maxV1=std::numeric_limits< double >::max(), const double maxV2=std::numeric_limits< double >::max())
return the resulting gap if, starting with gap currentGap, two vehicles continue with constant accele...
virtual double minNextSpeedEmergency(double speed, const MSVehicle *const veh=0) const
Returns the minimum speed after emergency braking, given the current speed (depends on the numerical ...
virtual double followSpeedTransient(double duration, const MSVehicle *const veh, double speed, double gap2pred, double predSpeed, double predMaxDecel) const
Computes the vehicle's follow speed that avoids a collision for the given amount of time.
virtual double applyStartupDelay(const MSVehicle *veh, const double vMin, const double vMax, const SUMOTime addTime=0) const
apply speed adaptation on startup
static double brakeGapEuler(const double speed, const double decel, const double headwayTime)
virtual double interactionGap(const MSVehicle *const veh, double vL) const
Returns the maximum gap at which an interaction between both vehicles occurs.
static double avoidArrivalAccel(double dist, double time, double speed, double maxDecel)
Computes the acceleration needed to arrive not before the given time.
double getMinimalArrivalSpeed(double dist, double currentSpeed) const
Computes the minimal possible arrival speed after covering a given distance.
virtual double patchSpeedBeforeLC(const MSVehicle *veh, double vMin, double vMax) const
apply custom speed adaptations within the given speed bounds
virtual double freeSpeed(const MSVehicle *const veh, double speed, double seen, double maxSpeed, const bool onInsertion=false, const CalcReason usage=CalcReason::CURRENT) const
Computes the vehicle's safe speed without a leader.
virtual double minNextSpeed(double speed, const MSVehicle *const veh=0) const
Returns the minimum speed given the current speed (depends on the numerical update scheme and its ste...
virtual double insertionFollowSpeed(const MSVehicle *const veh, double speed, double gap2pred, double predSpeed, double predMaxDecel, const MSVehicle *const pred=0) const
Computes the vehicle's safe speed (no dawdling) This method is used during the insertion stage....
SUMOTime myStartupDelay
The startup delay after halting [s].
SUMOTime getMinimalArrivalTime(double dist, double currentSpeed, double arrivalSpeed) const
Computes the minimal time needed to cover a distance given the desired speed at arrival.
void applyHeadwayPerceptionError(const MSVehicle *const veh, double speed, double &gap) const
Overwrites gap by the perceived value obtained from the vehicle's driver state.
static double speedAfterTime(const double t, const double oldSpeed, const double dist)
Calculates the speed after a time t \in [0,TS] given the initial speed and the distance traveled in a...
static double passingTime(const double lastPos, const double passedPos, const double currentPos, const double lastSpeed, const double currentSpeed)
Calculates the time at which the position passedPosition has been passed In case of a ballistic updat...
virtual double finalizeSpeed(MSVehicle *const veh, double vPos) const
Applies interaction with stops and lane changing model influences. Called at most once per simulation...
virtual ~MSCFModel()
Destructor.
double maximumSafeStopSpeedEuler(double gap, double decel, bool onInsertion, double headway) const
Returns the maximum next velocity for stopping within gap when using the semi-implicit Euler update.
double myEmergencyDecel
The vehicle's maximum emergency deceleration [m/s^2].
void applyHeadwayAndSpeedDifferencePerceptionErrors(const MSVehicle *const veh, double speed, double &gap, double &predSpeed, double predMaxDecel, const MSVehicle *const pred) const
Overwrites gap2pred and predSpeed by the perceived values obtained from the vehicle's driver state,...
double maximumSafeFollowSpeed(double gap, double egoSpeed, double predSpeed, double predMaxDecel, bool onInsertion=false) const
Returns the maximum safe velocity for following the given leader.
CalcReason
What the return value of stop/follow/free-Speed is used for.
@ FUTURE
the return value is used for calculating future speeds
virtual double getSecureGap(const MSVehicle *const veh, const MSVehicle *const, const double speed, const double leaderSpeed, const double leaderMaxDecel) const
Returns the minimum gap to reserve if the leader is braking at maximum (>=0)
double calculateEmergencyDeceleration(double gap, double egoSpeed, double predSpeed, double predMaxDecel) const
Returns the minimal deceleration for following the given leader safely.
MSCFModel(const MSVehicleType *vtype)
Constructor.
double myDecel
The vehicle's maximum deceleration [m/s^2].
double getMaxAccel() const
Get the vehicle type's maximum acceleration [m/s^2].
double brakeGap(const double speed) const
Returns the distance the vehicle needs to halt including driver's reaction time tau (i....
double maximumSafeStopSpeed(double gap, double decel, double currentSpeed, bool onInsertion=false, double headway=-1, bool relaxEmergency=true) const
Returns the maximum next velocity for stopping within gap.
void applyOwnSpeedPerceptionError(const MSVehicle *const veh, double &speed) const
Overwrites sped by the perceived values obtained from the vehicle's driver state,.
const MSVehicleType * myType
The type to which this model definition belongs to.
virtual double distAfterTime(double t, double speed, double accel) const
calculates the distance traveled after accelerating for time t
double getMaxDecel() const
Get the vehicle type's maximal comfortable deceleration [m/s^2].
double maximumSafeStopSpeedBallistic(double gap, double decel, double currentSpeed, bool onInsertion=false, double headway=-1) const
Returns the maximum next velocity for stopping within gap when using the ballistic positional update.
double getMinimalArrivalSpeedEuler(double dist, double currentSpeed) const
Computes the minimal possible arrival speed after covering a given distance for Euler update.
static double estimateArrivalTime(double dist, double speed, double maxSpeed, double accel)
Computes the time needed to travel a distance dist given an initial speed and constant acceleration....
virtual double followSpeed(const MSVehicle *const veh, double speed, double gap2pred, double predSpeed, double predMaxDecel, const MSVehicle *const pred=0, const CalcReason usage=CalcReason::CURRENT) const =0
Computes the vehicle's follow speed (no dawdling)
double myHeadwayTime
The driver's desired time headway (aka reaction time tau) [s].
double stopSpeed(const MSVehicle *const veh, const double speed, double gap, const CalcReason usage=CalcReason::CURRENT) const
Computes the vehicle's safe speed for approaching a non-moving obstacle (no dawdling)
virtual double insertionStopSpeed(const MSVehicle *const veh, double speed, double gap) const
Computes the vehicle's safe speed for approaching an obstacle at insertion without constraints due to...
virtual double getHeadwayTime() const
Get the driver's desired headway [s].
static bool gSemiImplicitEulerUpdate
static bool gComputeLC
whether the simulationLoop is in the lane changing phase
double getVehicleMaxSpeed(const SUMOTrafficObject *const veh) const
Returns the lane's maximum speed, given a vehicle's speed limit adaptation.
Representation of a vehicle in the micro simulation.
SUMOTime getTimeSinceStartup() const
Returns the SUMOTime spent driving since startup (speed was larger than 0.1m/s)
bool hasDriverState() const
Whether this vehicle is equipped with a MSDriverState.
double getFriction() const
Returns the current friction on the road as perceived by the friction device.
MSAbstractLaneChangeModel & getLaneChangeModel()
double getActionStepLengthSecs() const
Returns the vehicle's action step length in secs, i.e. the interval between two action points.
double getAcceleration() const
Returns the vehicle's acceleration in m/s (this is computed as the last step's mean acceleration in c...
std::shared_ptr< MSSimpleDriverState > getDriverState() const
Returns the vehicle driver's state.
const MSLane * getLane() const
Returns the lane the vehicle is on.
double getSpeed() const
Returns the vehicle's current speed.
double processNextStop(double currentVelocity)
Processes stops, returns the velocity needed to reach the stop.
The car-following model and parameter.
double getMaxSpeed() const
Get vehicle's (technical) maximum speed [m/s].
const std::string & getID() const
Returns the id.
Structure representing possible vehicle parameter.