rusEFI
The most advanced open source ECU
Public Member Functions | Data Fields | Private Member Functions | Private Attributes
Engine Class Referencefinal

#include <engine.h>

Inheritance diagram for Engine:
Inheritance graph
[legend]
Collaboration diagram for Engine:
Collaboration graph
[legend]

Public Member Functions

 Engine ()
 
template<typename get_t >
constexpr auto & module ()
 
void resetLua ()
 
void OnTriggerStateProperState (efitick_t nowNt) override
 
void OnTriggerSynchronization (bool wasSynchronized, bool isDecodingError) override
 
void OnTriggerSynchronizationLost () override
 
void setConfig ()
 
int getBailedOnDwellCount () const
 
void incrementBailedOnDwellCount ()
 
int getGlobalConfigurationVersion (void) const
 
void periodicFastCallback ()
 
void periodicSlowCallback ()
 
void updateSlowSensors ()
 
void updateSwitchInputs ()
 
void updateTriggerWaveform ()
 
void resetEngineSnifferIfInTestMode ()
 
void preCalculate ()
 
void efiWatchdog ()
 
void onEngineHasStopped ()
 
void checkShutdown ()
 
bool isInShutdownMode () const
 
bool isMainRelayEnabled () const
 
void onSparkFireKnockSense (uint8_t cylinderIndex, efitick_t nowNt)
 

Data Fields

StartStopState startStopState
 
bool enableOverdwellProtection = true
 
TunerStudioOutputChannels outputChannels
 
bool allowCanTx = true
 
bool isPwmEnabled = true
 
const char * prevOutputName = nullptr
 
bool pauseCANdueToSerial = false
 
PinRepository pinRepository
 
IEtbControlleretbControllers [ETB_COUNT] = {nullptr}
 
FuelComputer fuelComputer
 
type_list< Mockable< InjectorModelPrimary >, Mockable< InjectorModelSecondary >,#if EFI_IDLE_CONTROL Mockable< IdleController >,#endif TriggerScheduler,#if EFI_HPFP &&EFI_ENGINE_CONTROL HpfpController,#endif #if EFI_ENGINE_CONTROL Mockable< ThrottleModel >,#endif #if EFI_ALTERNATOR_CONTROL AlternatorController,#endif FuelPumpController, MainRelayController, IgnitionController, Mockable< AcController >, FanControl1, FanControl2, PrimeController, DfcoController,#if EFI_HD_ACR HarleyAcr,#endif Mockable< WallFuelController >,#if EFI_VEHICLE_SPEED GearDetector, TripOdometer,#endif KnockController, SensorChecker,#if EFI_ENGINE_CONTROL LimpManager,#endif #if EFI_VVT_PID VvtController1, VvtController2, VvtController3, VvtController4,#endif #if EFI_BOOST_CONTROL BoostController,#endif EngineModuleengineModules
 
GearControllerBasegearController
 
SwitchedState clutchUpSwitchedState
 
SwitchedState brakePedalSwitchedState
 
SwitchedState acButtonSwitchedState
 
SimpleSwitchedState luaDigitalInputState [LUA_DIGITAL_INPUT_COUNT]
 
LaunchControlBase launchController
 
SoftSparkLimiter softSparkLimiter
 
SoftSparkLimiter hardSparkLimiter
 
AntilagSystemBase antilagController
 
LambdaMonitor lambdaMonitor
 
IgnitionState ignitionState
 
LocalVersionHolder versionForConfigurationListeners
 
AuxActor auxValves [AUX_DIGITAL_VALVE_COUNT][2]
 
bool needTdcCallback = true
 
SingleTimerExecutor executor
 
SleepExecutor executor
 
TestExecutor executor
 
std::function< void(IgnitionEvent *, bool)> onIgnitionEvent
 
std::function< void(const IgnitionEvent &, efitick_t, angle_t, efitick_t)> onScheduleTurnSparkPinHighStartCharging = [](const IgnitionEvent&, efitick_t, angle_t, efitick_t) -> void {}
 
std::function< void(const IgnitionEvent &, efitick_t)> onScheduleOverFireSparkAndPrepareNextSchedule = [](const IgnitionEvent&, efitick_t) -> void {}
 
FuelSchedule injectionEvents
 
IgnitionEventList ignitionEvents
 
scheduling_s tdcScheduler [2]
 
bool etbAutoTune = false
 
bool tdcMarkEnabled = true
 
bool slowCallBackWasInvoked = false
 
RpmCalculator rpmCalculator
 
Timer configBurnTimer
 
int globalConfigurationVersion = 0
 
TpsAccelEnrichment tpsAccelEnrichment
 
TriggerCentral triggerCentral
 
bool isRunningPwmTest = false
 
bool isFunctionalTestMode = false
 
EngineState engineState
 
dc_motors_s dc_motors
 
sent_state_s sent_state
 
percent_t blipIdlePosition
 
efitimeus_t timeToStopBlip = 0
 
efitimeus_t timeToStopIdleTest = 0
 
SensorsState sensors
 
AirmassModelBasemockAirmassModel = nullptr
 

Private Member Functions

void reset ()
 
void injectEngineReferences ()
 

Private Attributes

int bailedOnDwellCount = 0
 

Detailed Description

Definition at line 90 of file engine.h.

Constructor & Destructor Documentation

◆ Engine()

Engine::Engine ( )

Definition at line 297 of file engine.cpp.

300  acButtonSwitchedState(&module<AcController>().unmock().acButtonState)
301 
302 #if EFI_LAUNCH_CONTROL
303 
304  , softSparkLimiter(false), hardSparkLimiter(true)
305 
306 #if EFI_ANTILAG_SYSTEM
307 // , ALSsoftSparkLimiter(false)
308 #endif /* EFI_ANTILAG_SYSTEM */
309 
310 #endif // EFI_LAUNCH_CONTROL
311 {
312  reset();
313 }
SoftSparkLimiter softSparkLimiter
Definition: engine.h:193
EngineState engineState
Definition: engine.h:312
SwitchedState brakePedalSwitchedState
Definition: engine.h:187
SwitchedState clutchUpSwitchedState
Definition: engine.h:186
SwitchedState acButtonSwitchedState
Definition: engine.h:188
SoftSparkLimiter hardSparkLimiter
Definition: engine.h:195
void reset()
Definition: engine.cpp:319
acButtonState("AC switch", SensorCategory.SENSOR_INPUTS, FieldType.INT8, 1080, 1.0, -1.0, -1.0, "")
Here is the call graph for this function:

Member Function Documentation

◆ checkShutdown()

void Engine::checkShutdown ( )

Needed by EFI_MAIN_RELAY_CONTROL to shut down the engine correctly. This method cancels shutdown if the ignition voltage is detected.

Definition at line 489 of file engine.cpp.

489  {
490 #if EFI_MAIN_RELAY_CONTROL
491  // if we are already in the "ignition_on" mode, then do nothing
492 /* this logic is not alive
493  if (ignitionOnTimeNt > 0) {
494  return;
495  }
496 todo: move to shutdown_controller.cpp
497 */
498 
499  // here we are in the shutdown (the ignition is off) or initial mode (after the firmware fresh start)
500 /* this needs work or tests
501  const efitick_t engineStopWaitTimeoutUs = 500000LL; // 0.5 sec
502  // in shutdown mode, we need a small cooldown time between the ignition off and on
503 todo: move to shutdown_controller.cpp
504  if (stopEngineRequestTimeNt == 0 || (getTimeNowNt() - stopEngineRequestTimeNt) > US2NT(engineStopWaitTimeoutUs)) {
505  // if the ignition key is turned on again,
506  // we cancel the shutdown mode, but only if all shutdown procedures are complete
507  const float vBattThresholdOn = 8.0f;
508  // we fallback into zero instead of VBAT_FALLBACK_VALUE because it's not safe to false-trigger the "ignition on" event,
509  // and we want to turn on the main relay only when 100% sure.
510  if ((Sensor::getOrZero(SensorType::BatteryVoltage) > vBattThresholdOn) && !isInShutdownMode()) {
511  ignitionOnTimeNt = getTimeNowNt();
512  efiPrintf("Ignition voltage detected!");
513  if (stopEngineRequestTimeNt != 0) {
514  efiPrintf("Cancel the engine shutdown!");
515  stopEngineRequestTimeNt = 0;
516  }
517  }
518  }
519 */
520 #endif /* EFI_MAIN_RELAY_CONTROL */
521 }

Referenced by periodicSlowCallback().

Here is the caller graph for this function:

◆ efiWatchdog()

void Engine::efiWatchdog ( )

todo: better watch dog implementation should be implemented - see http://sourceforge.net/p/rusefi/tickets/96/

Definition at line 448 of file engine.cpp.

448  {
450  if (isRunningPwmTest)
451  return;
452 
453 #if EFI_ENGINE_CONTROL && EFI_SHAFT_POSITION_INPUT
454  if (module<PrimeController>()->isPriming() || triggerCentral.engineMovedRecently()) {
455  // do not invoke check in priming or if engine moved recently, no need to assert safe pin state.
456  return;
457  }
458 
460  if (!isRunningBenchTest() && enginePins.stopPins()) {
461  // todo: make this a firmwareError assuming functional tests would run
462  warning(ObdCode::CUSTOM_ERR_2ND_WATCHDOG, "Some pins were turned off by 2nd pass watchdog");
463  }
464  return;
465  }
466 
467  /**
468  * todo: better watch dog implementation should be implemented - see
469  * http://sourceforge.net/p/rusefi/tickets/96/
470  */
473 #endif // EFI_ENGINE_CONTROL && EFI_SHAFT_POSITION_INPUT
474 }
bool isRunningBenchTest()
Definition: bench_test.cpp:28
TriggerCentral triggerCentral
Definition: engine.h:286
void onEngineHasStopped()
Definition: engine.cpp:476
bool isRunningPwmTest
Definition: engine.h:302
bool stopPins()
Definition: efi_gpio.cpp:215
bool engineMovedRecently(efitick_t nowNt) const
bool isSpinningJustForWatchdog
EnginePins enginePins
Definition: efi_gpio.cpp:24
static void assertTimeIsLinear()
Definition: engine.cpp:431
bool warning(ObdCode code, const char *fmt,...)
@ CUSTOM_ERR_2ND_WATCHDOG

Referenced by periodicSlowCallback().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getBailedOnDwellCount()

int Engine::getBailedOnDwellCount ( ) const
inline

Definition at line 230 of file engine.h.

230 { return bailedOnDwellCount; }
int bailedOnDwellCount
Definition: engine.h:228

◆ getGlobalConfigurationVersion()

int Engine::getGlobalConfigurationVersion ( void  ) const

Definition at line 315 of file engine.cpp.

315  {
317 }
int globalConfigurationVersion
Definition: engine.h:281

Referenced by TriggerCentral::checkIfTriggerConfigChanged(), configureRusefiLuaHooks(), doPeriodicSlowCallback(), printConfiguration(), and updateTriggerWaveformIfNeeded().

Here is the caller graph for this function:

◆ incrementBailedOnDwellCount()

void Engine::incrementBailedOnDwellCount ( )
inline

Definition at line 231 of file engine.h.

231 { bailedOnDwellCount++; }

Referenced by turnSparkPinHighStartCharging().

Here is the caller graph for this function:

◆ injectEngineReferences()

void Engine::injectEngineReferences ( )
private

Definition at line 410 of file engine.cpp.

410  {
411 #if EFI_SHAFT_POSITION_INPUT
413  for (int camIndex = 0;camIndex < CAMS_PER_BANK;camIndex++) {
415  }
416 #endif // EFI_SHAFT_POSITION_INPUT
417 }
VvtTriggerConfiguration vvtTriggerConfiguration[CAMS_PER_BANK]
PrimaryTriggerConfiguration primaryTriggerConfiguration

Referenced by setConfig().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ isInShutdownMode()

bool Engine::isInShutdownMode ( ) const

Allows to finish some long-term shutdown procedures (stepper motor parking etc.) Called when the ignition switch is turned off (vBatt is too low). Returns true if some operations are in progress on background.

Definition at line 523 of file engine.cpp.

523  {
524  // TODO: this logic is currently broken
525 #if 0 && EFI_MAIN_RELAY_CONTROL && EFI_PROD_CODE
526  // if we are in "ignition_on" mode and not in shutdown mode
527  if (stopEngineRequestTimeNt == 0 && ignitionOnTimeNt > 0) {
528  const float vBattThresholdOff = 5.0f;
529  // start the shutdown process if the ignition voltage dropped low
530  if (Sensor::get(SensorType::BatteryVoltage).value_or(VBAT_FALLBACK_VALUE) <= vBattThresholdOff) {
532  }
533  }
534 
535  // we are not in the shutdown mode?
536  if (stopEngineRequestTimeNt == 0) {
537  return false;
538  }
539 
540  const efitick_t turnOffWaitTimeoutNt = NT_PER_SECOND;
541  // We don't want any transients to step in, so we wait at least 1 second whatever happens.
542  // Also it's good to give the stepper motor some time to start moving to the initial position (or parking)
543  if ((getTimeNowNt() - stopEngineRequestTimeNt) < turnOffWaitTimeoutNt)
544  return true;
545 
546  const efitick_t engineSpinningWaitTimeoutNt = 5 * NT_PER_SECOND;
547  // The engine is still spinning! Give it some time to stop (but wait no more than 5 secs)
548  if (isSpinning && (getTimeNowNt() - stopEngineRequestTimeNt) < engineSpinningWaitTimeoutNt)
549  return true;
550 
551  // The idle motor valve is still moving! Give it some time to park (but wait no more than 10 secs)
552  // Usually it can move to the initial 'cranking' position or zero 'parking' position.
553  const efitick_t idleMotorWaitTimeoutNt = 10 * NT_PER_SECOND;
554  if (isIdleMotorBusy() && (getTimeNowNt() - stopEngineRequestTimeNt) < idleMotorWaitTimeoutNt)
555  return true;
556 #endif /* EFI_MAIN_RELAY_CONTROL */
557  return false;
558 }
virtual SensorResult get() const =0
efitick_t getTimeNowNt()
Definition: efitime.cpp:19
bool isIdleMotorBusy()
void scheduleStopEngine()
Definition: settings.cpp:586
Here is the call graph for this function:

◆ isMainRelayEnabled()

bool Engine::isMainRelayEnabled ( ) const

The stepper does not work if the main relay is turned off (it requires +12V). Needed by the stepper motor code to detect if it works.

Definition at line 560 of file engine.cpp.

560  {
561 #if EFI_MAIN_RELAY_CONTROL
563 #else
564  // if no main relay control, we assume it's always turned on
565  return true;
566 #endif /* EFI_MAIN_RELAY_CONTROL */
567 }
RegisteredOutputPin mainRelay
Definition: efi_gpio.h:76
bool getLogicValue() const
Definition: efi_gpio.cpp:645

Referenced by StepperMotorBase::doIteration(), StepDirectionStepper::pulse(), and LimpManager::updateState().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ module()

template<typename get_t >
constexpr auto& Engine::module ( )
inlineconstexpr

Slightly shorter helper function to keep the code looking clean.

Definition at line 177 of file engine.h.

177  {
178  return engineModules.get<get_t>();
179  }
type_list< Mockable< InjectorModelPrimary >, Mockable< InjectorModelSecondary >,#if EFI_IDLE_CONTROL Mockable< IdleController >,#endif TriggerScheduler,#if EFI_HPFP &&EFI_ENGINE_CONTROL HpfpController,#endif #if EFI_ENGINE_CONTROL Mockable< ThrottleModel >,#endif #if EFI_ALTERNATOR_CONTROL AlternatorController,#endif FuelPumpController, MainRelayController, IgnitionController, Mockable< AcController >, FanControl1, FanControl2, PrimeController, DfcoController,#if EFI_HD_ACR HarleyAcr,#endif Mockable< WallFuelController >,#if EFI_VEHICLE_SPEED GearDetector, TripOdometer,#endif KnockController, SensorChecker,#if EFI_ENGINE_CONTROL LimpManager,#endif #if EFI_VVT_PID VvtController1, VvtController2, VvtController3, VvtController4,#endif #if EFI_BOOST_CONTROL BoostController,#endif EngineModule > engineModules
Definition: engine.h:171
constexpr auto get() -> std::enable_if_t< decltype(first)::template has< get_t >(), decltype(first.template get< get_t >())>
Definition: type_list.h:66

Referenced by WallFuel::adjust(), applyPidSettings(), auxPlainPinTurnOn(), canDashboardHaltech(), EtbController::checkStatus(), configureRusefiLuaHooks(), getAdvanceCorrections(), AlternatorController::getClosedLoop(), IdleController::getClosedLoop(), getIdlePosition(), getInjectionMass(), getLimpManager(), getOutputValueByName(), PrimeController::getPrimeDuration(), getRunningAdvance(), IdleController::getRunningOpenLoop(), IdleController::getTargetRpm(), AirmassVeModelBase::getVe(), handleGetDataRequest(), TriggerCentral::handleShaftSignal(), hipThread(), initAlternatorCtrl(), initBoostCtrl(), initVvtActuators(), LambdaMonitorBase::isCurrentlyGood(), lua_getDigital(), mainTriggerCallback(), FanController::onSlowCallback(), InjectionEvent::onTriggerTooth(), EngineState::periodicFastCallback(), populateFrame(), processLastKnockEvent(), resetLua(), HpfpController::scheduleNextCycle(), scheduleOpen(), scheduleSparkEvent(), setAltPFactor(), shouldUpdateCorrection(), startIdleThread(), updateFlags(), updateFuelResults(), LimpManager::updateState(), updateSwitchInputs(), and updateVehicleSpeed().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ onEngineHasStopped()

void Engine::onEngineHasStopped ( )

Definition at line 476 of file engine.cpp.

476  {
477 #if EFI_ENGINE_CONTROL
478  ignitionEvents.isReady = false;
479 #endif // EFI_ENGINE_CONTROL
480 
481 #if EFI_PROD_CODE || EFI_SIMULATOR
482  efiPrintf("Engine has stopped spinning.");
483 #endif
484 
485  // this invocation should be the last layer of defence in terms of making sure injectors/coils are not active
487 }
IgnitionEventList ignitionEvents
Definition: engine.h:259

Referenced by efiWatchdog().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ onSparkFireKnockSense()

void Engine::onSparkFireKnockSense ( uint8_t  cylinderIndex,
efitick_t  nowNt 
)

Definition at line 160 of file knock_controller.cpp.

160  {
161 #if EFI_HIP_9011 || EFI_SOFTWARE_KNOCK
162  cylinderNumberCopy = cylinderNumber;
163  scheduleByAngle(nullptr, nowNt,
164  /*angle*/engineConfiguration->knockDetectionWindowStart, { startKnockSampling, engine });
165 #else
166  UNUSED(cylinderNumber);
167  UNUSED(nowNt);
168 #endif
169 
170 #if EFI_HIP_9011
171  hip9011_onFireEvent(cylinderNumber, nowNt);
172 #endif
173 }
void hip9011_onFireEvent(uint8_t cylinderNumber, efitick_t nowNt)
Definition: hip9011.cpp:281
UNUSED(samplingTimeSeconds)
static uint8_t cylinderNumberCopy
engine_configuration_s * engineConfiguration
efitick_t scheduleByAngle(scheduling_s *timer, efitick_t nowNt, angle_t angle, action_s action)

Referenced by fireSparkAndPrepareNextSchedule().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ OnTriggerStateProperState()

void Engine::OnTriggerStateProperState ( efitick_t  nowNt)
overridevirtual

Implements TriggerStateListener.

Definition at line 363 of file engine.cpp.

363  {
365 }
RpmCalculator rpmCalculator
Definition: engine.h:273
void setSpinningUp(efitick_t nowNt)
Here is the call graph for this function:

◆ OnTriggerSynchronization()

void Engine::OnTriggerSynchronization ( bool  wasSynchronized,
bool  isDecodingError 
)
overridevirtual

Implements TriggerStateListener.

Definition at line 381 of file engine.cpp.

381  {
382  // TODO: this logic probably shouldn't be part of engine.cpp
383 
384  // We only care about trigger shape once we have synchronized trigger. Anything could happen
385  // during first revolution and it's fine
386  if (wasSynchronized) {
387  enginePins.triggerDecoderErrorPin.setValue(isDecodingError);
388 
389  // 'triggerStateListener is not null' means we are running a real engine and now just preparing trigger shape
390  // that's a bit of a hack, a sweet OOP solution would be a real callback or at least 'needDecodingErrorLogic' method?
391  if (isDecodingError) {
392 #if EFI_PROD_CODE
394  efiPrintf("error: synchronizationPoint @ index %lu expected %d/%d got %d/%d",
400  }
401 #endif /* EFI_PROD_CODE */
402  }
403 
404  engine->triggerCentral.triggerErrorDetection.add(isDecodingError);
405  }
406 
407 }
RegisteredOutputPin triggerDecoderErrorPin
Definition: efi_gpio.h:119
void setValue(const char *msg, int logicValue, bool isForce=false)
Definition: efi_gpio.cpp:581
PrimaryTriggerDecoder triggerState
TriggerWaveform triggerShape
cyclic_buffer< int > triggerErrorDetection
current_cycle_state_s currentCycle
bool someSortOfTriggerError() const
size_t getExpectedEventCount(TriggerWheel channelIndex) const
Engine * engine
size_t eventCount[PWM_PHASE_MAX_WAVE_PER_PWM]
Here is the call graph for this function:

◆ OnTriggerSynchronizationLost()

void Engine::OnTriggerSynchronizationLost ( )
overridevirtual

Implements TriggerStateListener.

Definition at line 367 of file engine.cpp.

367  {
368  // Needed for early instant-RPM detection
370 
373 
374  for (size_t i = 0; i < efi::size(triggerCentral.vvtState); i++) {
375  for (size_t j = 0; j < efi::size(triggerCentral.vvtState[0]); j++) {
377  }
378  }
379 }
void resetState() override
VvtTriggerDecoder vvtState[BANKS_COUNT][CAMS_PER_BANK]
InstantRpmCalculator instantRpm
virtual void resetState()
composite packet size
Here is the call graph for this function:

◆ periodicFastCallback()

void Engine::periodicFastCallback ( )

See FAST_CALLBACK_PERIOD_MS

The idea of this method is to execute all heavy calculations in a lower-priority thread, so that trigger event handler/IO scheduler tasks are faster.

Definition at line 577 of file engine.cpp.

577  {
579 
580 #if EFI_MAP_AVERAGING
582 #endif
583 
585 
586  tachUpdate();
587  speedoUpdate();
588 
589  engine->engineModules.apply_all([](auto & m) { m.onFastCallback(); });
590 }
void periodicFastCallback()
Definition: engine2.cpp:104
void refreshMapAveragingPreCalc()
@ EnginePeriodicFastCallback
void speedoUpdate()
Definition: speedometer.cpp:9
void apply_all(func_t const &f)
Definition: type_list.h:43
void tachUpdate()
Definition: tachometer.cpp:31

Referenced by RpmCalculator::assignRpmValue(), and mainTriggerCallback().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ periodicSlowCallback()

void Engine::periodicSlowCallback ( )

See SLOW_CALLBACK_PERIOD_MS

Definition at line 146 of file engine.cpp.

146  {
148 
149 #if EFI_SHAFT_POSITION_INPUT
150  // Re-read config in case it's changed
152  for (int camIndex = 0;camIndex < CAMS_PER_BANK;camIndex++) {
154  }
155 
157  enginePins.o2heater.setValue(getEngineState()->heaterControlEnabled);
159 #endif // EFI_SHAFT_POSITION_INPUT
160 
161  efiWatchdog();
163  checkShutdown();
164 
166 
168 
169  updateGppwm();
170 
171  engine->engineModules.apply_all([](auto & m) { m.onSlowCallback(); });
172 
173 #if (BOARD_TLE8888_COUNT > 0)
174  tle8888startup();
175 #endif
176 
177 #if EFI_DYNO_VIEW
178  updateDynoView();
179 #endif
180 
181  slowCallBackWasInvoked = true;
182 
183 #if EFI_PROD_CODE
184  void baroLps25Update();
185  baroLps25Update();
186 #endif // EFI_PROD_CODE
187 
188 #if ANALOG_HW_CHECK_MODE
189  criticalAssertVoid(isAdcChannelValid(engineConfiguration->clt.adcChannel), "No CLT setting");
190  efitimesec_t secondsNow = getTimeNowS();
191 
192 #if ! HW_CHECK_ALWAYS_STIMULATE
193  fail("HW_CHECK_ALWAYS_STIMULATE required to have self-stimulation")
194 #endif
195 
196  int hwCheckRpm = 204;
197  if (secondsNow > 2 && secondsNow < 180) {
198  assertCloseTo("RPM", Sensor::get(SensorType::Rpm).Value, hwCheckRpm);
199  } else if (!hasFirmwareError() && secondsNow > 180) {
200  static bool isHappyTest = false;
201  if (!isHappyTest) {
202  setTriggerEmulatorRPM(5 * hwCheckRpm);
203  efiPrintf("TEST PASSED");
204  isHappyTest = true;
205  }
206  }
207 
212 #endif // ANALOG_HW_CHECK_MODE
213 }
bool isAdcChannelValid(adc_channel_e hwChannel)
Definition: adc_inputs.h:20
void updateSlowSensors()
Definition: engine.cpp:219
void checkShutdown()
Definition: engine.cpp:489
bool slowCallBackWasInvoked
Definition: engine.h:271
void efiWatchdog()
Definition: engine.cpp:448
TpsAccelEnrichment tpsAccelEnrichment
Definition: engine.h:283
OutputPin o2heater
Definition: efi_gpio.h:97
RegisteredOutputPin starterRelayDisable
Definition: efi_gpio.h:84
bool isRunning() const
virtual float getRaw() const
Definition: sensor.h:157
static float getOrZero(SensorType type)
Definition: sensor.h:92
void onNewValue(float currentValue)
void updateDynoView()
Definition: dynoview.cpp:147
efitimesec_t getTimeNowS()
Current system time in seconds (32 bits)
Definition: efitime.cpp:42
static void assertCloseTo(const char *msg, float actual, float expected)
Definition: engine.cpp:139
EngineState * getEngineState()
Definition: engine.cpp:596
void updateGppwm()
Definition: gppwm.cpp:58
void baroLps25Update()
Definition: init_baro.cpp:19
@ EnginePeriodicSlowCallback
void tle8888startup()
Definition: smart_gpio.cpp:338
fail("EFI_SHAFT_POSITION_INPUT required to have EFI_EMULATE_POSITION_SENSORS") static_assert(sizeof(composite_logger_s)
void setTriggerEmulatorRPM(int rpm)
static void updateVrThresholdPwm(int rpm, size_t index)
Definition: vr_pwm.cpp:13

Referenced by doPeriodicSlowCallback().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ preCalculate()

void Engine::preCalculate ( )

Here we have a bunch of stuff which should invoked after configuration change so that we can prepare some helper structures

Definition at line 350 of file engine.cpp.

350  {
351 #if EFI_TUNER_STUDIO
352  // we take 2 bytes of crc32, no idea if it's right to call it crc16 or not
353  // we have a hack here - we rely on the fact that engineMake is the first of three relevant fields
355 
356  // we need and can empty warning message for CRC purposes
357  memset(config->warning_message, 0, sizeof(config->warning_message));
359 #endif /* EFI_TUNER_STUDIO */
360 }
TunerStudioOutputChannels outputChannels
Definition: engine.h:99
persistent_config_s * config

Referenced by incrementGlobalConfigurationVersion(), and readFromFlash().

Here is the caller graph for this function:

◆ reset()

void Engine::reset ( )
private

it's important for wrapAngle() that engineCycle field never has zero

Definition at line 319 of file engine.cpp.

319  {
320  /**
321  * it's important for wrapAngle() that engineCycle field never has zero
322  */
324  resetLua();
325 }
void resetLua()
Definition: engine.cpp:327
angle_t engineCycle
Definition: engine_state.h:27
@ FOUR_STROKE_CRANK_SENSOR
Definition: rusefi_enums.h:258
angle_t getEngineCycle(operation_mode_e operationMode)

Referenced by Engine().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ resetEngineSnifferIfInTestMode()

void Engine::resetEngineSnifferIfInTestMode ( )

Definition at line 56 of file engine.cpp.

56  {
57 #if EFI_ENGINE_SNIFFER
59  // TODO: what is the exact reasoning for the exact engine sniffer pause time I wonder
61  waveChart.reset();
62  }
63 #endif /* EFI_ENGINE_SNIFFER */
64 }
bool isFunctionalTestMode
Definition: engine.h:308
efitick_t pauseEngineSnifferUntilNt
WaveChart waveChart

Referenced by setEngineType(), setTriggerEmulatorRPM(), setTriggerType(), setValue(), and setWholeTimingMapCmd().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ resetLua()

void Engine::resetLua ( )

Definition at line 327 of file engine.cpp.

327  {
328  // todo: https://github.com/rusefi/rusefi/issues/4308
329  engineState.lua = {};
330  engineState.lua.fuelAdd = 0;
332  engineState.lua.luaDisableEtb = false;
333  engineState.lua.luaIgnCut = false;
334  engineState.lua.luaFuelCut = false;
336 #if EFI_BOOST_CONTROL
337  module<BoostController>().unmock().resetLua();
338 #endif // EFI_BOOST_CONTROL
341 #if EFI_IDLE_CONTROL
342  module<IdleController>().unmock().luaAdd = 0;
343 #endif // EFI_IDLE_CONTROL
344 }
IgnitionState ignitionState
Definition: engine.h:210

Referenced by reset().

Here is the caller graph for this function:

◆ setConfig()

void Engine::setConfig ( )

Definition at line 419 of file engine.cpp.

419  {
420 #if !EFI_UNIT_TEST
421 // huh should this be happy? static_assert(config != nullptr);
422 #endif
423  efi::clear(config);
424 
426 }
void injectEngineReferences()
Definition: engine.cpp:410

Referenced by runRusEfi().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ updateSlowSensors()

void Engine::updateSlowSensors ( )

We are executing these heavy (logarithm) methods from outside the trigger callbacks for performance reasons. See also periodicFastCallback

Definition at line 219 of file engine.cpp.

Referenced by periodicSlowCallback(), and testRusefiMethods().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ updateSwitchInputs()

void Engine::updateSwitchInputs ( )

Definition at line 262 of file engine.cpp.

262  {
263  // this value is not used yet
267 #if EFI_GPIO_HARDWARE
268  {
269  bool currentState;
270  if (hasAcToggle()) {
271  currentState = getAcToggle();
272 #ifdef EFI_KLINE
273  } else if (engineConfiguration->hondaK) {
274 extern bool kAcRequestState;
275  currentState = kAcRequestState;
276 #endif // EFI_KLINE
277  } else {
278  currentState = engine->engineState.lua.acRequestState;
279  }
280  AcController & acController = engine->module<AcController>().unmock();
281  if (engine->acButtonSwitchedState.update(currentState)) {
282  acController.acSwitchLastChangeTimeMs = US2MS(getTimeNowUs());
283  }
284  }
285 
286 #if EFI_IDLE_CONTROL
289  }
290 #endif // EFI_IDLE_CONTROL
291 
292  pokeAuxDigital();
293 
294 #endif // EFI_GPIO_HARDWARE
295 }
bool getAcToggle()
Definition: allsensors.cpp:19
bool hasAcToggle()
Definition: allsensors.cpp:23
constexpr auto & module()
Definition: engine.h:177
bool update(bool newState)
Definition: efi_output.cpp:10
efitimeus_t getTimeNowUs()
Definition: efitime.cpp:26
bool getBrakePedalState()
Definition: engine.cpp:251
static bool getClutchUpState()
Definition: engine.cpp:241
bool getClutchDownState()
Definition: engine.cpp:231
void pokeAuxDigital()
bool efiReadPin(brain_pin_e pin)
Definition: io_pins.cpp:89
bool kAcRequestState
Definition: kline.cpp:31
bool isBrainPinValid(brain_pin_e brainPin)

Referenced by updateSlowSensors().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ updateTriggerWaveform()

void Engine::updateTriggerWaveform ( )

Definition at line 122 of file engine.cpp.

122  {
123 
124 
125 #if EFI_ENGINE_CONTROL && EFI_SHAFT_POSITION_INPUT
126  // we have a confusing threading model so some synchronization would not hurt
127  chibios_rt::CriticalSectionLocker csl;
128 
130 
131 
134  }
135 #endif /* EFI_ENGINE_CONTROL && EFI_SHAFT_POSITION_INPUT */
136 }
void prepareOutputSignals()

Referenced by applyNonPersistentConfiguration(), and onConfigurationChangeTriggerCallback().

Here is the call graph for this function:
Here is the caller graph for this function:

Field Documentation

◆ acButtonSwitchedState

SwitchedState Engine::acButtonSwitchedState

Definition at line 188 of file engine.h.

Referenced by sendQcBenchButtonCounters(), and updateSwitchInputs().

◆ allowCanTx

bool Engine::allowCanTx = true

Sometimes for instance during shutdown we need to completely supress CAN TX

Definition at line 104 of file engine.h.

Referenced by configureRusefiLuaHooks(), and CanTxMessage::~CanTxMessage().

◆ antilagController

AntilagSystemBase Engine::antilagController

◆ auxValves

AuxActor Engine::auxValves[AUX_DIGITAL_VALVE_COUNT][2]

Definition at line 223 of file engine.h.

Referenced by initAuxValves().

◆ bailedOnDwellCount

int Engine::bailedOnDwellCount = 0
private

Definition at line 228 of file engine.h.

Referenced by getBailedOnDwellCount(), and incrementBailedOnDwellCount().

◆ blipIdlePosition

percent_t Engine::blipIdlePosition

idle blip is a development tool: alternator PID research for instance have benefited from a repetitive change of RPM

Definition at line 320 of file engine.h.

Referenced by blipIdle(), and IdleController::getIdlePosition().

◆ brakePedalSwitchedState

SwitchedState Engine::brakePedalSwitchedState

◆ clutchUpSwitchedState

SwitchedState Engine::clutchUpSwitchedState

Definition at line 186 of file engine.h.

Referenced by sendQcBenchButtonCounters(), and updateSwitchInputs().

◆ configBurnTimer

Timer Engine::configBurnTimer

Definition at line 275 of file engine.h.

Referenced by assertTimeIsLinear(), and writeToFlashNow().

◆ dc_motors

dc_motors_s Engine::dc_motors

Definition at line 314 of file engine.h.

Referenced by getOutputValueByName(), and updateTunerStudioState().

◆ enableOverdwellProtection

bool Engine::enableOverdwellProtection = true

Definition at line 97 of file engine.h.

◆ engineModules

type_list< Mockable<InjectorModelPrimary>, Mockable<InjectorModelSecondary>,#if EFI_IDLE_CONTROL Mockable<IdleController>,#endif TriggerScheduler,#if EFI_HPFP && EFI_ENGINE_CONTROL HpfpController,#endif #if EFI_ENGINE_CONTROL Mockable<ThrottleModel>,#endif #if EFI_ALTERNATOR_CONTROL AlternatorController,#endif FuelPumpController, MainRelayController, IgnitionController, Mockable<AcController>, FanControl1, FanControl2, PrimeController, DfcoController,#if EFI_HD_ACR HarleyAcr,#endif Mockable<WallFuelController>,#if EFI_VEHICLE_SPEED GearDetector, TripOdometer,#endif KnockController, SensorChecker,#if EFI_ENGINE_CONTROL LimpManager,#endif #if EFI_VVT_PID VvtController1, VvtController2, VvtController3, VvtController4,#endif #if EFI_BOOST_CONTROL BoostController,#endif EngineModule > Engine::engineModules

◆ engineState

EngineState Engine::engineState

Definition at line 312 of file engine.h.

Referenced by auxPlainPinTurnOn(), HpfpQuantity::calcFuelPercent(), canDashboardHaltech(), EtbController::checkStatus(), configureRusefiLuaHooks(), AemXSeriesWideband::decodeRusefiDiag(), detectHellenBoardType(), fireSparkAndPrepareNextSchedule(), firmwareError(), getAcrState(), getAdvanceCorrections(), SpeedDensityAirmass::getAirmass(), AngleBasedEvent::getAngleFromNow(), getBaseFuelMass(), getBoardId(), getBrakePedalState(), getClutchDownState(), getClutchUpState(), getCrankingFuel3(), getEngineState(), getInjectionMass(), getInjectorDutyCycle(), getInjectorDutyCycleStage2(), getMultiSparkCount(), getOutputValueByName(), getPerCylinderFiringOrderOffset(), getRunningAdvance(), getRunningFuel(), DfcoController::getState(), AirmassVeModelBase::getVe(), handleGetDataRequest(), handleTestCommand(), initDataStructures(), initializeIgnitionActions(), is_F_OrOlder(), isMegaModuleRevision(), lua_getDigital(), mapAveragingTriggerCallback(), obdOnCanPacketRx(), KnockControllerBase::onKnockSenseCompleted(), HarleyAcr::onSlowCallback(), onStartStopButtonToggle(), onTriggerEventSparkLogic(), overFireSparkAndPrepareNextSchedule(), periodicFastCallback(), EngineState::periodicFastCallback(), populateFrame(), printConfiguration(), recalculateAuxValveTiming(), refreshMapAveragingPreCalc(), reset(), resetLua(), runOneLua(), sayHello(), scheduleOpen(), scheduleSparkEvent(), sendWidebandInfo(), setBoardConfigOverrides(), Generic4TransmissionController::setPcState(), slowStartStopButtonCallback(), startAveraging(), startDwellByTurningSparkPinHigh(), testRusefiMethods(), THD_FUNCTION(), turnSparkPinHighStartCharging(), updateFuelCorrections(), updateFuelInfo(), updateSlowSensors(), LimpManager::updateState(), updateSwitchInputs(), updateTunerStudioState(), updateWarningCodes(), and warning().

◆ etbAutoTune

bool Engine::etbAutoTune = false

◆ etbControllers

IEtbController* Engine::etbControllers[ETB_COUNT] = {nullptr}

◆ executor [1/3]

SingleTimerExecutor Engine::executor

◆ executor [2/3]

SleepExecutor Engine::executor

Definition at line 245 of file engine.h.

◆ executor [3/3]

TestExecutor Engine::executor

Definition at line 248 of file engine.h.

◆ fuelComputer

FuelComputer Engine::fuelComputer

◆ gearController

GearControllerBase* Engine::gearController

Definition at line 182 of file engine.h.

Referenced by doPeriodicSlowCallback(), and initGearController().

◆ globalConfigurationVersion

int Engine::globalConfigurationVersion = 0

This counter is incremented every time user adjusts ECU parameters online (either via rusEfi console or other tuning software)

Definition at line 281 of file engine.h.

Referenced by getGlobalConfigurationVersion(), and incrementGlobalConfigurationVersion().

◆ hardSparkLimiter

SoftSparkLimiter Engine::hardSparkLimiter

Definition at line 195 of file engine.h.

Referenced by onTriggerEventSparkLogic(), and EngineState::updateSparkSkip().

◆ ignitionEvents

IgnitionEventList Engine::ignitionEvents

◆ ignitionState

IgnitionState Engine::ignitionState

◆ injectionEvents

FuelSchedule Engine::injectionEvents

◆ isFunctionalTestMode

bool Engine::isFunctionalTestMode = false

are we running any kind of functional test? this affect some areas

Definition at line 308 of file engine.h.

Referenced by enableOrDisable(), and resetEngineSnifferIfInTestMode().

◆ isPwmEnabled

bool Engine::isPwmEnabled = true

Definition at line 107 of file engine.h.

Referenced by applyPinState(), and enableOrDisable().

◆ isRunningPwmTest

bool Engine::isRunningPwmTest = false

Definition at line 302 of file engine.h.

Referenced by efiWatchdog().

◆ lambdaMonitor

LambdaMonitor Engine::lambdaMonitor

◆ launchController

LaunchControlBase Engine::launchController

◆ luaDigitalInputState

SimpleSwitchedState Engine::luaDigitalInputState[LUA_DIGITAL_INPUT_COUNT]

Definition at line 189 of file engine.h.

Referenced by pokeAuxDigital(), and sendQcBenchAuxDigitalCounters().

◆ mockAirmassModel

AirmassModelBase* Engine::mockAirmassModel = nullptr

Definition at line 353 of file engine.h.

Referenced by getAirmassModel().

◆ needTdcCallback

bool Engine::needTdcCallback = true

Definition at line 226 of file engine.h.

Referenced by onTdcCallback().

◆ onIgnitionEvent

std::function<void(IgnitionEvent*, bool)> Engine::onIgnitionEvent

Definition at line 250 of file engine.h.

Referenced by fireSparkAndPrepareNextSchedule(), and turnSparkPinHighStartCharging().

◆ onScheduleOverFireSparkAndPrepareNextSchedule

std::function<void(const IgnitionEvent&, efitick_t)> Engine::onScheduleOverFireSparkAndPrepareNextSchedule = [](const IgnitionEvent&, efitick_t) -> void {}

Definition at line 253 of file engine.h.

◆ onScheduleTurnSparkPinHighStartCharging

std::function<void(const IgnitionEvent&, efitick_t, angle_t, efitick_t)> Engine::onScheduleTurnSparkPinHighStartCharging = [](const IgnitionEvent&, efitick_t, angle_t, efitick_t) -> void {}

Definition at line 251 of file engine.h.

Referenced by scheduleSparkEvent().

◆ outputChannels

TunerStudioOutputChannels Engine::outputChannels

Definition at line 99 of file engine.h.

Referenced by attachMsdSdCard(), canInfo(), EtbController::checkStatus(), TunerStudio::cmdOutputChannels(), completionCallback(), TriggerCentral::decodeMapCam(), executorStatistics(), fastAdcErrorCB(), fireSparkAndPrepareNextSchedule(), fuelClosedLoopCorrection(), getAdvanceCorrections(), VvtController::getClosedLoop(), BoostController::getClosedLoop(), AlternatorController::getClosedLoop(), EtbController::getClosedLoopAutotune(), IdleController::getIdlePosition(), getLiveData(), SpeedDensityAirmass::getMap(), BoostController::getOpenLoop(), getOutputValueByName(), getRunningAdvance(), BoostController::getSetpoint(), VvtController::getSetpoint(), EtbController::getSetpointEtb(), EtbController::getSetpointIdleValve(), TpsAccelEnrichment::getTpsEnrichment(), getTunerStudioOutputChannels(), AirmassVeModelBase::getVe(), grabPedalIsUp(), grabPedalIsWideOpen(), handleCommandX14(), handleFuel(), handleShaftSignal(), handleVvtCamSignal(), initElectronicThrottle(), lua_setDebug(), mapAveragingAdcCallback(), mountMmc(), myAlloc(), PrimeController::onPrimeStart(), onTriggerEventSparkLogic(), InjectionEvent::onTriggerTooth(), populateFrame(), postCanState(), StepperMotorBase::postCurrentPosition(), GearControllerBase::postState(), preCalculate(), prepareCylinderIgnitionSchedule(), printErrorCounters(), printUid(), processLastKnockEvent(), readGppwmChannel(), reportLogicAnalyzerToTS(), runBench(), runOneLua(), IgnitionOutputPin::setHigh(), IgnitionOutputPin::setLow(), EtbController::setOutput(), setToothLogReady(), slowAdcErrorCB(), AdcDevice::startConversionI(), startLua(), THD_FUNCTION(), tle8888PostState(), triggerScopeDisable(), triggerScopeGetBuffer(), InjectionEvent::update(), SimpleTransmissionController::update(), DynoView::update(), updateEgtSensors(), updateFlags(), updateFuelCorrections(), updateFuelInfo(), updateFuelResults(), updateFuelSensors(), updateGppwm(), updateIgnition(), updateLambda(), updateMiscSensors(), updatePressures(), updateRawSensors(), updateSdCardLiveFlags(), updateTempSensors(), updateThrottles(), updateTunerStudioState(), updateVehicleSpeed(), updateVvtSensors(), updateWarningCodes(), and CanTxMessage::~CanTxMessage().

◆ pauseCANdueToSerial

bool Engine::pauseCANdueToSerial = false

ELM327 cannot handle both RX and TX at the same time, we have to stay quite once first ISO/TP packet was detected this is a pretty temporary hack only while we are trying ELM327, long term ISO/TP and rusEFI broadcast should find a way to coexists

Definition at line 114 of file engine.h.

Referenced by CanWrite::PeriodicTask(), and CanStreamerState::receiveFrame().

◆ pinRepository

PinRepository Engine::pinRepository

Definition at line 116 of file engine.h.

Referenced by brain_pin_markUsed(), getBrainUsedPin(), and setPin().

◆ prevOutputName

const char* Engine::prevOutputName = nullptr

Definition at line 109 of file engine.h.

◆ rpmCalculator

RpmCalculator Engine::rpmCalculator

◆ sensors

SensorsState Engine::sensors

◆ sent_state

sent_state_s Engine::sent_state

Definition at line 315 of file engine.h.

Referenced by SentDecoderThread().

◆ slowCallBackWasInvoked

bool Engine::slowCallBackWasInvoked = false

Definition at line 271 of file engine.h.

Referenced by EngineState::periodicFastCallback(), and periodicSlowCallback().

◆ softSparkLimiter

SoftSparkLimiter Engine::softSparkLimiter

Definition at line 193 of file engine.h.

Referenced by onTriggerEventSparkLogic(), and EngineState::updateSparkSkip().

◆ startStopState

StartStopState Engine::startStopState

◆ tdcMarkEnabled

bool Engine::tdcMarkEnabled = true

Definition at line 267 of file engine.h.

Referenced by tdcMarkCallback().

◆ tdcScheduler

scheduling_s Engine::tdcScheduler[2]

Definition at line 260 of file engine.h.

Referenced by tdcMarkCallback().

◆ timeToStopBlip

efitimeus_t Engine::timeToStopBlip = 0

Definition at line 321 of file engine.h.

Referenced by blipIdle(), IdleController::getIdlePosition(), and undoIdleBlipIfNeeded().

◆ timeToStopIdleTest

efitimeus_t Engine::timeToStopIdleTest = 0

Definition at line 322 of file engine.h.

Referenced by applyIACposition(), finishIdleTestIfNeeded(), and startIdleBench().

◆ tpsAccelEnrichment

TpsAccelEnrichment Engine::tpsAccelEnrichment

◆ triggerCentral

TriggerCentral Engine::triggerCentral

◆ versionForConfigurationListeners

LocalVersionHolder Engine::versionForConfigurationListeners

Definition at line 221 of file engine.h.

Referenced by doPeriodicSlowCallback().


The documentation for this class was generated from the following files: