44#define DEBUG_COND (veh->isSelected())
48#define DEBUG_COND2 (gDebugFlag1)
63 myHeadwayTime(vtype->getParameter().getCFParam(
SUMO_ATTR_TAU, 1.0)),
85 return speed * (headwayTime + 0.5 * speed / decel);
96 const int steps = int(speed / speedReduction);
97 return SPEED2DIST(steps * speed - speedReduction * steps * (steps + 1) / 2) + speed * headwayTime;
102MSCFModel::freeSpeed(
const double currentSpeed,
const double decel,
const double dist,
const double targetSpeed,
const bool onInsertion,
const double actionStepLength) {
118 const double y =
MAX2(0.0, ((sqrt((b + 2.0 * v) * (b + 2.0 * v) + 8.0 * b * dist) - b) * 0.5 - v) / b);
119 const double yFull = floor(y);
120 const double exactGap = (yFull * yFull + yFull) * 0.5 * b + yFull * v + (y > yFull ? v : 0.0);
121 const double fullSpeedGain = (yFull + (onInsertion ? 1. : 0.)) *
ACCEL2SPEED(decel);
122 return DIST2SPEED(
MAX2(0.0, dist - exactGap) / (yFull + 1)) + fullSpeedGain + targetSpeed;
137 assert(currentSpeed >= 0);
138 assert(targetSpeed >= 0);
140 const double dt = onInsertion ? 0 : actionStepLength;
141 const double v0 = currentSpeed;
142 const double vT = targetSpeed;
143 const double b = decel;
144 const double d = dist - NUMERICAL_EPS;
154 if (0.5 * (v0 + vT)*dt >= d) {
156 return v0 +
TS * (vT - v0) / actionStepLength;
158 const double q = ((dt * v0 - 2 * d) * b - vT * vT);
159 const double p = 0.5 * b * dt;
160 const double vN = -p + sqrt(p * p - q);
161 return v0 +
TS * (vN - v0) / actionStepLength;
102MSCFModel::freeSpeed(
const double currentSpeed,
const double decel,
const double dist,
const double targetSpeed,
const bool onInsertion,
const double actionStepLength) {
…}
172 const double maxDecel =
MAX2(
myDecel, leaderMaxDecel);
173 const double bgLeader =
brakeGap(leaderSpeed, maxDecel, 0);
191 const double oldV = veh->
getSpeed();
200 const double factor = fric == 1. ? 1. : -0.3491 * fric * fric + 0.8922 * fric + 0.4493;
215#ifdef DEBUG_FINALIZE_SPEED
217 std::cout <<
"\n" <<
SIMTIME <<
" FINALIZE_SPEED\n";
221 vMax =
MAX2(vMin, vMax);
223#ifdef DEBUG_FINALIZE_SPEED
224 double vDawdle = vNext;
226 assert(vNext >= vMin);
227 assert(vNext <= vMax);
230#ifdef DEBUG_FINALIZE_SPEED
231 double vPatchLC = vNext;
236 assert(vNext >= vMinEmergency);
237 assert(vNext <= vMax);
239#ifdef DEBUG_FINALIZE_SPEED
242 <<
"veh '" << veh->
getID() <<
"' oldV=" << oldV
247 <<
" vStop=" << vStop
248 <<
" vDawdle=" << vDawdle
249 <<
" vPatchLC=" << vPatchLC
250 <<
" vNext=" << vNext
266 if (remainingDelay >=
DELTA_T) {
271 return (
double)(
DELTA_T - remainingDelay) / (
double)
DELTA_T * vMax;
282 if (speed < profile[0].first) {
283 val = profile[0].second;
284 }
else if (speed > profile.back().first) {
285 val = profile.back().second;
288 while (speed > profile[x + 1].first) {
291 double diff = (profile[x + 1].second - profile[x].second) / (profile[x + 1].first - profile[x].first);
292 val = profile[x].second + diff * (speed - profile[x].first);
304 const double gap = (vNext - vL) *
377 double leaderMinDist = gap2pred +
distAfterTime(duration, predSpeed, -predMaxDecel);
382 const int a = (int)ceil(duration /
TS -
TS);
388 if (
gDebugFlag2) std::cout <<
" followSpeedTransient"
389 <<
" duration=" << duration
390 <<
" gap=" << gap2pred
391 <<
" leaderMinDist=" << leaderMinDist
396 <<
" x=" << (b + leaderMinDist) / duration
398 return (b + leaderMinDist) / duration;
403 while (bg < leaderMinDist) {
412 const double fullBrakingSeconds = sqrt(leaderMinDist * 2 /
myDecel);
413 if (fullBrakingSeconds >= duration) {
417 return leaderMinDist / duration + duration *
getMaxDecel() / 2;
419 return fullBrakingSeconds *
myDecel;
427 return (speed + 0.5 * accel * t) * t;
429 const double decel = -accel;
430 if (speed <= decel * t) {
444 const double speed2 = speed - t * decel;
445 return 0.5 * (speed + speed2) * t;
458 const double accelTime = accel == 0. ? 0. : (arrivalSpeed - currentSpeed) / accel;
459 const double accelWay = accelTime * (arrivalSpeed + currentSpeed) * 0.5;
460 if (dist >= accelWay) {
461 const double nonAccelWay = dist - accelWay;
463 return TIME2STEPS(accelTime + nonAccelWay / nonAccelSpeed);
467 return TIME2STEPS(-(currentSpeed - sqrt(currentSpeed * currentSpeed + 2 * accel * dist)) / accel);
476 if (dist < NUMERICAL_EPS) {
480 if ((accel < 0. && -0.5 * speed * speed / accel < dist) || (accel <= 0. && speed == 0.)) {
485 if (fabs(accel) < NUMERICAL_EPS) {
489 double p = speed / accel;
493 return (-p - sqrt(p * p + 2 * dist / accel));
498 double t1 = (maxSpeed - speed) / accel;
500 double d1 = speed * t1 + 0.5 * accel * t1 * t1;
503 return (-p + sqrt(p * p + 2 * dist / accel));
505 return (-p + sqrt(p * p + 2 * d1 / accel)) + (dist - d1) / maxSpeed;
519 assert(accel == decel);
521 assert(initialSpeed == 0);
522 assert(arrivalSpeed == 0);
523 assert(maxSpeed > 0);
526 double accelTime = (maxSpeed - initialSpeed) / accel;
528 double accelDist = accelTime * (initialSpeed + 0.5 * (maxSpeed - initialSpeed));
530 if (accelDist >= dist * 0.5) {
532 arrivalTime = 4 * sqrt(dist / accel);
535 const double constSpeedTime = (dist - accelDist * 2) / maxSpeed;
536 arrivalTime = accelTime + constSpeedTime;
544 assert(time > 0 || dist == 0);
547 }
else if (time * speed > 2 * dist) {
550 return - 0.5 * speed * speed / dist;
554 return 2 * (dist / time - speed) / time;
568 double arrivalSpeedBraking;
571 if (dist < currentSpeed) {
579 return arrivalSpeedBraking;
586MSCFModel::gapExtrapolation(
const double duration,
const double currentGap,
double v1,
double v2,
double a1,
double a2,
const double maxV1,
const double maxV2) {
588 double newGap = currentGap;
591 for (
unsigned int steps = 1; steps *
TS <= duration; ++steps) {
592 v1 =
MIN2(
MAX2(v1 + a1, 0.), maxV1);
593 v2 =
MIN2(
MAX2(v2 + a2, 0.), maxV2);
594 newGap +=
TS * (v1 - v2);
599 double t1 = 0, t2 = 0, t3 = 0, t4 = 0;
602 if (a1 < 0 && v1 > 0) {
603 const double leaderStopTime = - v1 / a1;
604 t1 =
MIN2(leaderStopTime, duration);
605 }
else if (a1 >= 0) {
609 if (a2 < 0 && v2 > 0) {
610 const double followerStopTime = -v2 / a2;
611 t2 =
MIN2(followerStopTime, duration);
612 }
else if (a2 >= 0) {
616 if (a1 > 0 && v1 < maxV1) {
617 const double leaderMaxSpeedTime = (maxV1 - v1) / a1;
618 t3 =
MIN2(leaderMaxSpeedTime, duration);
619 }
else if (a1 <= 0) {
623 if (a2 > 0 && v2 < maxV2) {
624 const double followerMaxSpeedTime = (maxV2 - v2) / a2;
625 t4 =
MIN2(followerMaxSpeedTime, duration);
626 }
else if (a2 <= 0) {
638 std::list<double>::const_iterator i;
640 for (i = l.begin(); i != l.end(); ++i) {
642 double dt =
MIN2(*i, duration) - tLast;
645 newGap += dv * dt + da * dt * dt / 2.;
649 if (*i == t1 || *i == t3) {
654 if (*i == t2 || *i == t4) {
659 tLast =
MIN2(*i, duration);
660 if (tLast == duration) {
665 if (duration != tLast) {
667 assert(a1 == 0. && a2 == 0.);
668 double dt = duration - tLast;
586MSCFModel::gapExtrapolation(
const double duration,
const double currentGap,
double v1,
double v2,
double a1,
double a2,
const double maxV1,
const double maxV2) {
…}
680MSCFModel::passingTime(
const double lastPos,
const double passedPos,
const double currentPos,
const double lastSpeed,
const double currentSpeed) {
682 assert(passedPos <= currentPos);
683 assert(passedPos >= lastPos);
684 assert(currentPos > lastPos);
685 assert(currentSpeed >= 0);
687 if (passedPos > currentPos || passedPos < lastPos) {
688 std::stringstream ss;
692 ss <<
"passingTime(): given argument passedPos = " << passedPos <<
" doesn't lie within [lastPos, currentPos] = [" << lastPos <<
", " << currentPos <<
"]\nExtrapolating...";
693 std::cout << ss.str() <<
"\n";
696 const double lastCoveredDist = currentPos - lastPos;
697 const double extrapolated = passedPos > currentPos ?
TS * (passedPos - lastPos) / lastCoveredDist :
TS * (currentPos - passedPos) / lastCoveredDist;
699 }
else if (currentSpeed < 0) {
700 WRITE_ERROR(
"passingTime(): given argument 'currentSpeed' is negative. This case is not handled yet.");
704 const double distanceOldToPassed = passedPos - lastPos;
708 if (currentSpeed == 0) {
711 const double t = distanceOldToPassed / currentSpeed;
719 if (currentSpeed > 0) {
724 assert(currentSpeed == 0 && lastSpeed != 0);
728 a = lastSpeed * lastSpeed / (2 * (lastPos - currentPos));
735 if (fabs(a) < NUMERICAL_EPS) {
737 const double t = 2 * distanceOldToPassed / (lastSpeed + currentSpeed);
741 const double va = lastSpeed / a;
742 const double t = -va + sqrt(va * va + 2 * distanceOldToPassed / a);
743 assert(t < 1 && t >= 0);
747 const double va = lastSpeed / a;
748 const double t = -va - sqrt(va * va + 2 * distanceOldToPassed / a);
680MSCFModel::passingTime(
const double lastPos,
const double passedPos,
const double currentPos,
const double lastSpeed,
const double currentSpeed) {
…}
760 assert(t >= 0 && t <=
TS);
768 if (dist <
TS * v0 / 2) {
771 const double accel = - v0 * v0 / (2 * dist);
773 return v0 + accel * t;
776 const double accel = 2 * (dist /
TS - v0) /
TS;
778 return v0 + accel * t;
790 (
double)sqrt(
MAX2(0., 2 * dist * accel + v * v)));
805#ifdef DEBUG_EMERGENCYDECEL
807 std::cout <<
SIMTIME <<
" maximumSafeStopSpeed()"
809 <<
" v=" << currentSpeed
810 <<
" initial vsafe=" << vsafe <<
"(decel=" <<
SPEED2ACCEL(v - vsafe) <<
")" << std::endl;
814 double origSafeDecel =
SPEED2ACCEL(currentSpeed - vsafe);
815 if (origSafeDecel >
myDecel + NUMERICAL_EPS) {
818#ifdef DEBUG_EMERGENCYDECEL
820 std::cout <<
SIMTIME <<
" maximumSafeStopSpeed() results in emergency deceleration "
821 <<
"initial vsafe=" << vsafe <<
" egoSpeed=" << v <<
"(decel=" <<
SPEED2ACCEL(v - vsafe) <<
")" << std::endl;
829 safeDecel =
MIN2(safeDecel, origSafeDecel);
832 vsafe =
MAX2(vsafe, 0.);
835#ifdef DEBUG_EMERGENCYDECEL
837 std::cout <<
" -> corrected emergency deceleration: " <<
SPEED2ACCEL(v - vsafe) << std::endl;
851 const double g = gap - NUMERICAL_EPS;
863 const double n = floor(.5 - ((t + (sqrt(((s * s) + (4.0 * ((s * (2.0 * g / b - t)) + (t * t))))) * -0.5)) / s));
864 const double h = 0.5 * n * (n - 1) * b * s + n * b * t;
865 assert(h <= g + NUMERICAL_EPS);
868 const double r = (g - h) / (n * s + t);
869 const double x = n * b + r;
879 const double g =
MAX2(0., gap - NUMERICAL_EPS);
895 const double btau = decel * headway;
896 const double v0 = -btau + sqrt(btau * btau + 2 * decel * g);
905 const double tau = headway == 0 ?
TS : headway;
906 const double v0 =
MAX2(0., currentSpeed);
909 if (g <= v0 * tau * 0.5) {
921 const double a = -v0 * v0 / (2 * g);
938 const double btau2 = decel * tau / 2;
939 const double v1 = -btau2 + sqrt(btau2 * btau2 + decel * (2 * g - tau * v0));
940 const double a = (v1 - v0) / tau;
987 if (origSafeDecel >
myDecel + NUMERICAL_EPS) {
994#ifdef DEBUG_EMERGENCYDECEL
996 std::cout <<
SIMTIME <<
" initial vsafe=" << x
997 <<
" egoSpeed=" << egoSpeed <<
" (origSafeDecel=" << origSafeDecel <<
")"
998 <<
" predSpeed=" << predSpeed <<
" (predDecel=" << predMaxDecel <<
")"
999 <<
" safeDecel=" << safeDecel
1006 safeDecel =
MIN2(safeDecel, origSafeDecel);
1012#ifdef DEBUG_EMERGENCYDECEL
1014 std::cout <<
" -> corrected emergency deceleration: " << safeDecel <<
" newVSafe=" << x << std::endl;
1021 assert(!std::isnan(x));
1036 const double predBrakeDist = 0.5 * predSpeed * predSpeed / predMaxDecel;
1038 const double b1 = 0.5 * egoSpeed * egoSpeed / (gap + predBrakeDist);
1040#ifdef DEBUG_EMERGENCYDECEL
1042 std::cout <<
SIMTIME <<
" calculateEmergencyDeceleration()"
1043 <<
" gap=" << gap <<
" egoSpeed=" << egoSpeed <<
" predSpeed=" << predSpeed
1044 <<
" predBrakeDist=" << predBrakeDist
1050 if (b1 <= predMaxDecel) {
1052#ifdef DEBUG_EMERGENCYDECEL
1054 std::cout <<
" case 1 ..." << std::endl;
1059#ifdef DEBUG_EMERGENCYDECEL
1061 std::cout <<
" case 2 ...";
1067 const double b2 = 0.5 * (egoSpeed * egoSpeed - predSpeed * predSpeed) / gap;
1069#ifdef DEBUG_EMERGENCYDECEL
1071 std::cout <<
" b2=" << b2 << std::endl;
1096 const double perceivedGap = veh->
getDriverState()->getPerceivedHeadway(gap, pred);
1097 const double perceivedSpeedDifference = veh->
getDriverState()->getPerceivedSpeedDifference(predSpeed - speed, gap, pred);
1099#ifdef DEBUG_DRIVER_ERRORS
1103 std::cout <<
SIMTIME <<
" veh '" << veh->
getID() <<
"' -> MSCFModel_Krauss::applyHeadwayAndSpeedDifferencePerceptionErrors()\n"
1104 <<
" speed=" << speed <<
" gap=" << gap <<
" leaderSpeed=" << predSpeed
1105 <<
"\n perceivedGap=" << perceivedGap <<
" perceivedLeaderSpeed=" << speed + perceivedSpeedDifference
1106 <<
" perceivedSpeedDifference=" << perceivedSpeedDifference
1109 const double errorFollowSpeed =
followSpeed(veh, speed, perceivedGap, speed + perceivedSpeedDifference, predMaxDecel, pred,
CalcReason::FUTURE);
1110 const double accelError =
SPEED2ACCEL(errorFollowSpeed - exactFollowSpeed);
1111 std::cout <<
" gapError=" << perceivedGap - gap <<
" dvError=" << perceivedSpeedDifference - (predSpeed - speed)
1112 <<
"\n resulting accelError: " << accelError << std::endl;
1119 predSpeed = speed + perceivedSpeedDifference;
1134 const double perceivedGap = veh->
getDriverState()->getPerceivedHeadway(gap);
1136#ifdef DEBUG_DRIVER_ERRORS
1140 std::cout <<
SIMTIME <<
" veh '" << veh->
getID() <<
"' -> MSCFModel_Krauss::applyHeadwayPerceptionError()\n"
1141 <<
" speed=" << speed <<
" gap=" << gap <<
"\n perceivedGap=" << perceivedGap << std::endl;
1144 const double accelError =
SPEED2ACCEL(errorStopSpeed - exactStopSpeed);
1145 std::cout <<
" gapError=" << perceivedGap - gap <<
"\n resulting accelError: " << accelError << std::endl;
#define EMERGENCY_DECEL_AMPLIFIER
@ SUMO_ATTR_STARTUP_DELAY
@ SUMO_ATTR_MAXACCEL_PROFILE
@ SUMO_ATTR_APPARENTDECEL
@ SUMO_ATTR_EMERGENCYDECEL
@ SUMO_ATTR_COLLISION_MINGAP_FACTOR
@ SUMO_ATTR_DESACCEL_PROFILE
int gPrecision
the precision for floating point outputs
const double INVALID_DOUBLE
invalid double
const double SUMO_const_haltingSpeed
the speed threshold at which vehicles are considered as halting
static double getInterpolatedValue(const LinearApproxMap &map, double axisValue)
Get interpolated value.
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.
virtual double getCurrentAccel(const double speed) const
Get the vehicle type's maximum acceleration [m/s^2].
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,.
virtual double interpolateProfile(const double speed, const std::vector< std::pair< double, double > > profile) const
Get current interpolated value from a profile.
LinearApproxHelpers::LinearApproxMap myMaxAccelProfile
The vehicle's maximum acceleration profile [m/s^2].
double myAccel
The vehicle's maximum acceleration [m/s^2].
LinearApproxHelpers::LinearApproxMap myDesAccelProfile
The vehicle's desired acceleration profile [m/s^2].
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.
#define UNUSED_PARAMETER(x)