A train. More...
#include <train.h>
Signals | |
void | suddenAccelerationOccurred (std::string msg) |
report a sudden acceleration. | |
void | slowSpeedOrStopped (std::string msg) |
report the trains is very slow or stopped | |
Public Member Functions | |
Train (int simulatorID, string id, Vector< int > trainPath, double trainStartTime_sec, double frictionCoeff, Vector< std::shared_ptr< Locomotive > > locomotives, Vector< std::shared_ptr< Car > > cars, bool optimize, double desiredDecelerationRate_mPs=DefaultDesiredDecelerationRate, double operatorReactionTime_s=DefaultOperatorReactionTime, bool stopIfNoEnergy=DefaultStopIfNoEnergy, double maxAllowedJerk_mPcs=DefaultMaxAllowedJerk) | |
This constructor initializes a train with the passed parameters. | |
~Train () | |
void | setTrainSimulatorID (int newID) |
bool | rechargeCarsBatteries (double timeStep, double EC_kwh, std::shared_ptr< Locomotive > &loco) |
recharge all train cars batteries. | |
Map< string, double > | getTrainConsumedTank () |
getTrainConsumedTank | |
void | setTrainPath (Vector< int > path) |
set the train path. | |
double | getMinFollowingTrainGap () |
Gets minimum following train gap. | |
void | setTrainsCurrentLinks (Vector< std::shared_ptr< NetLink > > newLinks) |
set the current links the train is spanning | |
double | getCargoNetWeight () |
Gets cargo net weight. | |
Map< TrainTypes::PowerType, int > | LocTypeCount () |
Locomotive type count. | |
Map< TrainTypes::CarType, int > | carTypeCount () |
car type count | |
Map< std::shared_ptr< TrainComponent >, double > | getTrainCentroids () |
This function returns the centroids of all vehicles in the train. | |
int | getActiveLocomotivesNumber () |
Gets active locomotives number. | |
double | getBatteryEnergyConsumed () |
Gets the battery energy consumed in kWh. | |
double | getBatteryEnergyRegenerated () |
Gets the battery energy regenerated in kWh. | |
double | getBatteryNetEnergyConsumed () |
Gets the battery energy consumed in kWh. | |
double | getAverageLocomotivesBatteryStatus () |
Gets average locomotives battery status. | |
double | getAverageLocomotiveTankStatus () |
Gets average locomotives tank status. | |
double | getAverageTendersTankStatus () |
Gets average tenders tank status. | |
double | getAverageTendersBatteryStatus () |
Gets average tenders battery status. | |
double | getTrainTotalTorque () |
Gets train total torque in tons x meters. | |
double | getAverageTendersStatus () |
Gets average tenders status. | |
void | setTrainLength () |
Sets train length. | |
void | setTrainWeight () |
Sets train weight. | |
void | resetTrain () |
Resets the train parameters. | |
void | rearrangeTrain () |
Rearrange train. | |
void | updateGradesCurvatures (Vector< double > &LocsCurvature, Vector< double > &LocsGrade, Vector< double > &CarsCurvature, Vector< double > &CarsGrade) |
Updates the grades curvatures. | |
void | updateGradesCurvatures (const Vector< double > &trainGrade, const Vector< double > &trainCurvature) |
Updates the grades curvatures. | |
double | getTotalTractiveForce (double speed, double acceleration, bool optimize, double optimumThrottleLevel) |
Gets total tractive force. | |
double | getTotalResistance (double speed) |
Gets total resistance. | |
double | getAccelerationUpperBound (double speed, double acceleration, double freeFlowSpeed, bool optimize, double optimumThrottleLevel) |
Gets acceleration upper bound. | |
double | getSafeGap (double initialGap, double speed, double freeFlowSpeed, double T_s, bool estimate) |
Gets safe gap. | |
double | getNextTimeStepSpeed (double gap, double minGap, double speed, double freeFlowSpeed, double aMax, double T_s, double deltaT) |
Gets the next time step speed. | |
double | getTimeToCollision (double gap, double minGap, double speed, double leaderSpeed) |
Gets time to collision. | |
double | accelerate (double gap, double mingap, double speed, double acceleration, double leaderSpeed, double freeFlowSpeed, double deltaT, bool optimize, double throttleLevel=-1) |
Gets the acceleration of the train. | |
double | accelerateConsideringJerk (double acceleration, double previousAcceleration, double jerk, double deltaT) |
Accelerate considering jerk. | |
double | smoothAccelerate (double acceleration, double previousAccelerationValue, double alpha=0.2) |
Smooth the acceleration. | |
double | speedUpDown (double previousSpeed, double acceleration, double deltaT, double freeFlowSpeed) |
Gets the speed of the train based on the acceleration. | |
double | adjustAcceleration (double speed, double previousSpeed, double deltaT) |
Adjust acceleration. | |
void | checkSuddenAccChange (double previousAcceleration, double currentAcceleration, double deltaT) |
Check sudden accumulate change. | |
double | getStepAcceleration (double timeStep, double freeFlowSpeed, Vector< double > &gapToNextCriticalPoint, Vector< bool > &gapToNextCriticalPointType, Vector< double > &leaderSpeed) |
getStepDynamics | |
void | moveTrain (double timeStep, double freeFlowSpeed, Vector< double > &gapToNextCriticalPoint, Vector< bool > &gapToNextCriticalPointType, Vector< double > &leaderSpeed) |
Move train forward. | |
pair< Vector< double >, double > | getTractivePower (double speed, double acceleration, double resistanceForces) |
Gets tractive power. | |
void | updateLocNotch () |
Updates the location notch. | |
void | immediateStop (double timeStep) |
Immediate stop. | |
void | kickForwardADistance (double &distance) |
Kick forward a distance. | |
double | getEnergyConsumption (double timeStep) |
Gets energy consumption. | |
void | calculateEnergyConsumption (double timeStep, std::string currentRegion) |
Calculates the energy consumption. | |
double | getTotalEnergyConsumption (double &timeStep, Vector< double > &usedTractivePower) |
Gets total energy consumption. | |
bool | consumeEnergy (double &timeStep, double trainSpeed, Vector< double > &usedTractivePower) |
Consume energy. | |
void | resetTrainEnergyConsumption () |
Resets the train energy consumption. | |
std::pair< bool, double > | consumeTendersEnergy (double timeStep, double trainSpeed, double EC_kwh, TrainTypes::PowerType powerType, double dieselConversionFactor=EC::DefaultDieselConversionFactor, double hydrogenConversionFactor=EC::DefaultHydrogenConversionFactor, double dieselDensity=EC::DefaultDieselDensity) |
Consume tenders energy. | |
Vector< std::shared_ptr< Car > > | getActiveTanksOfType (TrainTypes::CarType cartype) |
Gets active tanks of type. | |
int | getRechargableCarsNumber () |
Gets rechargable cars number. | |
int | getRechargableLocsNumber () |
Gets rechargable locs number. | |
tuple< double, double, double > | AStarOptimization (double prevSpeed, double currentSpeed, double currentAcceleration, double prevThrottle, Vector< double > vector_grade, Vector< double > vector_curvature, double freeSpeed_ms, double timeStep, Vector< double > u_leader, Vector< double > gapToNextCriticalPoint) |
This function adopts the A Star optimization to get the optimum throttle level. | |
double | heuristicFunction (double distanceToEnd, double stepAcceleration, double stepSpeed, double timeStep, double resistance, double currentSpeed) |
The heuristic function for the A-Star algorithm. | |
double | pickOptimalThrottleLevelAStar (Vector< double > throttleLevels, int lookAheadCounterToUpdate) |
Picks the optimal throttle level considering the A-Star optimization. | |
void | calcTrainStats (Vector< double > listOfLinksFreeFlowSpeeds, double MinFreeFlow, double timeStep, std::string currentRegion) |
Calculates the train statistics. | |
double | calculateAverage (double previousAverage, double currentTimeStepData, double timeStep) |
Finds the average of the given arguments. | |
double | getDelayTimeStat (double freeflowSpeed, double timeStep) |
Gets delay time stat. | |
double | getMaxDelayTimeStat (Vector< double > listOfLinksFreeFlowSpeeds, double timeStep) |
Gets maximum delay time stat. | |
double | getStoppingTimeStat (Vector< double > listOfLinksFreeFlowSpeeds) |
Gets stopping time stat. | |
void | resetTrainLookAhead () |
reset train look ahead parameters | |
std::pair< double, Map< TrainTypes::PowerType, double > > | getMaxProvidedEnergy (double &timeStep) |
getMaxProvidedEnergy | |
bool | canProvideEnergy (double &EC, double &timeStep) |
check if the train can provide the required energy to move forward | |
void | reducePower (double &reductionFactor) |
reducePower | |
void | resetPowerRestriction () |
resetPowerRestriction | |
Static Public Member Functions | |
static unsigned int | getNumberOfTrainsInSimulator () |
this function returns how many trains are loaded in the simulator | |
Public Attributes | |
const double | g = 9.8066 |
(Immutable) gravitational acceleration | |
double | d_des |
The desired decceleration value. | |
double | operatorReactionTime |
the perception reaction time of the train operator. | |
double | totalLength |
Total length of the train. | |
double | totalMass |
The total weight of the train in kg. | |
double | totalEmptyMass = 0 |
The total empty weight of the train. | |
double | coefficientOfFriction = 0.9 |
Coefficient of fricition between the trains' wheels and the track. | |
double | maxJerk = 2.0 |
Max allowable jerk (m/s^3) for the train. | |
double | T_s |
Time to fully activate the brakes, considering the network signal speed equals speed of sound. | |
double | trainStartTime |
Start time of the train to enter the network retrative to the beginning of the simulator. | |
double | tripTime |
Total time spent between the train entering and leaving the network. | |
double | trainTotalPathLength |
The total length of the path the train is suppost to be taking. | |
double | travelledDistance |
Travelled distance of the train measured from the front tip of the train. | |
double | virtualTravelledDistance |
Travelled distance of the train measured from the front tip of the train (virtual and does not affect train movement. | |
double | currentSpeed |
The current speed of the train (at time t) | |
double | previousSpeed |
The previous speed of the train (at time t-1) | |
double | averageSpeed |
The average journey speed of the train from t = 0 to t. | |
double | currentAcceleration |
The current acceleration of the train (at time t) | |
double | previousAcceleration |
The previous acceleration of the train (at time t-1) | |
double | averageAcceleration |
The average journey acceleration of the train from t = 0 to t. | |
double | currentTractiveForce |
The current tractive forces the train is using in Newton. | |
double | currentResistanceForces |
The current resistance forces on the train in Newton. | |
double | currentUsedTractivePower |
The current used tractive power that the locomotives provides in kw. | |
double | cumUsedTractivePower |
The cummulative used tractive power (work) that the locomotives provide in kw. | |
double | optimumThrottleLevel |
The optimum throttle level that the train should go by to minimize its energy use. | |
double | energyStat |
Total energy consumption (consumed + regenerated) at time step t. | |
double | cumEnergyStat |
Cumulative total energy consumed till time step t. | |
double | totalEConsumed |
Total energy consumpted only of the train till time t. | |
double | totalERegenerated |
Energy regenerated of the train till time t. | |
double | delayTimeStat |
The time the train is delayed at time step t, relative to min free flow speed of all spanned links. | |
double | cumDelayTimeStat |
Cumulative total time delayed untill time step t, relative to min free flow speed of all spanned links. | |
double | maxDelayTimeStat |
The time the train is delayed at time step t, relative to max free flow speed of all spanned links. | |
double | cumMaxDelayTimeStat |
Total time delayed untill time step t, relative to max free flow speed of all spanned links. | |
double | stoppedStat |
Statistic of the stoppings at time t. | |
double | cumStoppedStat |
Statistic of stoppings untill time t. | |
double | waitedTimeAtNode |
holds the waited time at any depot | |
pair< double, double > | currentCoordinates |
Holds the current coordinates of the tip of the train. | |
std::shared_ptr< NetLink > | currentFirstLink |
Holds the first link the train is on. | |
Map< std::shared_ptr< TrainComponent >, double > | WeightCentroids |
Holds the centroid location mapped by the car/loco and relative to the tip of the train. | |
Map< int, double > | LinkGradeDirection |
Grade of the links the train is taking and it is mapped by the link ID. | |
Map< TrainTypes::CarType, Vector< std::shared_ptr< Car > > > | carsTypes |
Maps the train cars types. | |
Map< TrainTypes::CarType, Vector< std::shared_ptr< Car > > > | ActiveCarsTypes |
Maps the train active cars types. | |
Map< string, double > | cumRegionalConsumedEnergyStat |
Total energy consumed till time step t mapped by region. | |
Vector< std::shared_ptr< Car > > | cars |
Holds all cars in the train. | |
Vector< std::shared_ptr< Locomotive > > | locomotives |
Holds all locomotives in the train. | |
Vector< int > | trainPath |
The predefined path of the train by the simulator node id. | |
Vector< std::shared_ptr< NetNode > > | trainPathNodes |
The predefined path of the train by the node reference. | |
Vector< std::shared_ptr< NetLink > > | currentLinks |
The spanned links the train is on. | |
Vector< Vector< double > > | betweenNodesLengths |
Holds the computed distances between two nodes along the train's path. | |
Vector< double > | linksCumLengths |
Holds the cummulative distance from the start of the train's path to each and every node in the path. | |
Vector< Vector< Map< int, double > > > | LowerSpeedNodeIDs |
Holds the lower speed node ID's the train will have to reduce its speed at. | |
Vector< pair< double, double > > | startEndPoints |
Holds both the start and end tips' coordinates of the train. | |
Vector< std::shared_ptr< NetLink > > | previousLinks |
The previous links the train spanned before. | |
Vector< std::shared_ptr< TrainComponent > > | trainVehicles |
holds the arrangement of the train and how locomotives and cars are arranged in that train. | |
Vector< std::shared_ptr< Locomotive > > | ActiveLocos |
Maps the train active locomotives types. | |
Vector< double > | currentUsedTractivePowerList |
The current used tractive power list. | |
Vector< double > | throttleLevels |
The throttle levels that the train will go by. | |
string | trainUserID |
The name of the train. | |
Vector< bool > | trainStoppingStations |
The train stopping stations. | |
int | nCars = 0 |
Number of cars in the train. | |
int | nlocs = 0 |
Number of locomotives in the train. | |
int | id |
The name of the train. | |
int | previousNodeID |
The previous node ID the tip of the train just passed. | |
int | LastTrainPointpreviousNodeID |
The previous node ID the last point of the train just passed. | |
int | nextNodeID |
The next node the train is targetting. | |
int | NoPowerCountStep |
Counts the number of steps the train could not move forward because of the lack of power source. | |
int | lookAheadStepCounter |
The number of steps ahead the train is looking aheaf for optimization. | |
int | lookAheadCounterToUpdate |
The number of steps ahead the train should update its optimization at. | |
bool | stopTrainIfNoEnergy |
Change this to true if you want the train to stop if it runs out of energy. | |
bool | isOn |
True if the train has energy, false if dead. | |
bool | offloaded = false |
If the train is on the network, it is true, false otherwise. | |
bool | reachedDestination = false |
True if the simulator reached its destination, false otherwise. | |
bool | outOfEnergy = false |
True if the train ran out of energy. | |
bool | loaded = false |
True if the train is loaded to the simulator, false otherwise. | |
bool | optimize |
True if the train should optimize its energy consumption. | |
Static Public Attributes | |
static constexpr double | speedOfSound = 343.0 |
(Immutable) the speed of sound in m / s, this is an approximation of the brackes back propagation | |
Friends | |
ostream & | operator<< (ostream &ostr, Train &train) |
Stream insertion operator. | |
A train.
Train::Train | ( | int | simulatorID, |
string | id, | ||
Vector< int > | trainPath, | ||
double | trainStartTime_sec, | ||
double | frictionCoeff, | ||
Vector< std::shared_ptr< Locomotive > > | locomotives, | ||
Vector< std::shared_ptr< Car > > | cars, | ||
bool | optimize, | ||
double | desiredDecelerationRate_mPs = DefaultDesiredDecelerationRate , |
||
double | operatorReactionTime_s = DefaultOperatorReactionTime , |
||
bool | stopIfNoEnergy = DefaultStopIfNoEnergy , |
||
double | maxAllowedJerk_mPcs = DefaultMaxAllowedJerk |
||
) |
This constructor initializes a train with the passed parameters.
simulatorID | simulatorID A unique identifier for the node, it should start by 0 and increment by 1 |
id | The identifier. |
trainPath | Full pathname of the train file. |
trainStartTime_sec | The train start time security. |
frictionCoeff | The friction coeff. |
locomotives | The locomotives. |
cars | The cars. |
optimize | True to optimize. |
desiredDecelerationRate_mPs | (Optional) The desired deceleration rate m ps. |
operatorReactionTime_s | (Optional) The operator reaction time s. |
stopIfNoEnergy | (Optional) True to stop if no energy. |
isRunnigOffGrid | (Optional) True if is runnig off grid, false if not. |
maxAllowedJerk_mPcs | (Optional) The maximum allowed jerk m pcs. |
Train::~Train | ( | ) |
double Train::accelerate | ( | double | gap, |
double | mingap, | ||
double | speed, | ||
double | acceleration, | ||
double | leaderSpeed, | ||
double | freeFlowSpeed, | ||
double | deltaT, | ||
bool | optimize, | ||
double | throttleLevel = -1 |
||
) |
Gets the acceleration of the train.
gap | The gap. |
mingap | The mingap. |
speed | The speed. |
acceleration | The acceleration. |
leaderSpeed | The leader speed. |
freeFlowSpeed | The free flow speed. |
deltaT | The delta t. |
optimize | True to optimize. |
throttleLevel | (Optional) The throttle level. |
double Train::accelerateConsideringJerk | ( | double | acceleration, |
double | previousAcceleration, | ||
double | jerk, | ||
double | deltaT | ||
) |
Accelerate considering jerk.
acceleration | The acceleration. |
previousAcceleration | The previous acceleration. |
jerk | The jerk. |
deltaT | The delta t. |
double Train::adjustAcceleration | ( | double | speed, |
double | previousSpeed, | ||
double | deltaT | ||
) |
Adjust acceleration.
speed | The speed. |
previousSpeed | The previous speed. |
deltaT | The delta t. |
tuple< double, double, double > Train::AStarOptimization | ( | double | prevSpeed, |
double | currentSpeed, | ||
double | currentAcceleration, | ||
double | prevThrottle, | ||
Vector< double > | vector_grade, | ||
Vector< double > | vector_curvature, | ||
double | freeSpeed_ms, | ||
double | timeStep, | ||
Vector< double > | u_leader, | ||
Vector< double > | gapToNextCriticalPoint | ||
) |
This function adopts the A Star optimization to get the optimum throttle level.
prevSpeed | The previous speed. |
currentSpeed | The current speed. |
currentAcceleration | The current acceleration. |
prevThrottle | The previous throttle. |
vector_grade | The vector grade. |
vector_curvature | The vector curvature. |
freeSpeed_ms | The free speed in milliseconds. |
timeStep | The time step. |
u_leader | The leader. |
gapToNextCriticalPoint | The gap to next critical point. |
void Train::calcTrainStats | ( | Vector< double > | listOfLinksFreeFlowSpeeds, |
double | MinFreeFlow, | ||
double | timeStep, | ||
std::string | currentRegion | ||
) |
Calculates the train statistics.
listOfLinksFreeFlowSpeeds | The list of links free flow speeds. |
MinFreeFlow | The minimum free flow. |
timeStep | The time step. |
currentRegion | The current region. |
double Train::calculateAverage | ( | double | previousAverage, |
double | currentTimeStepData, | ||
double | timeStep | ||
) |
Finds the average of the given arguments.
previousAverage | The previous average. |
currentTimeStepData | Information describing the current time step. |
timeStep | The time step. |
void Train::calculateEnergyConsumption | ( | double | timeStep, |
std::string | currentRegion | ||
) |
Calculates the energy consumption.
timeStep | The time step. |
currentRegion | The current region. |
bool Train::canProvideEnergy | ( | double & | EC, |
double & | timeStep | ||
) |
Map< TrainTypes::CarType, int > Train::carTypeCount | ( | ) |
void Train::checkSuddenAccChange | ( | double | previousAcceleration, |
double | currentAcceleration, | ||
double | deltaT | ||
) |
Check sudden accumulate change.
previousAcceleration | The previous acceleration. |
currentAcceleration | The current acceleration. |
deltaT | The delta t. |
bool Train::consumeEnergy | ( | double & | timeStep, |
double | trainSpeed, | ||
Vector< double > & | usedTractivePower | ||
) |
Consume energy.
[in,out] | timeStep | The time step. |
[in,out] | usedTractivePower | The used tractive power. |
std::pair< bool, double > Train::consumeTendersEnergy | ( | double | timeStep, |
double | trainSpeed, | ||
double | EC_kwh, | ||
TrainTypes::PowerType | powerType, | ||
double | dieselConversionFactor = EC::DefaultDieselConversionFactor , |
||
double | hydrogenConversionFactor = EC::DefaultHydrogenConversionFactor , |
||
double | dieselDensity = EC::DefaultDieselDensity |
||
) |
Consume tenders energy.
EC_kwh | The ec kwh. |
powerType | Type of the power. |
dieselConversionFactor | (Optional) The diesel conversion factor. |
hydrogenConversionFactor | (Optional) The hydrogen conversion factor. |
dieselDensity | (Optional) The diesel density. |
double Train::getAccelerationUpperBound | ( | double | speed, |
double | acceleration, | ||
double | freeFlowSpeed, | ||
bool | optimize, | ||
double | optimumThrottleLevel | ||
) |
Gets acceleration upper bound.
speed | The speed. |
acceleration | The acceleration. |
freeFlowSpeed | The free flow speed. |
optimize | True to optimize. |
optimumThrottleLevel | The optimum throttle level. |
int Train::getActiveLocomotivesNumber | ( | ) |
Gets active locomotives number.
Vector< std::shared_ptr< Car > > Train::getActiveTanksOfType | ( | TrainTypes::CarType | cartype | ) |
Gets active tanks of type.
cartype | The cartype. |
double Train::getAverageLocomotivesBatteryStatus | ( | ) |
Gets average locomotives battery status.
double Train::getAverageLocomotiveTankStatus | ( | ) |
Gets average locomotives tank status.
double Train::getAverageTendersBatteryStatus | ( | ) |
Gets average tenders battery status.
double Train::getAverageTendersStatus | ( | ) |
Gets average tenders status.
double Train::getAverageTendersTankStatus | ( | ) |
Gets average tenders tank status.
double Train::getBatteryEnergyConsumed | ( | ) |
Gets the battery energy consumed in kWh.
Gets the battery energy consumed only. it does not report the energy regenerated.
double Train::getBatteryEnergyRegenerated | ( | ) |
Gets the battery energy regenerated in kWh.
double Train::getBatteryNetEnergyConsumed | ( | ) |
Gets the battery energy consumed in kWh.
Gets the battery energy consumed and regenerated.
double Train::getCargoNetWeight | ( | ) |
Gets cargo net weight.
double Train::getDelayTimeStat | ( | double | freeflowSpeed, |
double | timeStep | ||
) |
Gets delay time stat.
freeflowSpeed | The freeflow speed. |
timeStep | The time step. |
double Train::getEnergyConsumption | ( | double | timeStep | ) |
Gets energy consumption.
timeStep | The time step. |
double Train::getMaxDelayTimeStat | ( | Vector< double > | listOfLinksFreeFlowSpeeds, |
double | timeStep | ||
) |
Gets maximum delay time stat.
listOfLinksFreeFlowSpeeds | The list of links free flow speeds. |
timeStep | The time step. |
std::pair< double, Map< TrainTypes::PowerType, double > > Train::getMaxProvidedEnergy | ( | double & | timeStep | ) |
getMaxProvidedEnergy
timeStep |
double Train::getMinFollowingTrainGap | ( | ) |
Gets minimum following train gap.
double Train::getNextTimeStepSpeed | ( | double | gap, |
double | minGap, | ||
double | speed, | ||
double | freeFlowSpeed, | ||
double | aMax, | ||
double | T_s, | ||
double | deltaT | ||
) |
Gets the next time step speed.
gap | The gap. |
minGap | The minimum gap. |
speed | The speed. |
freeFlowSpeed | The free flow speed. |
aMax | The maximum. |
T_s | The s. |
deltaT | The delta t. |
|
static |
this function returns how many trains are loaded in the simulator
int Train::getRechargableCarsNumber | ( | ) |
Gets rechargable cars number.
int Train::getRechargableLocsNumber | ( | ) |
Gets rechargable locs number.
double Train::getSafeGap | ( | double | initialGap, |
double | speed, | ||
double | freeFlowSpeed, | ||
double | T_s, | ||
bool | estimate | ||
) |
Gets safe gap.
initialGap | The initial gap. |
speed | The speed. |
freeFlowSpeed | The free flow speed. |
T_s | The s. |
estimate | True to estimate. |
double Train::getStepAcceleration | ( | double | timeStep, |
double | freeFlowSpeed, | ||
Vector< double > & | gapToNextCriticalPoint, | ||
Vector< bool > & | gapToNextCriticalPointType, | ||
Vector< double > & | leaderSpeed | ||
) |
getStepDynamics
timeStep | |
freeFlowSpeed | |
gapToNextCriticalPoint | |
gapToNextCriticalPointType | |
leaderSpeed |
double Train::getStoppingTimeStat | ( | Vector< double > | listOfLinksFreeFlowSpeeds | ) |
Gets stopping time stat.
listOfLinksFreeFlowSpeeds | The list of links free flow speeds. |
double Train::getTimeToCollision | ( | double | gap, |
double | minGap, | ||
double | speed, | ||
double | leaderSpeed | ||
) |
Gets time to collision.
gap | The gap. |
minGap | The minimum gap. |
speed | The speed. |
leaderSpeed | The leader speed. |
double Train::getTotalEnergyConsumption | ( | double & | timeStep, |
Vector< double > & | usedTractivePower | ||
) |
Gets total energy consumption.
[in,out] | timeStep | The time step. |
[in,out] | usedTractivePower | The used tractive power. |
double Train::getTotalResistance | ( | double | speed | ) |
Gets total resistance.
speed | The speed. |
double Train::getTotalTractiveForce | ( | double | speed, |
double | acceleration, | ||
bool | optimize, | ||
double | optimumThrottleLevel | ||
) |
Gets total tractive force.
speed | The speed. |
acceleration | The acceleration. |
optimize | True to optimize. |
optimumThrottleLevel | The optimum throttle level. |
pair< Vector< double >, double > Train::getTractivePower | ( | double | speed, |
double | acceleration, | ||
double | resistanceForces | ||
) |
Gets tractive power.
speed | The speed. |
acceleration | The acceleration. |
resistanceForces | The resistance forces. |
Map< std::shared_ptr< TrainComponent >, double > Train::getTrainCentroids | ( | ) |
This function returns the centroids of all vehicles in the train.
Map< std::string, double > Train::getTrainConsumedTank | ( | ) |
getTrainConsumedTank
double Train::getTrainTotalTorque | ( | ) |
Gets train total torque in tons x meters.
double Train::heuristicFunction | ( | double | distanceToEnd, |
double | stepAcceleration, | ||
double | stepSpeed, | ||
double | timeStep, | ||
double | resistance, | ||
double | currentSpeed | ||
) |
The heuristic function for the A-Star algorithm.
distanceToEnd | The distance to end. |
stepAcceleration | The step acceleration. |
stepSpeed | The step speed. |
timeStep | The time step. |
resistance | The resistance. |
currentSpeed | The current speed. |
void Train::immediateStop | ( | double | timeStep | ) |
Immediate stop.
timeStep | The time step. |
void Train::kickForwardADistance | ( | double & | distance | ) |
Kick forward a distance.
[in,out] | distance | The distance. |
Map< TrainTypes::PowerType, int > Train::LocTypeCount | ( | ) |
void Train::moveTrain | ( | double | timeStep, |
double | freeFlowSpeed, | ||
Vector< double > & | gapToNextCriticalPoint, | ||
Vector< bool > & | gapToNextCriticalPointType, | ||
Vector< double > & | leaderSpeed | ||
) |
Move train forward.
timeStep | The time step. | |
freeFlowSpeed | The free flow speed. | |
[in,out] | gapToNextCriticalPoint | The gap to next critical point. |
[in,out] | gapToNextCriticalPointType | Type of the gap to next critical point. |
[in,out] | leaderSpeed | The leader speed. |
double Train::pickOptimalThrottleLevelAStar | ( | Vector< double > | throttleLevels, |
int | lookAheadCounterToUpdate | ||
) |
Picks the optimal throttle level considering the A-Star optimization.
throttleLevels | The throttle levels. |
lookAheadCounterToUpdate | The look ahead counter to update. |
void Train::rearrangeTrain | ( | ) |
Rearrange train.
bool Train::rechargeCarsBatteries | ( | double | timeStep, |
double | EC_kwh, | ||
std::shared_ptr< Locomotive > & | loco | ||
) |
recharge all train cars batteries.
EC_kwh |
void Train::reducePower | ( | double & | reductionFactor | ) |
reducePower
reductionFactor |
void Train::resetPowerRestriction | ( | ) |
resetPowerRestriction
void Train::resetTrain | ( | ) |
Resets the train parameters.
void Train::resetTrainEnergyConsumption | ( | ) |
Resets the train energy consumption.
void Train::resetTrainLookAhead | ( | ) |
reset train look ahead parameters
void Train::setTrainLength | ( | ) |
Sets train length.
void Train::setTrainPath | ( | Vector< int > | path | ) |
set the train path.
path | the new path of the simulator node ids. |
set the current links the train is spanning
newLinks |
void Train::setTrainSimulatorID | ( | int | newID | ) |
void Train::setTrainWeight | ( | ) |
Sets train weight.
|
signal |
report the trains is very slow or stopped
this is emitted when the train's speed is very slow either because the resistance is high or because the distance in front of the train is very small
msg |
double Train::smoothAccelerate | ( | double | acceleration, |
double | previousAccelerationValue, | ||
double | alpha = 0.2 |
||
) |
Smooth the acceleration.
acceleration | The acceleration. |
previousAccelerationValue | The previous acceleration value. |
alpha | (Optional) The alpha. |
double Train::speedUpDown | ( | double | previousSpeed, |
double | acceleration, | ||
double | deltaT, | ||
double | freeFlowSpeed | ||
) |
Gets the speed of the train based on the acceleration.
previousSpeed | The previous speed. |
acceleration | The acceleration. |
deltaT | The delta t. |
freeFlowSpeed | The free flow speed. |
|
signal |
report a sudden acceleration.
this is emitted when the train's acceleration is larger than the jerk
msg | is the warning message |
void Train::updateGradesCurvatures | ( | const Vector< double > & | trainGrade, |
const Vector< double > & | trainCurvature | ||
) |
Updates the grades curvatures.
trainGrade | The train grade. |
trainCurvature | The train curvature. |
void Train::updateGradesCurvatures | ( | Vector< double > & | LocsCurvature, |
Vector< double > & | LocsGrade, | ||
Vector< double > & | CarsCurvature, | ||
Vector< double > & | CarsGrade | ||
) |
Updates the grades curvatures.
[in,out] | LocsCurvature | The locs curvature. |
[in,out] | LocsGrade | The locs grade. |
[in,out] | CarsCurvature | The cars curvature. |
[in,out] | CarsGrade | The cars grade. |
void Train::updateLocNotch | ( | ) |
Updates the location notch.
|
friend |
Stream insertion operator.
[in,out] | ostr | The ostr. |
[in,out] | train | The train. |
Map<TrainTypes::CarType, Vector<std::shared_ptr<Car> > > Train::ActiveCarsTypes |
Maps the train active cars types.
Vector<std::shared_ptr<Locomotive> > Train::ActiveLocos |
Maps the train active locomotives types.
double Train::averageAcceleration |
The average journey acceleration of the train from t = 0 to t.
double Train::averageSpeed |
The average journey speed of the train from t = 0 to t.
Holds the computed distances between two nodes along the train's path.
Map<TrainTypes::CarType, Vector<std::shared_ptr<Car> > > Train::carsTypes |
Maps the train cars types.
double Train::coefficientOfFriction = 0.9 |
Coefficient of fricition between the trains' wheels and the track.
double Train::cumDelayTimeStat |
Cumulative total time delayed untill time step t, relative to min free flow speed of all spanned links.
double Train::cumEnergyStat |
Cumulative total energy consumed till time step t.
double Train::cumMaxDelayTimeStat |
Total time delayed untill time step t, relative to max free flow speed of all spanned links.
Map<string, double> Train::cumRegionalConsumedEnergyStat |
Total energy consumed till time step t mapped by region.
double Train::cumStoppedStat |
Statistic of stoppings untill time t.
double Train::cumUsedTractivePower |
The cummulative used tractive power (work) that the locomotives provide in kw.
double Train::currentAcceleration |
The current acceleration of the train (at time t)
pair<double, double> Train::currentCoordinates |
Holds the current coordinates of the tip of the train.
std::shared_ptr<NetLink> Train::currentFirstLink |
Holds the first link the train is on.
The spanned links the train is on.
works as blocks
double Train::currentResistanceForces |
The current resistance forces on the train in Newton.
double Train::currentSpeed |
The current speed of the train (at time t)
double Train::currentTractiveForce |
The current tractive forces the train is using in Newton.
double Train::currentUsedTractivePower |
The current used tractive power that the locomotives provides in kw.
Vector<double> Train::currentUsedTractivePowerList |
The current used tractive power list.
double Train::d_des |
The desired decceleration value.
double Train::delayTimeStat |
The time the train is delayed at time step t, relative to min free flow speed of all spanned links.
double Train::energyStat |
Total energy consumption (consumed + regenerated) at time step t.
const double Train::g = 9.8066 |
(Immutable) gravitational acceleration
int Train::id |
The name of the train.
bool Train::isOn |
True if the train has energy, false if dead.
int Train::LastTrainPointpreviousNodeID |
The previous node ID the last point of the train just passed.
Map<int, double> Train::LinkGradeDirection |
Grade of the links the train is taking and it is mapped by the link ID.
Vector<double> Train::linksCumLengths |
Holds the cummulative distance from the start of the train's path to each and every node in the path.
bool Train::loaded = false |
True if the train is loaded to the simulator, false otherwise.
Vector<std::shared_ptr<Locomotive> > Train::locomotives |
Holds all locomotives in the train.
int Train::lookAheadCounterToUpdate |
The number of steps ahead the train should update its optimization at.
int Train::lookAheadStepCounter |
The number of steps ahead the train is looking aheaf for optimization.
Holds the lower speed node ID's the train will have to reduce its speed at.
double Train::maxDelayTimeStat |
The time the train is delayed at time step t, relative to max free flow speed of all spanned links.
double Train::maxJerk = 2.0 |
Max allowable jerk (m/s^3) for the train.
int Train::nCars = 0 |
Number of cars in the train.
int Train::nextNodeID |
The next node the train is targetting.
int Train::nlocs = 0 |
Number of locomotives in the train.
int Train::NoPowerCountStep |
Counts the number of steps the train could not move forward because of the lack of power source.
bool Train::offloaded = false |
If the train is on the network, it is true, false otherwise.
double Train::operatorReactionTime |
the perception reaction time of the train operator.
bool Train::optimize |
True if the train should optimize its energy consumption.
train trajectory will vary here.
double Train::optimumThrottleLevel |
The optimum throttle level that the train should go by to minimize its energy use.
bool Train::outOfEnergy = false |
True if the train ran out of energy.
double Train::previousAcceleration |
The previous acceleration of the train (at time t-1)
int Train::previousNodeID |
The previous node ID the tip of the train just passed.
double Train::previousSpeed |
The previous speed of the train (at time t-1)
bool Train::reachedDestination = false |
True if the simulator reached its destination, false otherwise.
|
staticconstexpr |
(Immutable) the speed of sound in m / s, this is an approximation of the brackes back propagation
Vector<pair<double, double> > Train::startEndPoints |
Holds both the start and end tips' coordinates of the train.
double Train::stoppedStat |
Statistic of the stoppings at time t.
bool Train::stopTrainIfNoEnergy |
Change this to true if you want the train to stop if it runs out of energy.
double Train::T_s |
Time to fully activate the brakes, considering the network signal speed equals speed of sound.
Vector<double> Train::throttleLevels |
The throttle levels that the train will go by.
double Train::totalEConsumed |
Total energy consumpted only of the train till time t.
double Train::totalEmptyMass = 0 |
The total empty weight of the train.
double Train::totalERegenerated |
Energy regenerated of the train till time t.
double Train::totalLength |
Total length of the train.
double Train::totalMass |
The total weight of the train in kg.
Vector<int> Train::trainPath |
The predefined path of the train by the simulator node id.
It is originally populated by the user node ids. the simulator replaces it by the simulator node ids.
The predefined path of the train by the node reference.
double Train::trainStartTime |
Start time of the train to enter the network retrative to the beginning of the simulator.
Vector<bool> Train::trainStoppingStations |
The train stopping stations.
double Train::trainTotalPathLength |
The total length of the path the train is suppost to be taking.
string Train::trainUserID |
The name of the train.
Vector< std::shared_ptr<TrainComponent> > Train::trainVehicles |
holds the arrangement of the train and how locomotives and cars are arranged in that train.
double Train::travelledDistance |
Travelled distance of the train measured from the front tip of the train.
double Train::tripTime |
Total time spent between the train entering and leaving the network.
double Train::virtualTravelledDistance |
Travelled distance of the train measured from the front tip of the train (virtual and does not affect train movement.
it is only used for optimization.
double Train::waitedTimeAtNode |
holds the waited time at any depot
Map<std::shared_ptr<TrainComponent>, double> Train::WeightCentroids |
Holds the centroid location mapped by the car/loco and relative to the tip of the train.