mirror of
https://github.com/MaSzyna-EU07/maszyna.git
synced 2026-03-22 15:05:03 +01:00
build 180621. serial port input device continuous independent brake control, scenery item selection and info, minor bug fixes, tweaks and refactoring
This commit is contained in:
22
Driver.cpp
22
Driver.cpp
@@ -858,19 +858,28 @@ TCommandType TController::TableUpdate(double &fVelDes, double &fDist, double &fN
|
|||||||
}
|
}
|
||||||
} // koniec obsługi przelotu na W4
|
} // koniec obsługi przelotu na W4
|
||||||
else {
|
else {
|
||||||
if ( !sSpeedTable[i].bMoved )
|
// zatrzymanie na W4
|
||||||
{
|
if ( ( false == sSpeedTable[i].bMoved )
|
||||||
|
&& ( ( OrderCurrentGet() & ( Obey_train | Shunt ) ) != 0 ) ) {
|
||||||
|
// potentially shift the stop point in accordance with its defined parameters
|
||||||
|
/*
|
||||||
|
// https://rainsted.com/pl/Wersja/18.2.133#Okr.C4.99gi_dla_W4_i_W32
|
||||||
|
Pierwszy parametr ujemny - preferowane zatrzymanie czoła składu (np. przed przejściem).
|
||||||
|
Pierwszy parametr dodatni - preferowane zatrzymanie środka składu (np. przy wiacie, przejściu podziemnym).
|
||||||
|
Drugi parametr ujemny - wskazanie zatrzymania dla krótszych składów (W32).
|
||||||
|
Drugi paramer dodatni - długość peronu (W4).
|
||||||
|
*/
|
||||||
auto L = 0.0;
|
auto L = 0.0;
|
||||||
auto Par1 = sSpeedTable[i].evEvent->ValueGet(1);
|
auto Par1 = sSpeedTable[i].evEvent->ValueGet(1);
|
||||||
auto Par2 = sSpeedTable[i].evEvent->ValueGet(2);
|
auto Par2 = sSpeedTable[i].evEvent->ValueGet(2);
|
||||||
if ((Par2 > 0) || (fLength < -Par2)) { //użyj tego W4
|
if ((Par2 > 0) || (fLength < -Par2)) { //użyj tego W4
|
||||||
if (Par1 < 0) { //środek
|
if (Par1 < 0) { //środek
|
||||||
L = -Par1 - fLength * 0.5 - 10;
|
L = -Par1 - fMinProximityDist - fLength * 0.5;
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
L = Par1;
|
L = Par1;
|
||||||
}
|
}
|
||||||
L = std::max(0.0, std::min(L, abs(Par2) - 10 - fLength));
|
L = std::max(0.0, std::min(L, std::abs(Par2) - fMinProximityDist - fLength));
|
||||||
sSpeedTable[i].UpdateDistance(L);
|
sSpeedTable[i].UpdateDistance(L);
|
||||||
sSpeedTable[i].bMoved = true;
|
sSpeedTable[i].bMoved = true;
|
||||||
}
|
}
|
||||||
@@ -878,7 +887,6 @@ TCommandType TController::TableUpdate(double &fVelDes, double &fDist, double &fN
|
|||||||
sSpeedTable[i].iFlags = 0;
|
sSpeedTable[i].iFlags = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// zatrzymanie na W4
|
|
||||||
isatpassengerstop = (
|
isatpassengerstop = (
|
||||||
// Ra 2F1I: odległość plus długość pociągu musi być mniejsza od długości
|
// Ra 2F1I: odległość plus długość pociągu musi być mniejsza od długości
|
||||||
// peronu, chyba że pociąg jest dłuższy, to wtedy minimalna.
|
// peronu, chyba że pociąg jest dłuższy, to wtedy minimalna.
|
||||||
@@ -887,7 +895,7 @@ TCommandType TController::TableUpdate(double &fVelDes, double &fDist, double &fN
|
|||||||
( iDrivigFlags & moveStopCloser ) ?
|
( iDrivigFlags & moveStopCloser ) ?
|
||||||
( sSpeedTable[ i ].fDist + fLength ) <=
|
( sSpeedTable[ i ].fDist + fLength ) <=
|
||||||
std::max(
|
std::max(
|
||||||
sSpeedTable[ i ].evEvent->ValueGet( 2 ),
|
std::abs( sSpeedTable[ i ].evEvent->ValueGet( 2 ) ),
|
||||||
2.0 * fMaxProximityDist + fLength ) : // fmaxproximitydist typically equals ~50 m
|
2.0 * fMaxProximityDist + fLength ) : // fmaxproximitydist typically equals ~50 m
|
||||||
sSpeedTable[ i ].fDist < d_to_next_sem );
|
sSpeedTable[ i ].fDist < d_to_next_sem );
|
||||||
|
|
||||||
@@ -990,7 +998,7 @@ TCommandType TController::TableUpdate(double &fVelDes, double &fDist, double &fN
|
|||||||
// NOTE: this calculation is expected to run after completing loading/unloading
|
// NOTE: this calculation is expected to run after completing loading/unloading
|
||||||
AutoRewident(); // nastawianie hamulca do jazdy pociągowej
|
AutoRewident(); // nastawianie hamulca do jazdy pociągowej
|
||||||
|
|
||||||
if( int( floor( sSpeedTable[ i ].evEvent->ValueGet( 1 ) ) ) & 1 ) {
|
if( static_cast<int>( std::floor( std::abs( sSpeedTable[ i ].evEvent->ValueGet( 1 ) ) ) ) % 2 ) {
|
||||||
// nie podjeżdżać do semafora, jeśli droga nie jest wolna
|
// nie podjeżdżać do semafora, jeśli droga nie jest wolna
|
||||||
iDrivigFlags |= moveStopHere;
|
iDrivigFlags |= moveStopHere;
|
||||||
}
|
}
|
||||||
|
|||||||
125
Event.cpp
125
Event.cpp
@@ -982,75 +982,76 @@ event_manager::FindEvent( std::string const &Name ) {
|
|||||||
|
|
||||||
// legacy method, inserts specified event in the event query
|
// legacy method, inserts specified event in the event query
|
||||||
bool
|
bool
|
||||||
event_manager::AddToQuery( TEvent *Event, TDynamicObject *Owner ) {
|
event_manager::AddToQuery( TEvent *Event, TDynamicObject const *Owner ) {
|
||||||
|
|
||||||
if( true == Event->bEnabled ) {
|
if( false == Event->bEnabled ) { return false; }
|
||||||
// jeśli może być dodany do kolejki (nie używany w skanowaniu)
|
if( Event->iQueued != 0 ) { return false; }
|
||||||
if( !Event->iQueued ) // jeśli nie dodany jeszcze do kolejki
|
// jeśli może być dodany do kolejki (nie używany w skanowaniu)
|
||||||
{ // kolejka eventów jest posortowana względem (fStartTime)
|
// jeśli nie dodany jeszcze do kolejki
|
||||||
Event->Activator = Owner;
|
|
||||||
if( ( Event->Type == tp_AddValues )
|
// kolejka eventów jest posortowana względem (fStartTime)
|
||||||
&& ( Event->fDelay == 0.0 ) ) {
|
Event->Activator = Owner;
|
||||||
// eventy AddValues trzeba wykonywać natychmiastowo, inaczej kolejka może zgubić jakieś dodawanie
|
if( ( Event->Type == tp_AddValues )
|
||||||
// Ra: kopiowanie wykonania tu jest bez sensu, lepiej by było wydzielić funkcję
|
&& ( Event->fDelay == 0.0 ) ) {
|
||||||
// wykonującą eventy i ją wywołać
|
// eventy AddValues trzeba wykonywać natychmiastowo, inaczej kolejka może zgubić jakieś dodawanie
|
||||||
if( ( false == Event->m_ignored )
|
// Ra: kopiowanie wykonania tu jest bez sensu, lepiej by było wydzielić funkcję
|
||||||
&& ( true == EventConditon( Event ) ) ) { // teraz mogą być warunki do tych eventów
|
// wykonującą eventy i ją wywołać
|
||||||
|
if( ( false == Event->m_ignored )
|
||||||
|
&& ( true == EventConditon( Event ) ) ) { // teraz mogą być warunki do tych eventów
|
||||||
|
|
||||||
Event->Params[ 5 ].asMemCell->UpdateValues(
|
Event->Params[ 5 ].asMemCell->UpdateValues(
|
||||||
Event->Params[ 0 ].asText, Event->Params[ 1 ].asdouble,
|
Event->Params[ 0 ].asText, Event->Params[ 1 ].asdouble,
|
||||||
Event->Params[ 2 ].asdouble, Event->iFlags );
|
Event->Params[ 2 ].asdouble, Event->iFlags );
|
||||||
|
|
||||||
if( Event->Params[ 6 ].asTrack ) { // McZapkie-100302 - updatevalues oprocz zmiany wartosci robi putcommand dla
|
if( Event->Params[ 6 ].asTrack ) {
|
||||||
// wszystkich 'dynamic' na danym torze
|
// McZapkie-100302 - updatevalues oprocz zmiany wartosci robi putcommand dla wszystkich 'dynamic' na danym torze
|
||||||
for( auto dynamic : Event->Params[ 6 ].asTrack->Dynamics ) {
|
for( auto dynamic : Event->Params[ 6 ].asTrack->Dynamics ) {
|
||||||
Event->Params[ 5 ].asMemCell->PutCommand(
|
Event->Params[ 5 ].asMemCell->PutCommand(
|
||||||
dynamic->Mechanik,
|
dynamic->Mechanik,
|
||||||
Event->Params[ 4 ].asLocation );
|
Event->Params[ 4 ].asLocation );
|
||||||
}
|
|
||||||
//if (DebugModeFlag)
|
|
||||||
WriteLog(
|
|
||||||
"EVENT EXECUTED" + ( Owner ? ( " by " + Owner->asName ) : "" ) + ": AddValues & Track command - ["
|
|
||||||
+ std::string{ Event->Params[ 0 ].asText } + "] ["
|
|
||||||
+ to_string( Event->Params[ 1 ].asdouble, 2 ) + "] ["
|
|
||||||
+ to_string( Event->Params[ 2 ].asdouble, 2 ) + " ]" );
|
|
||||||
}
|
|
||||||
//else if (DebugModeFlag)
|
|
||||||
WriteLog(
|
|
||||||
"EVENT EXECUTED" + ( Owner ? ( " by " + Owner->asName ) : "" ) + ": AddValues - ["
|
|
||||||
+ std::string( Event->Params[ 0 ].asText ) + "] ["
|
|
||||||
+ to_string( Event->Params[ 1 ].asdouble, 2 ) + "] ["
|
|
||||||
+ to_string( Event->Params[ 2 ].asdouble, 2 ) + "]" );
|
|
||||||
}
|
|
||||||
// jeśli jest kolejny o takiej samej nazwie, to idzie do kolejki (and if there's no joint event it'll be set to null and processing will end here)
|
|
||||||
do {
|
|
||||||
Event = Event->evJoined;
|
|
||||||
// NOTE: we could've received a new event from joint event above, so we need to check conditions just in case and discard the bad events
|
|
||||||
// TODO: refactor this arrangement, it's hardly optimal
|
|
||||||
} while( ( Event != nullptr )
|
|
||||||
&& ( ( false == Event->bEnabled )
|
|
||||||
|| ( Event->iQueued > 0 ) ) );
|
|
||||||
}
|
|
||||||
if( ( Event != nullptr )
|
|
||||||
&& ( false == Event->m_ignored ) ) {
|
|
||||||
// standardowe dodanie do kolejki
|
|
||||||
++Event->iQueued; // zabezpieczenie przed podwójnym dodaniem do kolejki
|
|
||||||
WriteLog( "EVENT ADDED TO QUEUE" + ( Owner ? ( " by " + Owner->asName ) : "" ) + ": " + Event->asName );
|
|
||||||
Event->fStartTime = std::abs( Event->fDelay ) + Timer::GetTime(); // czas od uruchomienia scenerii
|
|
||||||
if( Event->fRandomDelay > 0.0 ) {
|
|
||||||
// doliczenie losowego czasu opóźnienia
|
|
||||||
Event->fStartTime += Event->fRandomDelay * Random( 10000 ) * 0.0001;
|
|
||||||
}
|
|
||||||
if( QueryRootEvent != nullptr ) {
|
|
||||||
TEvent::AddToQuery( Event, QueryRootEvent );
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
QueryRootEvent = Event;
|
|
||||||
QueryRootEvent->evNext = nullptr;
|
|
||||||
}
|
}
|
||||||
|
//if (DebugModeFlag)
|
||||||
|
WriteLog(
|
||||||
|
"EVENT EXECUTED" + ( Owner ? ( " by " + Owner->asName ) : "" ) + ": AddValues & Track command - ["
|
||||||
|
+ std::string{ Event->Params[ 0 ].asText } + "] ["
|
||||||
|
+ to_string( Event->Params[ 1 ].asdouble, 2 ) + "] ["
|
||||||
|
+ to_string( Event->Params[ 2 ].asdouble, 2 ) + " ]" );
|
||||||
}
|
}
|
||||||
|
//else if (DebugModeFlag)
|
||||||
|
WriteLog(
|
||||||
|
"EVENT EXECUTED" + ( Owner ? ( " by " + Owner->asName ) : "" ) + ": AddValues - ["
|
||||||
|
+ std::string( Event->Params[ 0 ].asText ) + "] ["
|
||||||
|
+ to_string( Event->Params[ 1 ].asdouble, 2 ) + "] ["
|
||||||
|
+ to_string( Event->Params[ 2 ].asdouble, 2 ) + "]" );
|
||||||
|
}
|
||||||
|
// jeśli jest kolejny o takiej samej nazwie, to idzie do kolejki (and if there's no joint event it'll be set to null and processing will end here)
|
||||||
|
do {
|
||||||
|
Event = Event->evJoined;
|
||||||
|
// NOTE: we could've received a new event from joint event above, so we need to check conditions just in case and discard the bad events
|
||||||
|
// TODO: refactor this arrangement, it's hardly optimal
|
||||||
|
} while( ( Event != nullptr )
|
||||||
|
&& ( ( false == Event->bEnabled )
|
||||||
|
|| ( Event->iQueued > 0 ) ) );
|
||||||
|
}
|
||||||
|
if( ( Event != nullptr )
|
||||||
|
&& ( false == Event->m_ignored ) ) {
|
||||||
|
// standardowe dodanie do kolejki
|
||||||
|
++Event->iQueued; // zabezpieczenie przed podwójnym dodaniem do kolejki
|
||||||
|
WriteLog( "EVENT ADDED TO QUEUE" + ( Owner ? ( " by " + Owner->asName ) : "" ) + ": " + Event->asName );
|
||||||
|
Event->fStartTime = std::abs( Event->fDelay ) + Timer::GetTime(); // czas od uruchomienia scenerii
|
||||||
|
if( Event->fRandomDelay > 0.0 ) {
|
||||||
|
// doliczenie losowego czasu opóźnienia
|
||||||
|
Event->fStartTime += Event->fRandomDelay * Random( 10000 ) * 0.0001;
|
||||||
|
}
|
||||||
|
if( QueryRootEvent != nullptr ) {
|
||||||
|
TEvent::AddToQuery( Event, QueryRootEvent );
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
QueryRootEvent = Event;
|
||||||
|
QueryRootEvent->evNext = nullptr;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
4
Event.h
4
Event.h
@@ -104,7 +104,7 @@ public:
|
|||||||
TEventType Type = tp_Unknown;
|
TEventType Type = tp_Unknown;
|
||||||
double fStartTime = 0.0;
|
double fStartTime = 0.0;
|
||||||
double fDelay = 0.0;
|
double fDelay = 0.0;
|
||||||
TDynamicObject *Activator = nullptr;
|
TDynamicObject const *Activator = nullptr;
|
||||||
TParam Params[13]; // McZapkie-070502 //Ra: zamienić to na union/struct
|
TParam Params[13]; // McZapkie-070502 //Ra: zamienić to na union/struct
|
||||||
unsigned int iFlags = 0; // zamiast Params[8] z flagami warunku
|
unsigned int iFlags = 0; // zamiast Params[8] z flagami warunku
|
||||||
std::string asNodeName; // McZapkie-100302 - dodalem zeby zapamietac nazwe toru
|
std::string asNodeName; // McZapkie-100302 - dodalem zeby zapamietac nazwe toru
|
||||||
@@ -147,7 +147,7 @@ public:
|
|||||||
FindEvent( std::string const &Name );
|
FindEvent( std::string const &Name );
|
||||||
// legacy method, inserts specified event in the event query
|
// legacy method, inserts specified event in the event query
|
||||||
bool
|
bool
|
||||||
AddToQuery( TEvent *Event, TDynamicObject *Owner );
|
AddToQuery( TEvent *Event, TDynamicObject const *Owner );
|
||||||
// legacy method, executes queued events
|
// legacy method, executes queued events
|
||||||
bool
|
bool
|
||||||
CheckQuery();
|
CheckQuery();
|
||||||
|
|||||||
@@ -1714,19 +1714,12 @@ bool TMoverParameters::IncMainCtrl(int CtrlSpeed)
|
|||||||
// szybkie przejœcie na bezoporow¹
|
// szybkie przejœcie na bezoporow¹
|
||||||
if( TrainType == dt_ET40 ) {
|
if( TrainType == dt_ET40 ) {
|
||||||
break; // this means ET40 won't react at all to fast acceleration command. should it issue just IncMainCtrl(1) instead?
|
break; // this means ET40 won't react at all to fast acceleration command. should it issue just IncMainCtrl(1) instead?
|
||||||
}
|
}
|
||||||
while( ( RList[ MainCtrlPos ].R > 0.0 )
|
while( ( RList[ MainCtrlPos ].R > 0.0 )
|
||||||
&& IncMainCtrl( 1 ) ) {
|
&& IncMainCtrl( 1 ) ) {
|
||||||
// all work is done in the loop header
|
// all work is done in the loop header
|
||||||
;
|
;
|
||||||
}
|
}
|
||||||
// OK:=true ; {takie chamskie, potem poprawie} <-Ra: kto mia³ to poprawiæ i po co?
|
|
||||||
if( ActiveDir < 0 ) {
|
|
||||||
while( ( RList[ MainCtrlPos ].Bn > 1 )
|
|
||||||
&& IncMainCtrl( 1 ) ) {
|
|
||||||
--MainCtrlPos;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
OK = false; // shouldn't this be part of the loop above?
|
OK = false; // shouldn't this be part of the loop above?
|
||||||
// if (TrainType=dt_ET40) then
|
// if (TrainType=dt_ET40) then
|
||||||
// while Abs (Im)>IminHi do
|
// while Abs (Im)>IminHi do
|
||||||
@@ -1752,14 +1745,6 @@ bool TMoverParameters::IncMainCtrl(int CtrlSpeed)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if( ActiveDir < 0 ) {
|
|
||||||
if( ( TrainType != dt_PseudoDiesel )
|
|
||||||
&& ( RList[ MainCtrlPos ].Bn > 1 ) ) {
|
|
||||||
// blokada wejścia na równoległą podczas jazdy do tyłu
|
|
||||||
--MainCtrlPos;
|
|
||||||
OK = false;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
//
|
//
|
||||||
// if (TrainType == "et40")
|
// if (TrainType == "et40")
|
||||||
// if (Abs(Im) > IminHi)
|
// if (Abs(Im) > IminHi)
|
||||||
@@ -1768,15 +1753,14 @@ bool TMoverParameters::IncMainCtrl(int CtrlSpeed)
|
|||||||
// OK = false;
|
// OK = false;
|
||||||
// }
|
// }
|
||||||
//}
|
//}
|
||||||
}
|
}
|
||||||
|
|
||||||
if( ( TrainType == dt_ET42 ) && ( true == DynamicBrakeFlag ) ) {
|
if( ( TrainType == dt_ET42 ) && ( true == DynamicBrakeFlag ) ) {
|
||||||
if( MainCtrlPos > 20 ) {
|
if( MainCtrlPos > 20 ) {
|
||||||
MainCtrlPos = 20;
|
MainCtrlPos = 20;
|
||||||
OK = false;
|
OK = false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// return OK;
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -2866,7 +2850,6 @@ bool TMoverParameters::IncLocalBrakeLevel(int CtrlSpeed)
|
|||||||
while ((LocalBrakePos < LocalBrakePosNo) && (CtrlSpeed > 0))
|
while ((LocalBrakePos < LocalBrakePosNo) && (CtrlSpeed > 0))
|
||||||
{
|
{
|
||||||
LocalBrakePos++;
|
LocalBrakePos++;
|
||||||
// LocalBrakePosA = static_cast<double>(LocalBrakePos) / LocalBrakePosNo; // temporary hack until i figure out how this element is supposed to work
|
|
||||||
CtrlSpeed--;
|
CtrlSpeed--;
|
||||||
}
|
}
|
||||||
IBL = true;
|
IBL = true;
|
||||||
@@ -2890,7 +2873,6 @@ bool TMoverParameters::DecLocalBrakeLevel(int CtrlSpeed)
|
|||||||
while ((CtrlSpeed > 0) && (LocalBrakePos > 0))
|
while ((CtrlSpeed > 0) && (LocalBrakePos > 0))
|
||||||
{
|
{
|
||||||
LocalBrakePos--;
|
LocalBrakePos--;
|
||||||
// LocalBrakePosA = static_cast<double>( LocalBrakePos ) / LocalBrakePosNo; // temporary hack until i figure out how this element is supposed to work
|
|
||||||
CtrlSpeed--;
|
CtrlSpeed--;
|
||||||
}
|
}
|
||||||
DBL = true;
|
DBL = true;
|
||||||
@@ -2912,7 +2894,6 @@ bool TMoverParameters::IncLocalBrakeLevelFAST(void)
|
|||||||
if (LocalBrakePos < LocalBrakePosNo)
|
if (LocalBrakePos < LocalBrakePosNo)
|
||||||
{
|
{
|
||||||
LocalBrakePos = LocalBrakePosNo;
|
LocalBrakePos = LocalBrakePosNo;
|
||||||
// LocalBrakePosA = static_cast<double>( LocalBrakePos ) / LocalBrakePosNo; // temporary hack until i figure out how this element is supposed to work
|
|
||||||
ILBLF = true;
|
ILBLF = true;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
@@ -2931,7 +2912,6 @@ bool TMoverParameters::DecLocalBrakeLevelFAST(void)
|
|||||||
if (LocalBrakePos > 0)
|
if (LocalBrakePos > 0)
|
||||||
{
|
{
|
||||||
LocalBrakePos = 0;
|
LocalBrakePos = 0;
|
||||||
// LocalBrakePosA = static_cast<double>( LocalBrakePos ) / LocalBrakePosNo; // temporary hack until i figure out how this element is supposed to work
|
|
||||||
DLBLF = true;
|
DLBLF = true;
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
@@ -6472,7 +6452,7 @@ void TMoverParameters::dizel_Heat( double const dt ) {
|
|||||||
auto const zaluzje2 { ( dizel_heat.zaluzje2 ? 1 : 0 ) };
|
auto const zaluzje2 { ( dizel_heat.zaluzje2 ? 1 : 0 ) };
|
||||||
// auxiliary water circuit heat transfer values
|
// auxiliary water circuit heat transfer values
|
||||||
auto const kf2 { kurek07 * ( ( dizel_heat.kw * ( 0.3 + 0.7 * zaluzje2 ) ) * dizel_heat.rpmw2 + ( dizel_heat.kv * ( 0.3 + 0.7 * zaluzje2 ) * Vel / 3.6 ) ) + 2 };
|
auto const kf2 { kurek07 * ( ( dizel_heat.kw * ( 0.3 + 0.7 * zaluzje2 ) ) * dizel_heat.rpmw2 + ( dizel_heat.kv * ( 0.3 + 0.7 * zaluzje2 ) * Vel / 3.6 ) ) + 2 };
|
||||||
auto const dTs2 { ( ( dizel_heat.kfs * ( 0.3 ) * ( dizel_heat.To - dizel_heat.Tsr2 ) ) ) / ( gw2 * Cw ) };
|
auto const dTs2 { ( ( dizel_heat.kfo2 * ( dizel_heat.To - dizel_heat.Tsr2 ) ) ) / ( gw2 * Cw ) };
|
||||||
// przy otwartym kurku B ma³y obieg jest dogrzewany przez du¿y - stosujemy przy korzystaniu z podgrzewacza oraz w zimie
|
// przy otwartym kurku B ma³y obieg jest dogrzewany przez du¿y - stosujemy przy korzystaniu z podgrzewacza oraz w zimie
|
||||||
auto const Qch2 { -kf2 * ( dizel_heat.Tsr2 - dizel_heat.Te ) + ( 80 * ( true == WaterCircuitsLink ? 1 : 0 ) * ( dizel_heat.Twy - dizel_heat.Tsr2 ) ) };
|
auto const Qch2 { -kf2 * ( dizel_heat.Tsr2 - dizel_heat.Te ) + ( 80 * ( true == WaterCircuitsLink ? 1 : 0 ) * ( dizel_heat.Twy - dizel_heat.Tsr2 ) ) };
|
||||||
auto const dTch2 { Qch2 / ( gw2 * Cw ) };
|
auto const dTch2 { Qch2 / ( gw2 * Cw ) };
|
||||||
|
|||||||
10
Track.cpp
10
Track.cpp
@@ -922,6 +922,16 @@ bool TTrack::AssignForcedEvents(TEvent *NewEventPlus, TEvent *NewEventMinus)
|
|||||||
return false;
|
return false;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
void TTrack::QueueEvents( event_sequence const &Events, TDynamicObject const *Owner ) {
|
||||||
|
|
||||||
|
for( auto const &event : Events ) {
|
||||||
|
if( ( event.second != nullptr )
|
||||||
|
&& ( event.second->fDelay <= -1.0 ) ) {
|
||||||
|
simulation::Events.AddToQuery( event.second, Owner );
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
std::string TTrack::IsolatedName()
|
std::string TTrack::IsolatedName()
|
||||||
{ // podaje nazwę odcinka izolowanego, jesli nie ma on jeszcze przypisanych zdarzeń
|
{ // podaje nazwę odcinka izolowanego, jesli nie ma on jeszcze przypisanych zdarzeń
|
||||||
if (pIsolated)
|
if (pIsolated)
|
||||||
|
|||||||
1
Track.h
1
Track.h
@@ -247,6 +247,7 @@ public:
|
|||||||
void Load(cParser *parser, Math3D::vector3 pOrigin);
|
void Load(cParser *parser, Math3D::vector3 pOrigin);
|
||||||
bool AssignEvents();
|
bool AssignEvents();
|
||||||
bool AssignForcedEvents(TEvent *NewEventPlus, TEvent *NewEventMinus);
|
bool AssignForcedEvents(TEvent *NewEventPlus, TEvent *NewEventMinus);
|
||||||
|
void QueueEvents( event_sequence const &Events, TDynamicObject const *Owner );
|
||||||
bool CheckDynamicObject(TDynamicObject *Dynamic);
|
bool CheckDynamicObject(TDynamicObject *Dynamic);
|
||||||
bool AddDynamicObject(TDynamicObject *Dynamic);
|
bool AddDynamicObject(TDynamicObject *Dynamic);
|
||||||
bool RemoveDynamicObject(TDynamicObject *Dynamic);
|
bool RemoveDynamicObject(TDynamicObject *Dynamic);
|
||||||
|
|||||||
10
Train.cpp
10
Train.cpp
@@ -919,7 +919,12 @@ void TTrain::OnCommand_independentbrakedecreasefast( TTrain *Train, command_data
|
|||||||
}
|
}
|
||||||
|
|
||||||
void TTrain::OnCommand_independentbrakeset( TTrain *Train, command_data const &Command ) {
|
void TTrain::OnCommand_independentbrakeset( TTrain *Train, command_data const &Command ) {
|
||||||
|
|
||||||
|
Train->mvControlled->LocalBrakePosA = (
|
||||||
|
clamp(
|
||||||
|
reinterpret_cast<double const &>( Command.param1 ),
|
||||||
|
0.0, 1.0 ) );
|
||||||
|
/*
|
||||||
Train->mvControlled->LocalBrakePos = (
|
Train->mvControlled->LocalBrakePos = (
|
||||||
std::round(
|
std::round(
|
||||||
interpolate<double>(
|
interpolate<double>(
|
||||||
@@ -928,6 +933,7 @@ void TTrain::OnCommand_independentbrakeset( TTrain *Train, command_data const &C
|
|||||||
clamp(
|
clamp(
|
||||||
reinterpret_cast<double const &>( Command.param1 ),
|
reinterpret_cast<double const &>( Command.param1 ),
|
||||||
0.0, 1.0 ) ) ) );
|
0.0, 1.0 ) ) ) );
|
||||||
|
*/
|
||||||
}
|
}
|
||||||
|
|
||||||
void TTrain::OnCommand_independentbrakebailoff( TTrain *Train, command_data const &Command ) {
|
void TTrain::OnCommand_independentbrakebailoff( TTrain *Train, command_data const &Command ) {
|
||||||
@@ -5174,7 +5180,7 @@ bool TTrain::Update( double const Deltatime )
|
|||||||
#endif
|
#endif
|
||||||
{
|
{
|
||||||
// standardowa prodedura z kranem powiązanym z klawiaturą
|
// standardowa prodedura z kranem powiązanym z klawiaturą
|
||||||
ggLocalBrake.UpdateValue( double( mvOccupied->LocalBrakePos ) );
|
ggLocalBrake.UpdateValue( std::max<double>( mvOccupied->LocalBrakePos, mvOccupied->LocalBrakePosA * LocalBrakePosNo ) );
|
||||||
}
|
}
|
||||||
ggLocalBrake.Update();
|
ggLocalBrake.Update();
|
||||||
}
|
}
|
||||||
|
|||||||
75
TrkFoll.cpp
75
TrkFoll.cpp
@@ -109,19 +109,9 @@ bool TTrackFollower::Move(double fDistance, bool bPrimary)
|
|||||||
if( ( Owner->Mechanik != nullptr )
|
if( ( Owner->Mechanik != nullptr )
|
||||||
&& ( Owner->Mechanik->Primary() ) ) {
|
&& ( Owner->Mechanik->Primary() ) ) {
|
||||||
// tylko dla jednego członu
|
// tylko dla jednego członu
|
||||||
for( auto &event : pCurrentTrack->m_events0 ) {
|
pCurrentTrack->QueueEvents( pCurrentTrack->m_events0, Owner );
|
||||||
if( ( event.second != nullptr )
|
|
||||||
&& ( event.second->iQueued == 0 ) ) {
|
|
||||||
simulation::Events.AddToQuery( event.second, Owner );
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
for( auto &event : pCurrentTrack->m_events0all ) {
|
|
||||||
if( ( event.second != nullptr )
|
|
||||||
&& ( event.second->iQueued == 0 ) ) {
|
|
||||||
simulation::Events.AddToQuery( event.second, Owner );
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
pCurrentTrack->QueueEvents( pCurrentTrack->m_events0all, Owner );
|
||||||
}
|
}
|
||||||
else if (fDistance < 0) {
|
else if (fDistance < 0) {
|
||||||
// event1, eventall1
|
// event1, eventall1
|
||||||
@@ -132,26 +122,14 @@ bool TTrackFollower::Move(double fDistance, bool bPrimary)
|
|||||||
// tylko dla jednego członu
|
// tylko dla jednego członu
|
||||||
// McZapkie-280503: wyzwalanie event tylko dla pojazdow z obsada
|
// McZapkie-280503: wyzwalanie event tylko dla pojazdow z obsada
|
||||||
if( true == bPrimary ) {
|
if( true == bPrimary ) {
|
||||||
for( auto &event : pCurrentTrack->m_events1 ) {
|
pCurrentTrack->QueueEvents( pCurrentTrack->m_events1, Owner );
|
||||||
if( ( event.second != nullptr )
|
|
||||||
&& ( event.second->iQueued == 0 ) ) {
|
|
||||||
// dodanie do kolejki
|
|
||||||
simulation::Events.AddToQuery( event.second, Owner );
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if( SetFlag( iEventallFlag, -1 ) ) {
|
if( SetFlag( iEventallFlag, -1 ) ) {
|
||||||
// McZapkie-280503: wyzwalanie eventall dla wszystkich pojazdow
|
// McZapkie-280503: wyzwalanie eventall dla wszystkich pojazdow
|
||||||
if( true == bPrimary ) {
|
if( true == bPrimary ) {
|
||||||
for( auto &event : pCurrentTrack->m_events1all ) {
|
pCurrentTrack->QueueEvents( pCurrentTrack->m_events1all, Owner );
|
||||||
if( ( event.second != nullptr )
|
|
||||||
&& ( event.second->iQueued == 0 ) ) {
|
|
||||||
// dodanie do kolejki
|
|
||||||
simulation::Events.AddToQuery( event.second, Owner );
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -163,26 +141,14 @@ bool TTrackFollower::Move(double fDistance, bool bPrimary)
|
|||||||
&& ( Owner->Mechanik->Primary() ) ) {
|
&& ( Owner->Mechanik->Primary() ) ) {
|
||||||
// tylko dla jednego członu
|
// tylko dla jednego członu
|
||||||
if( true == bPrimary ) {
|
if( true == bPrimary ) {
|
||||||
for( auto &event : pCurrentTrack->m_events2 ) {
|
pCurrentTrack->QueueEvents( pCurrentTrack->m_events2, Owner );
|
||||||
if( ( event.second != nullptr )
|
|
||||||
&& ( event.second->iQueued == 0 ) ) {
|
|
||||||
// dodanie do kolejki
|
|
||||||
simulation::Events.AddToQuery( event.second, Owner );
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
if( SetFlag( iEventallFlag, -2 ) ) {
|
if( SetFlag( iEventallFlag, -2 ) ) {
|
||||||
// sprawdza i zeruje na przyszłość, true jeśli zmieni z 2 na 0
|
// sprawdza i zeruje na przyszłość, true jeśli zmieni z 2 na 0
|
||||||
if( true == bPrimary ) {
|
if( true == bPrimary ) {
|
||||||
for( auto &event : pCurrentTrack->m_events2all ) {
|
pCurrentTrack->QueueEvents( pCurrentTrack->m_events2all, Owner );
|
||||||
if( ( event.second != nullptr )
|
|
||||||
&& ( event.second->iQueued == 0 ) ) {
|
|
||||||
// dodanie do kolejki
|
|
||||||
simulation::Events.AddToQuery( event.second, Owner );
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -279,34 +245,13 @@ bool TTrackFollower::Move(double fDistance, bool bPrimary)
|
|||||||
{ // tylko gdy początkowe ustawienie, dodajemy eventy stania do kolejki
|
{ // tylko gdy początkowe ustawienie, dodajemy eventy stania do kolejki
|
||||||
if (Owner->MoverParameters->ActiveCab != 0) {
|
if (Owner->MoverParameters->ActiveCab != 0) {
|
||||||
|
|
||||||
for( auto &event : pCurrentTrack->m_events1 ) {
|
pCurrentTrack->QueueEvents( pCurrentTrack->m_events1, Owner );
|
||||||
if( ( event.second != nullptr )
|
pCurrentTrack->QueueEvents( pCurrentTrack->m_events2, Owner );
|
||||||
&& ( event.second->fDelay <= -1.0 ) ) {
|
|
||||||
simulation::Events.AddToQuery( event.second, Owner );
|
|
||||||
}
|
|
||||||
}
|
|
||||||
for( auto &event : pCurrentTrack->m_events2 ) {
|
|
||||||
if( ( event.second != nullptr )
|
|
||||||
&& ( event.second->fDelay <= -1.0 ) ) {
|
|
||||||
simulation::Events.AddToQuery( event.second, Owner );
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
for( auto &event : pCurrentTrack->m_events1all ) {
|
|
||||||
if( ( event.second != nullptr )
|
|
||||||
&& ( event.second->fDelay <= -1.0 ) ) {
|
|
||||||
simulation::Events.AddToQuery( event.second, Owner );
|
|
||||||
}
|
|
||||||
}
|
|
||||||
for( auto &event : pCurrentTrack->m_events2all ) {
|
|
||||||
if( ( event.second != nullptr )
|
|
||||||
&& ( event.second->fDelay <= -1.0 ) ) {
|
|
||||||
simulation::Events.AddToQuery( event.second, Owner );
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
pCurrentTrack->QueueEvents( pCurrentTrack->m_events1all, Owner );
|
||||||
|
pCurrentTrack->QueueEvents( pCurrentTrack->m_events2all, Owner );
|
||||||
}
|
}
|
||||||
fCurrentDistance = s;
|
fCurrentDistance = s;
|
||||||
// fDistance=0;
|
|
||||||
return ComputatePosition(); // przeliczenie XYZ, true o ile nie wyjechał na NULL
|
return ComputatePosition(); // przeliczenie XYZ, true o ile nie wyjechał na NULL
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
67
TrkFoll.h
67
TrkFoll.h
@@ -13,49 +13,50 @@ http://mozilla.org/MPL/2.0/.
|
|||||||
#include "classes.h"
|
#include "classes.h"
|
||||||
#include "segment.h"
|
#include "segment.h"
|
||||||
|
|
||||||
class TTrackFollower
|
// oś poruszająca się po torze
|
||||||
{ // oś poruszająca się po torze
|
class TTrackFollower {
|
||||||
private:
|
|
||||||
TTrack *pCurrentTrack = nullptr; // na którym torze siê znajduje
|
public:
|
||||||
std::shared_ptr<TSegment> pCurrentSegment; // zwrotnice mog¹ mieæ dwa segmenty
|
// constructors
|
||||||
double fCurrentDistance = 0.0; // przesuniêcie wzglêdem Point1 w stronê Point2
|
|
||||||
double fDirection = 1.0; // ustawienie wzglêdem toru: -1.0 albo 1.0, mno¿one przez dystans // jest przodem do Point2
|
|
||||||
bool ComputatePosition(); // przeliczenie pozycji na torze
|
|
||||||
TDynamicObject *Owner = nullptr; // pojazd posiadający
|
|
||||||
int iEventFlag = 0; // McZapkie-020602: informacja o tym czy wyzwalac zdarzenie: 0,1,2,3
|
|
||||||
int iEventallFlag = 0;
|
|
||||||
int iSegment = 0; // który segment toru jest używany (żeby nie przeskakiwało po przestawieniu
|
|
||||||
// zwrotnicy pod taborem)
|
|
||||||
public:
|
|
||||||
double fOffsetH = 0.0; // Ra: odległość środka osi od osi toru (dla samochodów) - użyć do wężykowania
|
|
||||||
Math3D::vector3 pPosition; // współrzędne XYZ w układzie scenerii
|
|
||||||
Math3D::vector3 vAngles; // x:przechyłka, y:pochylenie, z:kierunek w planie (w radianach)
|
|
||||||
TTrackFollower() = default;
|
TTrackFollower() = default;
|
||||||
|
// destructor
|
||||||
~TTrackFollower();
|
~TTrackFollower();
|
||||||
|
// methods
|
||||||
TTrack * SetCurrentTrack(TTrack *pTrack, int end);
|
TTrack * SetCurrentTrack(TTrack *pTrack, int end);
|
||||||
bool Move(double fDistance, bool bPrimary);
|
bool Move(double fDistance, bool bPrimary);
|
||||||
inline TTrack * GetTrack() const
|
inline TTrack * GetTrack() const {
|
||||||
{
|
return pCurrentTrack; };
|
||||||
return pCurrentTrack;
|
// przechyłka policzona przy ustalaniu pozycji
|
||||||
};
|
inline double GetRoll() {
|
||||||
inline double GetRoll()
|
return vAngles.x; };
|
||||||
{
|
|
||||||
return vAngles.x;
|
|
||||||
}; // przechyłka policzona przy ustalaniu pozycji
|
|
||||||
//{return pCurrentSegment->GetRoll(fCurrentDistance)*fDirection;}; //zamiast liczyć można pobrać
|
//{return pCurrentSegment->GetRoll(fCurrentDistance)*fDirection;}; //zamiast liczyć można pobrać
|
||||||
inline double GetDirection() const
|
// zwrot na torze
|
||||||
{
|
inline double GetDirection() const {
|
||||||
return fDirection;
|
return fDirection; };
|
||||||
}; // zwrot na torze
|
// ABu-030403
|
||||||
inline double GetTranslation() const
|
inline double GetTranslation() const {
|
||||||
{
|
return fCurrentDistance; };
|
||||||
return fCurrentDistance;
|
|
||||||
}; // ABu-030403
|
|
||||||
// inline double GetLength(vector3 p1, vector3 cp1, vector3 cp2, vector3 p2)
|
// inline double GetLength(vector3 p1, vector3 cp1, vector3 cp2, vector3 p2)
|
||||||
//{ return pCurrentSegment->ComputeLength(p1,cp1,cp2,p2); };
|
//{ return pCurrentSegment->ComputeLength(p1,cp1,cp2,p2); };
|
||||||
// inline double GetRadius(double L, double d); //McZapkie-150503
|
// inline double GetRadius(double L, double d); //McZapkie-150503
|
||||||
bool Init(TTrack *pTrack, TDynamicObject *NewOwner, double fDir);
|
bool Init(TTrack *pTrack, TDynamicObject *NewOwner, double fDir);
|
||||||
void Render(float fNr);
|
void Render(float fNr);
|
||||||
|
// members
|
||||||
|
double fOffsetH = 0.0; // Ra: odległość środka osi od osi toru (dla samochodów) - użyć do wężykowania
|
||||||
|
Math3D::vector3 pPosition; // współrzędne XYZ w układzie scenerii
|
||||||
|
Math3D::vector3 vAngles; // x:przechyłka, y:pochylenie, z:kierunek w planie (w radianach)
|
||||||
|
private:
|
||||||
|
// methods
|
||||||
|
bool ComputatePosition(); // przeliczenie pozycji na torze
|
||||||
|
// members
|
||||||
|
TTrack *pCurrentTrack = nullptr; // na którym torze siê znajduje
|
||||||
|
std::shared_ptr<TSegment> pCurrentSegment; // zwrotnice mog¹ mieæ dwa segmenty
|
||||||
|
double fCurrentDistance = 0.0; // przesuniêcie wzglêdem Point1 w stronê Point2
|
||||||
|
double fDirection = 1.0; // ustawienie wzglêdem toru: -1.0 albo 1.0, mno¿one przez dystans // jest przodem do Point2
|
||||||
|
TDynamicObject *Owner = nullptr; // pojazd posiadający
|
||||||
|
int iEventFlag = 0; // McZapkie-020602: informacja o tym czy wyzwalac zdarzenie: 0,1,2,3
|
||||||
|
int iEventallFlag = 0;
|
||||||
|
int iSegment = 0; // który segment toru jest używany (żeby nie przeskakiwało po przestawieniu zwrotnicy pod taborem)
|
||||||
};
|
};
|
||||||
//---------------------------------------------------------------------------
|
//---------------------------------------------------------------------------
|
||||||
#endif
|
#endif
|
||||||
|
|||||||
@@ -75,7 +75,7 @@ mouse_input::button( int const Button, int const Action ) {
|
|||||||
|
|
||||||
if( true == FreeFlyModeFlag ) {
|
if( true == FreeFlyModeFlag ) {
|
||||||
// world editor controls
|
// world editor controls
|
||||||
// currently we only handle view panning in this mode
|
// TODO: separate behaviour when the scenery editor is active and in 'regular' free fly mode
|
||||||
if( Action == GLFW_RELEASE ) {
|
if( Action == GLFW_RELEASE ) {
|
||||||
// if it's the right mouse button that got released we were potentially in view panning mode; stop it
|
// if it's the right mouse button that got released we were potentially in view panning mode; stop it
|
||||||
if( Button == GLFW_MOUSE_BUTTON_RIGHT ) {
|
if( Button == GLFW_MOUSE_BUTTON_RIGHT ) {
|
||||||
@@ -84,6 +84,19 @@ mouse_input::button( int const Button, int const Action ) {
|
|||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
// button press
|
// button press
|
||||||
|
if( Button == GLFW_MOUSE_BUTTON_LEFT ) {
|
||||||
|
// the left button selects scene node
|
||||||
|
// further behaviour can vary depending on whether we're in editor mode
|
||||||
|
auto const *node { GfxRenderer.Update_Pick_Node() };
|
||||||
|
if( true == EditorModeFlag ) {
|
||||||
|
// NOTE: until we have proper editor object in place we set the current node manually
|
||||||
|
editor::Node = node;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
// launch on_click event associated with to the node
|
||||||
|
// TODO: implement
|
||||||
|
}
|
||||||
|
}
|
||||||
if( Button == GLFW_MOUSE_BUTTON_RIGHT ) {
|
if( Button == GLFW_MOUSE_BUTTON_RIGHT ) {
|
||||||
// the right button activates mouse panning mode
|
// the right button activates mouse panning mode
|
||||||
m_pickmodepanning = true;
|
m_pickmodepanning = true;
|
||||||
|
|||||||
@@ -762,4 +762,11 @@ basic_node::radius_() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
} // scene
|
} // scene
|
||||||
|
|
||||||
|
namespace editor {
|
||||||
|
|
||||||
|
scene::basic_node const *Node { nullptr }; // temporary helper, currently selected scene node
|
||||||
|
|
||||||
|
} // editor
|
||||||
|
|
||||||
//---------------------------------------------------------------------------
|
//---------------------------------------------------------------------------
|
||||||
|
|||||||
@@ -381,4 +381,10 @@ basic_node::visible() const {
|
|||||||
|
|
||||||
} // scene
|
} // scene
|
||||||
|
|
||||||
|
namespace editor {
|
||||||
|
|
||||||
|
extern scene::basic_node const *Node; // temporary helper, currently selected scene node
|
||||||
|
|
||||||
|
} // editor
|
||||||
|
|
||||||
//---------------------------------------------------------------------------
|
//---------------------------------------------------------------------------
|
||||||
|
|||||||
@@ -465,7 +465,7 @@ float
|
|||||||
sound_source::compute_combined_point() const {
|
sound_source::compute_combined_point() const {
|
||||||
|
|
||||||
return (
|
return (
|
||||||
m_properties.pitch < 1.1f ?
|
m_properties.pitch <= 1.f ?
|
||||||
// most sounds use 0-1 value range, we clamp these to 0-99 to allow more intuitive sound definition in .mmd files
|
// most sounds use 0-1 value range, we clamp these to 0-99 to allow more intuitive sound definition in .mmd files
|
||||||
clamp( m_properties.pitch, 0.f, 0.99f ) :
|
clamp( m_properties.pitch, 0.f, 0.99f ) :
|
||||||
std::max( 0.f, m_properties.pitch )
|
std::max( 0.f, m_properties.pitch )
|
||||||
|
|||||||
2
stdafx.h
2
stdafx.h
@@ -85,6 +85,8 @@
|
|||||||
//m7todo: jest tu bo nie chcia³o mi siê wpychaæ do wszystkich plików
|
//m7todo: jest tu bo nie chcia³o mi siê wpychaæ do wszystkich plików
|
||||||
#include <GLFW/glfw3.h>
|
#include <GLFW/glfw3.h>
|
||||||
|
|
||||||
|
#define GLM_ENABLE_EXPERIMENTAL
|
||||||
|
#define GLM_FORCE_CTOR_INIT
|
||||||
#include <glm/glm.hpp>
|
#include <glm/glm.hpp>
|
||||||
#include <glm/gtc/matrix_transform.hpp>
|
#include <glm/gtc/matrix_transform.hpp>
|
||||||
#include <glm/gtc/matrix_access.hpp>
|
#include <glm/gtc/matrix_access.hpp>
|
||||||
|
|||||||
@@ -708,6 +708,13 @@ ui_layer::update() {
|
|||||||
|
|
||||||
case( GLFW_KEY_F11 ): {
|
case( GLFW_KEY_F11 ): {
|
||||||
// scenario inspector
|
// scenario inspector
|
||||||
|
auto const *node { editor::Node };
|
||||||
|
|
||||||
|
if( node == nullptr ) { break; }
|
||||||
|
|
||||||
|
uitextline1 =
|
||||||
|
"Node name: " + node->name()
|
||||||
|
+ "; location: [" + to_string( node->location().x, 2 ) + ", " + to_string( node->location().y, 2 ) + ", " + to_string( node->location().z, 2 ) + "]";
|
||||||
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|||||||
Reference in New Issue
Block a user