manual sync

This commit is contained in:
Andrey B 2014-04-30 11:03:21 -05:00
parent 7050527756
commit 785ffea80f
43 changed files with 15 additions and 3330 deletions

View File

@ -269,7 +269,7 @@ const char *dbg_panic_msg;
* @param[in] msg the pointer to the panic message string
*/
void chDbgPanic3(const char *msg, char * file, int line);
void chDbgPanic3(const char *msg, const char * file, int line);
void chDbgPanic(const char *msg) {
chDbgPanic3(msg, __FILE__, __LINE__);

View File

@ -1,31 +0,0 @@
/**
* @file GY6_139QMB.c
* @brief 139qmb default engine configuration
*
* @date Feb 13, 2014
* @author rus084
* @author Andrey Belomutskiy, (c) 2012-2014
*/
#include "GY6_139QMB.h"
void setGy6139qmbDefaultEngineConfiguration(engine_configuration_s *engineConfiguration) {
engineConfiguration->rpmHardLimit = 9000;
engineConfiguration->crankingSettings.crankingRpm = 800;
engineConfiguration->analogInputDividerCoefficient = 1.52;
engineConfiguration->engineLoadMode = LM_MAP;
engineConfiguration->globalTriggerAngleOffset = 15;
engineConfiguration->analogChartMode = AC_MAP;
engineConfiguration->cylindersCount = 1;
engineConfiguration->rpmMultiplier = 1;
engineConfiguration->firingOrder = FO_ONE_CYLINDER;
/**
* We treat the trigger as 1/0 toothed wheel
*/
engineConfiguration->triggerConfig.totalToothCount = 1;
engineConfiguration->triggerConfig.skippedToothCount = 0;
engineConfiguration->triggerConfig.isSynchronizationNeeded = FALSE;
engineConfiguration->needSecondTriggerInput = FALSE;
}

View File

@ -1,52 +0,0 @@
/**
* @file audi_aan.c
* @brief Audo AAN default engine configuration
*
* @date Nov 24, 2013
* @author Andrey Belomutskiy, (c) 2012-2014
*
* This file is part of rusEfi - see http://rusefi.com
*
* rusEfi is free software; you can redistribute it and/or modify it under the terms of
* the GNU General Public License as published by the Free Software Foundation; either
* version 3 of the License, or (at your option) any later version.
*
* rusEfi is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without
* even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along with this program.
* If not, see <http://www.gnu.org/licenses/>.
*
*/
#include "main.h"
#if EFI_ENGINE_AUDI_AAN || defined(__DOXYGEN__)
#include "engine_controller.h"
extern engine_configuration2_s engineConfiguration2;
void configureShaftPositionEmulatorShape(PwmConfig *state) {
/**
* One signal per cam shaft revolution
*/
int pinStates0[] = { 1, 0 };
float switchTimes[] = { 0.8, 1 };
int *pinStates[2] = { pinStates0 };
weComplexInit("distributor", state, 0, 2, switchTimes, 1, pinStates);
}
void configureEngineEventHandler(EventHandlerConfiguration *config) {
registerActuatorEvent(&config->ignitionEvents, 0, 1, 0);
registerActuatorEvent(&config->ignitionEvents, 0, 2, 90);
}
void setDefaultEngineConfiguration(EngineConfiguration *engineConfiguration) {
engineConfiguration2.shaftPositionEventCount = 2;
}
#endif /* EFI_ENGINE_AUDI_AAN */

View File

@ -1,112 +0,0 @@
/**
* @file dodge_neon.c
*
* DODGE_NEON_1995 = 2
*
* @date Dec 16, 2013
* @author Andrey Belomutskiy, (c) 2012-2014
*/
#include "main.h"
#if EFI_SUPPORT_DODGE_NEON || defined(__DOXYGEN__)
#include "dodge_neon.h"
#include "engine_configuration.h"
#include "thermistors.h"
#include "engine_math.h"
void setDodgeNeonEngineConfiguration(engine_configuration_s *engineConfiguration,
board_configuration_s *boardConfiguration) {
engineConfiguration->triggerConfig.triggerType = TT_DODGE_NEON;
engineConfiguration->engineLoadMode = LM_TPS;
// set_rpm_hard_limit 4000
engineConfiguration->rpmHardLimit = 4000; // yes, 4k. let's play it safe for now
// set_cranking_rpm 550
engineConfiguration->crankingSettings.crankingRpm = 550;
// since CLT is not wired up yet let's just use same value for min and max
// set_cranking_fuel_max 6 40
engineConfiguration->crankingSettings.coolantTempMaxC = 37.7; // 6ms at 37.7C
engineConfiguration->crankingSettings.fuelAtMaxTempMs = 6;
// set_cranking_fuel_min 6 -40
engineConfiguration->crankingSettings.coolantTempMinC = -40; // 6ms at -40C
engineConfiguration->crankingSettings.fuelAtMinTempMs = 6;
// set_whole_fuel_map 3
setWholeFuelMap(engineConfiguration, 3);
engineConfiguration->triggerConfig.syncRatioFrom = 0.72 * 0.8;
engineConfiguration->triggerConfig.syncRatioTo = 0.72 * 1.3;
engineConfiguration->triggerConfig.isSynchronizationNeeded = TRUE;
engineConfiguration->triggerConfig.useRiseEdge = FALSE;
engineConfiguration->needSecondTriggerInput = TRUE;
// set_cranking_injection_mode 0
engineConfiguration->crankingInjectionMode = IM_SIMULTANEOUS;
// set_injection_mode 1
engineConfiguration->injectionMode = IM_SEQUENTIAL;
// set_ignition_mode 2
engineConfiguration->ignitionMode = IM_WASTED_SPARK;
// set_firing_order 2
engineConfiguration->firingOrder = FO_1_THEN_3_THEN_4_THEN2;
// set_global_trigger_offset_angle 497
engineConfiguration->globalTriggerAngleOffset = 497;
// set_ignition_offset 350
engineConfiguration->ignitionOffset = 350;
// set_injection_offset 510
engineConfiguration->injectionOffset = 510;
// set_cranking_charge_angle 70
engineConfiguration->crankingChargeAngle = 7;
// set_cranking_timing_angle 0
engineConfiguration->crankingTimingAngle = 0;
// Frankenstein: low side - inj #1: PC14
// Frankenstein: low side - inj #2: PC15
// Frankenstein: low side - inj #3: PE6
// Frankenstein: low side - inj #4: PC13
// Frankenstein: low side - inj #5: PE4
// Frankenstein: low side - inj #6: PE5
// Frankenstein: low side - inj #7: PE2
// Frankenstein: low side - inj #8: PE3
// Frankenstein: low side - inj #9: PE0
// Frankenstein: low side - inj #10: PE1
// Frankenstein: low side - inj #11: PB8
// Frankenstein: low side - inj #12: PB9
boardConfiguration->injectionPins[0] = GPIOB_9; // Frankenstein: low side - inj #12
boardConfiguration->injectionPins[1] = GPIOB_8; // Frankenstein: low side - inj #11
boardConfiguration->injectionPins[2] = GPIOE_3; // Frankenstein: low side - inj #8
boardConfiguration->injectionPins[3] = GPIOE_5; // Frankenstein: low side - inj #6
boardConfiguration->fuelPumpPin = GPIOC_13; // Frankenstein: low side - inj #4
boardConfiguration->fuelPumpPinMode = OM_DEFAULT;
// set_injection_pin_mode 0
boardConfiguration->injectionPinMode = OM_DEFAULT;
// Frankenstein: high side #1: PE8
// Frankenstein: high side #2: PE10
boardConfiguration->ignitionPins[0] = GPIOE_8; // Frankenstein: high side #1
boardConfiguration->ignitionPins[1] = GPIO_NONE;
boardConfiguration->ignitionPins[2] = GPIOE_10; // // Frankenstein: high side #2
// set_ignition_pin_mode 0
boardConfiguration->ignitionPinMode = OM_DEFAULT;
setThermistorConfiguration(&engineConfiguration->cltThermistorConf, 0, 32500, 30, 7550, 100, 700);
engineConfiguration->cltThermistorConf.bias_resistor = 2700;
engineConfiguration->analogChartFrequency = 7;
}
#endif /* EFI_SUPPORT_DODGE_NEON */

View File

@ -1,100 +0,0 @@
/**
* @file ford_1995_inline_6.c
* @brief Default engine configuration for a 1995 Ford inline 6 engine
*
* http://rusefi.com/forum/viewtopic.php?f=3&t=469
*
* FORD_INLINE_6_1995 = 7
*
* @date Feb 12, 2014
* @author Andrey Belomutskiy, (c) 2012-2014
*/
#include "main.h"
#include "ford_1995_inline_6.h"
#include "engine_math.h"
#include "allsensors.h"
#if EFI_SUPPORT_1995_FORD_INLINE_6 || defined(__DOXYGEN__)
/**
* @brief Default values for persistent properties
*/
void setFordInline6(engine_configuration_s *engineConfiguration, board_configuration_s *boardConfiguration) {
engineConfiguration->cylindersCount = 6;
/**
* 0.5 means primary position sensor is on a camshaft
*/
engineConfiguration->rpmMultiplier = 0.5;
engineConfiguration->ignitionMode = IM_ONE_COIL;
engineConfiguration->firingOrder = FO_1_THEN_5_THEN_3_THEN_6_THEN_2_THEN_4;
engineConfiguration->crankingInjectionMode = IM_SIMULTANEOUS;
engineConfiguration->injectionMode = IM_BATCH;
/**
* 0.5ms dweel time just to be sure it would fit within camshaft revolution, dwell is not controlled by us anyway
*/
setConstantDwell(engineConfiguration, 0.5);
/**
* We treat the trigger as 6/0 toothed wheel
*/
engineConfiguration->triggerConfig.totalToothCount = 6;
engineConfiguration->triggerConfig.skippedToothCount = 0;
engineConfiguration->triggerConfig.isSynchronizationNeeded = FALSE;
engineConfiguration->triggerConfig.useRiseEdge = TRUE;
engineConfiguration->needSecondTriggerInput = FALSE;
engineConfiguration->globalTriggerAngleOffset = 0;
engineConfiguration->ignitionOffset = 13;
setThermistorConfiguration(&engineConfiguration->cltThermistorConf, -10, 160310, 60, 7700, 120.00, 1180);
engineConfiguration->cltThermistorConf.bias_resistor = 2700;
setThermistorConfiguration(&engineConfiguration->iatThermistorConf, -10, 160310, 60, 7700, 120.00, 1180);
engineConfiguration->iatThermistorConf.bias_resistor = 2700;
// 12ch analog board pinout:
// input channel 3 is PA7, that's ADC7
// input channel 5 is PA4, that's ADC4
// input channel 6 is PA3, that's ADC3
// input channel 7 is PA2, that's ADC2
// input channel 8 is PA1, that's ADC1
// input channel 9 is PA0, that's ADC0
// input channel 10 is PC3, that's ADC13
// input channel 12 is PC1, that's ADC11
engineConfiguration->tpsAdcChannel = 4;
engineConfiguration->iatAdcChannel = 2;
engineConfiguration->cltAdcChannel = 1;
engineConfiguration->afrSensor.afrAdcChannel = 11;
// 6 channel output board
// output 1 is PB9
// output 3 is PE3
// output 5 is PC13
// output 6 is PC15
boardConfiguration->fuelPumpPin = GPIOC_13;
boardConfiguration->injectionPins[0] = GPIOB_9;
boardConfiguration->injectionPins[1] = GPIOE_3;
boardConfiguration->ignitionPins[0] = GPIOC_15;
boardConfiguration->injectionPins[2] = GPIO_NONE;
boardConfiguration->fanPin = GPIO_NONE;
engineConfiguration->tpsMin = convertVoltageTo10bitADC(1.250);
engineConfiguration->tpsMax = convertVoltageTo10bitADC(4.538);
engineConfiguration->map.config.mapType = MT_MPX4250;
engineConfiguration->map.channel = 2; // input channel 8 is ADC2
// engineConfiguration->vBattAdcChannel = 0; //
// engineConfiguration->mafAdcChannel = 1;
}
#endif /* EFI_SUPPORT_1995_FORD_INLINE_6 */

View File

@ -1,31 +0,0 @@
/**
* @file ford_fiesta.c
* @brief European 1990 Ford Fiesta
*
* FORD_FIESTA = 4
*
* @date Nov 22, 2013
* @author Andrey Belomutskiy, (c) 2012-2014
*/
#include "main.h"
#if EFI_SUPPORT_FORD_FIESTA || defined(__DOXYGEN__)
#include "ford_fiesta.h"
#include "engine_configuration.h"
#include "engine_math.h"
void setFordFiestaDefaultEngineConfiguration(engine_configuration_s *engineConfiguration) {
engineConfiguration->rpmHardLimit = 7000;
// only crankshaft sensor so far
engineConfiguration->rpmMultiplier = 1;
engineConfiguration->triggerConfig.totalToothCount = 36;
engineConfiguration->triggerConfig.skippedToothCount = 1;
engineConfiguration->ignitionMode = IM_WASTED_SPARK;
engineConfiguration->firingOrder = FO_1_THEN_3_THEN_4_THEN2;
}
#endif /* EFI_SUPPORT_FORD_FIESTA */

View File

@ -1,16 +0,0 @@
/**
* @file honda_accord.c
*
* @date Jan 12, 2014
* @author Andrey Belomutskiy, (c) 2012-2014
*/
#include "main.h"
#include "engine_configuration.h"
#include "trigger_decoder.h"
void setHondaAccordConfiguration(engine_configuration_s *engineConfiguration) {
engineConfiguration->triggerConfig.totalToothCount = 24;
engineConfiguration->triggerConfig.skippedToothCount = 2;
}

View File

@ -1,22 +0,0 @@
/**
* @file mazda_323.c
*
* @date Mar 8, 2014
* @author Andrey Belomutskiy, (c) 2012-2013
*/
#include "mazda_323.h"
void setMazda323EngineConfiguration(engine_configuration_s *engineConfiguration) {
engineConfiguration->cylindersCount = 6;
engineConfiguration->ignitionMode = IM_ONE_COIL;
/**
* We treat the trigger as 4/0 toothed wheel
*/
engineConfiguration->triggerConfig.totalToothCount = 4;
engineConfiguration->triggerConfig.skippedToothCount = 0;
engineConfiguration->triggerConfig.isSynchronizationNeeded = FALSE;
}

View File

@ -1,83 +0,0 @@
/**
* @file mazda_miata_nb.c
*
* MAZDA_MIATA_NB = 9
*
* @date Feb 18, 2014
* @author Andrey Belomutskiy, (c) 2012-2014
*/
#include "mazda_miata_nb.h"
#include "thermistors.h"
void setMazdaMiataNbEngineConfiguration(engine_configuration_s *engineConfiguration,
board_configuration_s *boardConfiguration) {
// set_rpm_hard_limit 3000
engineConfiguration->rpmHardLimit = 3000; // yes, 3k. let's play it safe for now
engineConfiguration->triggerConfig.triggerType = TT_MAZDA_MIATA_NB;
engineConfiguration->triggerConfig.isSynchronizationNeeded = TRUE;
engineConfiguration->triggerConfig.syncRatioFrom = 0.11 * 0.7;
engineConfiguration->triggerConfig.syncRatioTo = 0.11 * 1.3;
engineConfiguration->triggerConfig.useRiseEdge = FALSE;
engineConfiguration->globalTriggerAngleOffset = 276;
// set_cranking_injection_mode 0
engineConfiguration->crankingInjectionMode = IM_SIMULTANEOUS;
// set_injection_mode 1
engineConfiguration->injectionMode = IM_SEQUENTIAL;
// set_ignition_mode 2
engineConfiguration->ignitionMode = IM_WASTED_SPARK;
// set_firing_order 2
engineConfiguration->firingOrder = FO_1_THEN_3_THEN_4_THEN2;
setThermistorConfiguration(&engineConfiguration->cltThermistorConf, 0, 32500, 30, 7550, 100, 700);
engineConfiguration->cltThermistorConf.bias_resistor = 2700;
setThermistorConfiguration(&engineConfiguration->iatThermistorConf, -10, 160310, 60, 7700, 120.00, 1180);
engineConfiguration->iatThermistorConf.bias_resistor = 2700;
engineConfiguration->tpsAdcChannel = 3; // 15 is the old value
engineConfiguration->vBattAdcChannel = 0; // 1 is the old value
// engineConfiguration->map.channel = 1;
engineConfiguration->mafAdcChannel = 1;
engineConfiguration->cltAdcChannel = 11;
engineConfiguration->iatAdcChannel = 13;
engineConfiguration->afrSensor.afrAdcChannel = 2;
boardConfiguration->idleValvePin = GPIOE_0;
boardConfiguration->idleValvePinMode = OM_DEFAULT;
boardConfiguration->fuelPumpPin = GPIOC_14; // Frankenstein: low side - inj #4
boardConfiguration->fuelPumpPinMode = OM_DEFAULT;
boardConfiguration->injectionPins[0] = GPIOB_9; // Frankenstein: low side - inj #12
boardConfiguration->injectionPins[1] = GPIOB_8; // Frankenstein: low side - inj #11
boardConfiguration->injectionPins[2] = GPIOE_3; // Frankenstein: low side - inj #8
boardConfiguration->injectionPins[3] = GPIOE_5; // Frankenstein: low side - inj #6
boardConfiguration->injectionPins[4] = GPIO_NONE;
boardConfiguration->injectionPins[5] = GPIO_NONE;
boardConfiguration->injectionPinMode = OM_DEFAULT;
boardConfiguration->ignitionPins[0] = GPIOE_10; // Frankenstein: high side #1
boardConfiguration->ignitionPins[1] = GPIO_NONE;
boardConfiguration->ignitionPins[2] = GPIOC_9; // // Frankenstein: high side #2
boardConfiguration->ignitionPins[3] = GPIO_NONE;
boardConfiguration->ignitionPinMode = OM_INVERTED;
boardConfiguration->malfunctionIndicatorPin = GPIOE_1;
boardConfiguration->malfunctionIndicatorPinMode = OM_DEFAULT;
boardConfiguration->fanPin = GPIOE_6;
boardConfiguration->fanPinMode = OM_DEFAULT;
boardConfiguration->electronicThrottlePin1 = GPIO_NONE;
boardConfiguration->idleSwitchPin = GPIO_NONE;
// set_whole_fuel_map 3
setWholeFuelMap(engineConfiguration, 3);
// 10 deg before TDC is default timing
}

View File

@ -1,18 +0,0 @@
/**
* @file nissan_primera.c
*
* @date Oct 14, 2013
* @author Andrey Belomutskiy, (c) 2012-2014
*/
#include "main.h"
#if EFI_SUPPORT_NISSAN_PRIMERA || defined(__DOXYGEN__)
#include "nissan_primera.h"
void setNissanPrimeraEngineConfiguration(engine_configuration_s *engineConfiguration) {
engineConfiguration->triggerConfig.totalToothCount = 60;
engineConfiguration->triggerConfig.skippedToothCount = 2;
}
#endif /* EFI_SUPPORT_NISSAN_PRIMERA */

View File

@ -1,14 +0,0 @@
/**
* @file snow_blower.c
* @brief Default configuration of a single-cylinder engine
*
* @date Sep 9, 2013
* @author Andrey Belomutskiy, (c) 2012-2014
*/
#include "main.h"
#if EFI_ENGINE_SNOW_BLOWER
#endif

View File

@ -43,7 +43,7 @@
extern "C"
{
#endif
void chDbgPanic3(const char *msg, char * file, int line);
void chDbgPanic3(const char *msg, const char * file, int line);
#ifdef __cplusplus
}
#endif

View File

@ -1,408 +0,0 @@
/**
* @file status_loop.c
* @brief Human-readable protocol status messages
*
* http://rusefi.com/forum/viewtopic.php?t=263 Dev console overview
* http://rusefi.com/forum/viewtopic.php?t=210 Commands overview
*
*
* @date Mar 15, 2013
* @author Andrey Belomutskiy, (c) 2012-2014
*
* This file is part of rusEfi - see http://rusefi.com
*
* rusEfi is free software; you can redistribute it and/or modify it under the terms of
* the GNU General Public License as published by the Free Software Foundation; either
* version 3 of the License, or (at your option) any later version.
*
* rusEfi is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without
* even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along with this program.
* If not, see <http://www.gnu.org/licenses/>.
*
*/
#include "main.h"
#include "status_loop.h"
#include "adc_inputs.h"
#if EFI_WAVE_ANALYZER
#include "wave_analyzer.h"
#endif
#include "trigger_central.h"
#include "engine_state.h"
#include "io_pins.h"
#include "mmc_card.h"
#include "rusefi.h"
#include "console_io.h"
#include "advance_map.h"
#if EFI_TUNER_STUDIO
#include "tunerstudio.h"
#endif /* EFI_TUNER_STUDIO */
#include "wave_math.h"
#include "fuel_math.h"
#include "main_trigger_callback.h"
#include "engine_math.h"
#include "idle_thread.h"
#include "engine_configuration.h"
#include "rfiutil.h"
#include "svnversion.h"
#if EFI_PROD_CODE
// todo: move this logic to algo folder!
#include "rtc_helper.h"
#include "lcd_HD44780.h"
#endif
// this 'true' value is needed for simulator
static volatile int fullLog = TRUE;
int warningEnabled = TRUE;
//int warningEnabled = FALSE;
extern engine_configuration_s * engineConfiguration;
extern engine_configuration2_s * engineConfiguration2;
#define FULL_LOGGING_KEY "fl"
#if EFI_PROD_CODE || EFI_SIMULATOR
static Logging logger;
static void setWarningEnabled(int value) {
warningEnabled = value;
}
#endif /* EFI_PROD_CODE || EFI_SIMULATOR */
#if EFI_FILE_LOGGING
static Logging fileLogger;
#endif /* EFI_FILE_LOGGING */
static void reportSensorF(char *caption, float value, int precision) {
#if EFI_PROD_CODE || EFI_SIMULATOR
debugFloat(&logger, caption, value, precision);
#endif /* EFI_PROD_CODE || EFI_SIMULATOR */
#if EFI_FILE_LOGGING
debugFloat(&fileLogger, caption, value, precision);
#endif /* EFI_FILE_LOGGING */
}
static void reportSensorI(char *caption, int value) {
#if EFI_PROD_CODE || EFI_SIMULATOR
debugInt(&logger, caption, value);
#endif /* EFI_PROD_CODE || EFI_SIMULATOR */
#if EFI_FILE_LOGGING
debugInt(&fileLogger, caption, value);
#endif /* EFI_FILE_LOGGING */
}
static char* boolean2string(int value) {
return value ? "YES" : "NO";
}
void finishStatusLine(void) {
printLine(&logger);
}
void printSensors(void) {
#if EFI_FILE_LOGGING
resetLogging(&fileLogger);
#endif /* EFI_FILE_LOGGING */
// current time, in milliseconds
int nowMs = currentTimeMillis();
float sec = ((float) nowMs) / 1000;
reportSensorF("time", sec, 3);
reportSensorI("rpm", getRpm());
reportSensorF("maf", getMaf(), 2);
if (engineConfiguration2->hasMapSensor) {
reportSensorF(getCaption(LP_MAP), getMap(), 2);
}
reportSensorF("afr", getAfr(), 2);
reportSensorF("vref", getVRef(), 2);
reportSensorF("vbatt", getVBatt(), 2);
reportSensorF(getCaption(LP_THROTTLE), getTPS(), 2);
if (engineConfiguration2->hasCltSensor) {
reportSensorF(getCaption(LP_ECT), getCoolantTemperature(), 2);
}
reportSensorF(getCaption(LP_IAT), getIntakeAirTemperature(), 2);
// debugFloat(&logger, "tch", getTCharge1(tps), 2);
#if EFI_FILE_LOGGING
appendPrintf(&fileLogger, "\r\n");
appendToLog(fileLogger.buffer);
#endif /* EFI_FILE_LOGGING */
}
void printState(int currentCkpEventCounter) {
printSensors();
int rpm = getRpm();
debugInt(&logger, "ckp_c", currentCkpEventCounter);
debugInt(&logger, "fuel_lag", getRevolutionCounter());
// debugInt(&logger, "idl", getIdleSwitch());
// debugFloat(&logger, "table_spark", getAdvance(rpm, getMaf()), 2);
float engineLoad = getEngineLoad();
debugFloat(&logger, "fuel_base", getBaseFuel(rpm, engineLoad), 2);
// debugFloat(&logger, "fuel_iat", getIatCorrection(getIntakeAirTemperature()), 2);
// debugFloat(&logger, "fuel_clt", getCltCorrection(getCoolantTemperature()), 2);
// debugFloat(&logger, "fuel_lag", getInjectorLag(getVBatt()), 2);
debugFloat(&logger, "fuel", getRunningFuel(rpm, engineLoad), 2);
debugFloat(&logger, "timing", getAdvance(rpm, engineLoad), 2);
// float map = getMap();
// float fuel = getDefaultFuel(rpm, map);
// debugFloat(&logger, "d_fuel", fuel, 2);
}
#define INITIAL_FULL_LOG TRUE
//#define INITIAL_FULL_LOG FALSE
static char LOGGING_BUFFER[500];
#if EFI_PROD_CODE
volatile int needToReportStatus = FALSE;
static int prevCkpEventCounter = -1;
static Logging logger2;
static void printStatus(void) {
needToReportStatus = TRUE;
}
//float getTCharge1(float tps) {
// float cltK = tempCtoKelvin(getCoolantTemperature());
// float iatK = tempCtoKelvin(getIntakeAirTemperature());
// return getTCharge(getCurrentRpm(), tps, cltK, iatK);
//}
#if EFI_CUSTOM_PANIC_METHOD
extern char *dbg_panic_file;
extern int dbg_panic_line;
#endif
void onDbgPanic(void) {
setOutputPinValue(LED_ERROR, 1);
}
int hasFatalError(void) {
return dbg_panic_msg != NULL;
}
static void checkIfShouldHalt(void) {
#if CH_DBG_ENABLED
if (hasFatalError()) {
setOutputPinValue(LED_ERROR, 1);
#if EFI_CUSTOM_PANIC_METHOD
print("my FATAL [%s] at %s:%d\r\n", dbg_panic_msg, dbg_panic_file, dbg_panic_line);
#else
print("my FATAL [%s] at %s:%d\r\n", dbg_panic_msg);
#endif
chThdSleepSeconds(1);
// todo: figure out how we halt exactly
while (TRUE) {
}
chSysHalt();
}
#endif
}
/**
* Time when the firmware version was reported last time, in seconds
* TODO: implement a request/response instead of just constantly sending this out
*/
static systime_t timeOfPreviousPrintVersion = (systime_t) -1;
static void printVersion(systime_t nowSeconds) {
if (overflowDiff(nowSeconds, timeOfPreviousPrintVersion) < 4)
return;
timeOfPreviousPrintVersion = nowSeconds;
appendPrintf(&logger, "rusEfiVersion%s%d@%d %s%s", DELIMETER, getRusEfiVersion(), SVN_VERSION, getConfigurationName(engineConfiguration),
DELIMETER);
}
static systime_t timeOfPreviousReport = (systime_t) -1;
extern bool hasFirmwareError;
extern char errorMessageBuffer[200];
/**
* @brief Sends all pending data to dev console
*/
void updateDevConsoleState(void) {
if (!is_serial_ready())
return;
checkIfShouldHalt();
printPending();
pokeAdcInputs();
if (hasFirmwareError) {
printMsg(&logger, "firmware error: %s", errorMessageBuffer);
return;
}
if (!fullLog)
return;
systime_t nowSeconds = getTimeNowSeconds();
printVersion(nowSeconds);
int currentCkpEventCounter = getCrankEventCounter();
if (prevCkpEventCounter == currentCkpEventCounter && timeOfPreviousReport == nowSeconds)
return;
timeOfPreviousReport = nowSeconds;
prevCkpEventCounter = currentCkpEventCounter;
printState(currentCkpEventCounter);
#if EFI_WAVE_ANALYZER
// printWave(&logger);
#endif
finishStatusLine();
}
/*
* command example:
* sfm 3500 400
* that would be 'show fuel for rpm 3500 maf 4.0'
*/
static void showFuelMap(int rpm, int key100) {
float engineLoad = key100 / 100.0;
float baseFuel = getBaseFuel(rpm, engineLoad);
float iatCorrection = getIatCorrection(getIntakeAirTemperature());
float cltCorrection = getCltCorrection(getCoolantTemperature());
float injectorLag = getInjectorLag(getVBatt());
print("baseFuel=%f\r\n", baseFuel);
print("iatCorrection=%f cltCorrection=%f injectorLag=%d\r\n", iatCorrection, cltCorrection,
(int) (100 * injectorLag));
float value = getRunningFuel(rpm, engineLoad);
print("fuel map rpm=%d, key=%f: %d\r\n", rpm, engineLoad, (int) (100 * value));
scheduleMsg(&logger2, "fuel map value = %f", value);
}
static char buffer[10];
static char dateBuffer[30];
void updateHD44780lcd(void) {
lcd_HD44780_set_position(0, 9);
lcd_HD44780_print_char('R');
lcd_HD44780_set_position(0, 10);
char * ptr = itoa10(buffer, getRpm());
ptr[0] = 0;
int len = ptr - buffer;
for (int i = 0; i < 6 - len; i++)
lcd_HD44780_print_char(' ');
lcd_HD44780_print_string(buffer);
lcd_HD44780_set_position(2, 0);
lcd_HD44780_print_char('C');
ftoa(buffer, getCoolantTemperature(), 100);
lcd_HD44780_print_string(buffer);
#if EFI_PROD_CODE
dateToString(dateBuffer);
lcd_HD44780_set_position(1, 0);
lcd_HD44780_print_string(dateBuffer);
#endif /* EFI_PROD_CODE */
}
#endif /* EFI_PROD_CODE */
static WORKING_AREA(lcdThreadStack, UTILITY_THREAD_STACK_SIZE);
static void lcdThread(void *arg) {
chRegSetThreadName("lcd");
while (true) {
#if EFI_HD44780_LCD
updateHD44780lcd();
#endif
chThdSleepMilliseconds(50);
}
}
static WORKING_AREA(tsThreadStack, UTILITY_THREAD_STACK_SIZE);
static void tsStatusThread(void *arg) {
chRegSetThreadName("tuner s");
while (true) {
#if EFI_TUNER_STUDIO
// sensor state for EFI Analytics Tuner Studio
updateTunerStudioState();
#endif /* EFI_TUNER_STUDIO */
chThdSleepMilliseconds(50);
}
}
void initStatusLoop(void) {
#if EFI_PROD_CODE || EFI_SIMULATOR
initLoggingExt(&logger, "status loop", LOGGING_BUFFER, sizeof(LOGGING_BUFFER));
#endif /* EFI_PROD_CODE || EFI_SIMULATOR */
setFullLog(INITIAL_FULL_LOG);
addConsoleActionI(FULL_LOGGING_KEY, setFullLog);
addConsoleActionI("warn", setWarningEnabled);
#if EFI_PROD_CODE
initLogging(&logger2, "main event handler");
addConsoleActionII("sfm", showFuelMap);
addConsoleAction("status", printStatus);
#endif /* EFI_PROD_CODE */
#if EFI_FILE_LOGGING
initLogging(&fileLogger, "file logger");
#endif /* EFI_FILE_LOGGING */
}
void startStatusThreads(void) {
// todo: refactoring needed, this file should probably be split into pieces
chThdCreateStatic(lcdThreadStack, sizeof(lcdThreadStack), NORMALPRIO, (tfunc_t) lcdThread, NULL);
chThdCreateStatic(tsThreadStack, sizeof(tsThreadStack), NORMALPRIO, (tfunc_t) tsStatusThread, NULL);
}
void setFullLog(int value) {
print("Setting full logging: %s\r\n", boolean2string(value));
printMsg(&logger, "%s%d", FULL_LOGGING_KEY, value);
fullLog = value;
}
int getFullLog(void) {
return fullLog;
}

View File

@ -1,28 +0,0 @@
/*
* @file accel_enrichmemnt.cpp
* @brief accel_enrichmemnt calculator
*
* @date Apr 21, 2014
* @author Dmitry Sidin
* @author Andrey Belomutskiy (c) 2012-2014
*/
#include "accel_enrichmemnt.h"
#include "engine_configuration.h"
extern engine_configuration_s *engineConfiguration;
float AccelEnrichmemnt::getEnrichment(float engineLoad) {
for (int i = 0; i == 4; i++) {
engineLoadD[i] = engineLoadD[i + 1];
}
engineLoadD[0] = engineLoad;
float Dcurr = engineLoadD[1] - engineLoadD[0];
float Dold = engineLoadD[3] - engineLoadD[2];
float diffEnrichment = ((3 * Dcurr + Dold) / 4)
* (engineConfiguration->diffLoadEnrichmentCoef);
return diffEnrichment;
}

View File

@ -1,20 +0,0 @@
/*
* @file accel_enrichmemnt.h
* @brief accel_enrichmemnt calculator
*
* @date Apr 21, 2014
* @author Dmitry Sidin
* @author Andrey Belomutskiy (c) 2012-2014
*/
#ifndef EVENTQUEUE_H_
#define EVENTQUEUE_H_
class AccelEnrichmemnt {
public:
float getEnrichment(float engineLoad);
private:
float engineLoadD[5];
};
#endif /* EVENTQUEUE_H_ */

View File

@ -1,48 +0,0 @@
/*
* @file algo.c
*
* @date Mar 2, 2014
* @author Andrey Belomutskiy, (c) 2012-2014
*
*
* This file is part of rusEfi - see http://rusefi.com
*
* rusEfi is free software; you can redistribute it and/or modify it under the terms of
* the GNU General Public License as published by the Free Software Foundation; either
* version 3 of the License, or (at your option) any later version.
*
* rusEfi is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without
* even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along with this program.
* If not, see <http://www.gnu.org/licenses/>.
*/
#include "global.h"
#include "algo.h"
//#include "rpm_calculator.h"
#include "advance_map.h"
#include "fuel_math.h"
#include "wave_chart.h"
#include "settings.h"
#include "signal_executor.h"
WaveChart waveChart;
void initAlgo(void) {
#if EFI_PROD_CODE || EFI_SIMULATOR
initSettings();
initSignalExecutor();
#endif
#if EFI_WAVE_CHART
initWaveChart(&waveChart);
#endif
prepareFuelMap();
prepareTimingMap();
}

View File

@ -1,370 +0,0 @@
/**
* @file engine_controller.c
* @brief Utility method related to the engine configuration data structure.
*
* @date Nov 22, 2013
* @author Andrey Belomutskiy, (c) 2012-2014
*
* This file is part of rusEfi - see http://rusefi.com
*
* rusEfi is free software; you can redistribute it and/or modify it under the terms of
* the GNU General Public License as published by the Free Software Foundation; either
* version 3 of the License, or (at your option) any later version.
*
* rusEfi is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without
* even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along with this program.
* If not, see <http://www.gnu.org/licenses/>.
*
*/
#include "main.h"
#include "engine_configuration.h"
#include "allsensors.h"
#include "interpolation.h"
#include "trigger_decoder.h"
#include "engine_math.h"
#if EFI_PROD_CODE
#include "tunerstudio.h"
#endif
#include "audi_aan.h"
#include "dodge_neon.h"
#include "ford_aspire.h"
#include "ford_fiesta.h"
#include "ford_1995_inline_6.h"
#include "snow_blower.h"
#include "nissan_primera.h"
#include "honda_accord.h"
#include "GY6_139QMB.h"
#include "mazda_miata_nb.h"
#include "mazda_323.h"
#include "saturn_ion.h"
#include "MiniCooperR50.h"
#include "ford_escort_gt.h"
#include "citroenBerlingoTU3JP.h"
#define ADC_CHANNEL_FAST_ADC 256
static volatile int globalConfigurationVersion = 0;
int getGlobalConfigurationVersion(void) {
return globalConfigurationVersion;
}
void incrementGlobalConfigurationVersion(void) {
globalConfigurationVersion++;
}
/**
* @brief Sets the same dwell time across the whole getRpm() range
*/
void setConstantDwell(engine_configuration_s *engineConfiguration, float dwellMs) {
for (int i = 0; i < DWELL_CURVE_SIZE; i++) {
engineConfiguration->sparkDwellBins[i] = 1000 * i;
engineConfiguration->sparkDwell[i] = dwellMs;
}
}
void initBpsxD1Sensor(afr_sensor_s *sensor) {
/**
* This decodes BPSX D1 Wideband Controller analog signal
*/
sensor->v1 = 0;
sensor->value1 = 9;
sensor->v2 = 5;
sensor->value2 = 19;
}
void setWholeFuelMap(engine_configuration_s *engineConfiguration, float value) {
for (int l = 0; l < FUEL_LOAD_COUNT; l++) {
for (int r = 0; r < FUEL_RPM_COUNT; r++) {
engineConfiguration->fuelTable[l][r] = value;
}
}
}
/**
* @brief Global default engine configuration
* This method sets the default global engine configuration. These values are later overridden by engine-specific defaults
* and the settings saves in flash memory.
*/
void setDefaultConfiguration(engine_configuration_s *engineConfiguration,
board_configuration_s *boardConfiguration) {
memset(engineConfiguration, 0, sizeof(engine_configuration_s));
memset(boardConfiguration, 0, sizeof(board_configuration_s));
engineConfiguration->injectorLag = 0.0;
for (int i = 0; i < IAT_CURVE_SIZE; i++) {
engineConfiguration->iatFuelCorrBins[i] = -40 + i * 10;
engineConfiguration->iatFuelCorr[i] = 1; // this correction is a multiplier
}
for (int i = 0; i < CLT_CURVE_SIZE; i++) {
engineConfiguration->cltFuelCorrBins[i] = -40 + i * 10;
engineConfiguration->cltFuelCorr[i] = 1; // this correction is a multiplier
}
// setTableValue(engineConfiguration->cltFuelCorrBins, engineConfiguration->cltFuelCorr, CLT_CURVE_SIZE, -40, 1.5);
// setTableValue(engineConfiguration->cltFuelCorrBins, engineConfiguration->cltFuelCorr, CLT_CURVE_SIZE, -30, 1.5);
// setTableValue(engineConfiguration->cltFuelCorrBins, engineConfiguration->cltFuelCorr, CLT_CURVE_SIZE, -20, 1.42);
// setTableValue(engineConfiguration->cltFuelCorrBins, engineConfiguration->cltFuelCorr, CLT_CURVE_SIZE, -10, 1.36);
// setTableValue(engineConfiguration->cltFuelCorrBins, engineConfiguration->cltFuelCorr, CLT_CURVE_SIZE, 0, 1.28);
// setTableValue(engineConfiguration->cltFuelCorrBins, engineConfiguration->cltFuelCorr, CLT_CURVE_SIZE, 10, 1.19);
// setTableValue(engineConfiguration->cltFuelCorrBins, engineConfiguration->cltFuelCorr, CLT_CURVE_SIZE, 20, 1.12);
// setTableValue(engineConfiguration->cltFuelCorrBins, engineConfiguration->cltFuelCorr, CLT_CURVE_SIZE, 30, 1.10);
// setTableValue(engineConfiguration->cltFuelCorrBins, engineConfiguration->cltFuelCorr, CLT_CURVE_SIZE, 40, 1.06);
// setTableValue(engineConfiguration->cltFuelCorrBins, engineConfiguration->cltFuelCorr, CLT_CURVE_SIZE, 50, 1.06);
// setTableValue(engineConfiguration->cltFuelCorrBins, engineConfiguration->cltFuelCorr, CLT_CURVE_SIZE, 60, 1.03);
// setTableValue(engineConfiguration->cltFuelCorrBins, engineConfiguration->cltFuelCorr, CLT_CURVE_SIZE, 70, 1.01);
for (int i = 0; i < VBAT_INJECTOR_CURVE_SIZE; i++) {
engineConfiguration->battInjectorLagCorrBins[i] = 12 - VBAT_INJECTOR_CURVE_SIZE / 2 + i;
engineConfiguration->battInjectorLagCorr[i] = 0; // zero extra time by default
}
setConstantDwell(engineConfiguration, 4); // 4ms is global default dwell
setFuelLoadBin(engineConfiguration, 1.2, 4.4);
setFuelRpmBin(engineConfiguration, 800, 7000);
setTimingLoadBin(engineConfiguration, 1.2, 4.4);
setTimingRpmBin(engineConfiguration, 800, 7000);
setTableBin(engineConfiguration->map.config.samplingAngleBins, MAP_ANGLE_SIZE, 800, 7000);
setTableBin(engineConfiguration->map.config.samplingWindowBins, MAP_ANGLE_SIZE, 800, 7000);
// set_whole_timing_map 3
setWholeFuelMap(engineConfiguration, 3);
setThermistorConfiguration(&engineConfiguration->cltThermistorConf, 0, 9500, 23.8889, 2100, 48.8889, 1000);
engineConfiguration->cltThermistorConf.bias_resistor = 1500;
setThermistorConfiguration(&engineConfiguration->iatThermistorConf, 32, 9500, 75, 2100, 120, 1000);
// todo: this value is way off! I am pretty sure temp coeffs are off also
engineConfiguration->iatThermistorConf.bias_resistor = 2700;
engineConfiguration->rpmHardLimit = 7000;
engineConfiguration->crankingSettings.crankingRpm = 550;
engineConfiguration->analogInputDividerCoefficient = 2;
engineConfiguration->crankingChargeAngle = 70;
engineConfiguration->timingMode = TM_DYNAMIC;
engineConfiguration->fixedModeTiming = 50;
engineConfiguration->analogChartMode = AC_TRIGGER;
engineConfiguration->map.channel = ADC_CHANNEL_FAST_ADC;
engineConfiguration->firingOrder = FO_1_THEN_3_THEN_4_THEN2;
engineConfiguration->crankingInjectionMode = IM_SIMULTANEOUS;
engineConfiguration->injectionMode = IM_SEQUENTIAL;
engineConfiguration->ignitionMode = IM_ONE_COIL;
engineConfiguration->globalTriggerAngleOffset = 0;
engineConfiguration->injectionOffset = 0;
engineConfiguration->ignitionOffset = 0;
engineConfiguration->overrideCrankingIgnition = TRUE;
engineConfiguration->analogChartFrequency = 20;
engineConfiguration->engineLoadMode = LM_MAF;
engineConfiguration->vbattDividerCoeff = ((float)(15 + 65)) / 15;
engineConfiguration->fanOnTemperature = 75;
engineConfiguration->fanOffTemperature = 70;
engineConfiguration->tpsMin = convertVoltageTo10bitADC(1.250);
engineConfiguration->tpsMax = convertVoltageTo10bitADC(4.538);
engineConfiguration->can_nbc_type = CAN_BUS_NBC_BMW;
engineConfiguration->can_sleep_period = 50;
engineConfiguration->canReadEnabled = TRUE;
engineConfiguration->canWriteEnabled = FALSE;
/**
* 0.5 means primary position sensor is on a camshaft
*/
engineConfiguration->rpmMultiplier = 0.5;
engineConfiguration->cylindersCount = 4;
engineConfiguration->displayMode = DM_HD44780;
engineConfiguration->logFormat = LF_NATIVE;
engineConfiguration->triggerConfig.triggerType = TT_TOOTHED_WHEEL;
engineConfiguration->triggerConfig.syncRatioFrom = 1.5;
engineConfiguration->triggerConfig.syncRatioTo = 3;
engineConfiguration->triggerConfig.isSynchronizationNeeded = TRUE;
engineConfiguration->triggerConfig.useRiseEdge = TRUE;
engineConfiguration->HD44780width = 16;
engineConfiguration->HD44780height = 2;
engineConfiguration->tpsAdcChannel = 3;
engineConfiguration->vBattAdcChannel = 5;
engineConfiguration->cltAdcChannel = 6;
engineConfiguration->iatAdcChannel = 7;
engineConfiguration->mafAdcChannel = 0;
engineConfiguration->afrSensor.afrAdcChannel = 14;
initBpsxD1Sensor(&engineConfiguration->afrSensor);
engineConfiguration->globalFuelCorrection = 1;
engineConfiguration->needSecondTriggerInput = TRUE;
engineConfiguration->map.config.mapType = MT_CUSTOM;
engineConfiguration->map.config.Min = 0;
engineConfiguration->map.config.Max = 500;
engineConfiguration->diffLoadEnrichmentCoef = 1;
boardConfiguration->idleValvePin = GPIOE_2;
boardConfiguration->idleValvePinMode = OM_DEFAULT;
boardConfiguration->fuelPumpPin = GPIOC_13;
boardConfiguration->fuelPumpPinMode = OM_DEFAULT;
boardConfiguration->electronicThrottlePin1 = GPIOC_9;
boardConfiguration->injectionPins[0] = GPIOB_9;
boardConfiguration->injectionPins[1] = GPIOB_8;
boardConfiguration->injectionPins[2] = GPIOE_3;
boardConfiguration->injectionPins[3] = GPIOE_5;
boardConfiguration->injectionPins[4] = GPIOE_6;
boardConfiguration->injectionPins[5] = GPIOC_12;
boardConfiguration->injectionPinMode = OM_DEFAULT;
boardConfiguration->ignitionPins[0] = GPIOC_7;
boardConfiguration->ignitionPins[1] = GPIOE_4; // todo: update this value
boardConfiguration->ignitionPins[2] = GPIOE_0; // todo: update this value
boardConfiguration->ignitionPins[3] = GPIOE_1; // todo: update this value
boardConfiguration->ignitionPinMode = OM_DEFAULT;
boardConfiguration->malfunctionIndicatorPin = GPIOC_9;
boardConfiguration->malfunctionIndicatorPinMode = OM_DEFAULT;
boardConfiguration->fanPin = GPIOC_15;
boardConfiguration->fanPinMode = OM_DEFAULT;
boardConfiguration->idleSwitchPin = GPIOC_8;
boardConfiguration->triggerSimulatorPins[0] = GPIOD_1;
boardConfiguration->triggerSimulatorPins[1] = GPIOD_2;
boardConfiguration->triggerSimulatorPinModes[0] = OM_DEFAULT;
boardConfiguration->triggerSimulatorPinModes[1] = OM_DEFAULT;
boardConfiguration->HD44780_rs = GPIOE_9;
boardConfiguration->HD44780_e = GPIOE_11;
boardConfiguration->HD44780_db4 = GPIOE_13;
boardConfiguration->HD44780_db5 = GPIOE_15;
boardConfiguration->HD44780_db6 = GPIOB_11;
boardConfiguration->HD44780_db7 = GPIOB_13;
}
void setDefaultNonPersistentConfiguration(engine_configuration2_s *engineConfiguration2) {
/**
* 720 is the range for four stroke
*/
engineConfiguration2->crankAngleRange = 720;
engineConfiguration2->hasMapSensor = TRUE;
engineConfiguration2->hasCltSensor = TRUE;
}
void resetConfigurationExt(engine_type_e engineType,
engine_configuration_s *engineConfiguration,
engine_configuration2_s *engineConfiguration2,
board_configuration_s *boardConfiguration) {
/**
* Let's apply global defaults first
*/
setDefaultConfiguration(engineConfiguration, boardConfiguration);
engineConfiguration->engineType = engineType;
/**
* And override them with engine-specific defaults
*/
switch (engineType) {
#if EFI_SUPPORT_DODGE_NEON || defined(__DOXYGEN__)
case DODGE_NEON_1995:
setDodgeNeonEngineConfiguration(engineConfiguration, boardConfiguration);
break;
#endif /* EFI_SUPPORT_DODGE_NEON */
#if EFI_SUPPORT_FORD_ASPIRE || defined(__DOXYGEN__)
case FORD_ASPIRE_1996:
setFordAspireEngineConfiguration(engineConfiguration, boardConfiguration);
break;
#endif /* EFI_SUPPORT_FORD_ASPIRE */
#if EFI_SUPPORT_FORD_FIESTA || defined(__DOXYGEN__)
case FORD_FIESTA:
setFordFiestaDefaultEngineConfiguration(engineConfiguration);
break;
#endif /* EFI_SUPPORT_FORD_FIESTA */
#if EFI_SUPPORT_NISSAN_PRIMERA || defined(__DOXYGEN__)
case NISSAN_PRIMERA:
setNissanPrimeraEngineConfiguration(engineConfiguration);
break;
#endif
case HONDA_ACCORD:
setHondaAccordConfiguration(engineConfiguration);
break;
#if EFI_SUPPORT_1995_FORD_INLINE_6 || defined(__DOXYGEN__)
case FORD_INLINE_6_1995:
setFordInline6(engineConfiguration, boardConfiguration);
break;
#endif /* EFI_SUPPORT_1995_FORD_INLINE_6 */
case GY6_139QMB:
setGy6139qmbDefaultEngineConfiguration(engineConfiguration);
break;
case MAZDA_MIATA_NB:
setMazdaMiataNbEngineConfiguration(engineConfiguration, boardConfiguration);
break;
case MAZDA_323:
setMazda323EngineConfiguration(engineConfiguration);
break;
case SATURN_ION_2004:
setSaturnIonEngineConfiguration(engineConfiguration);
break;
case MINI_COOPER_R50:
setMiniCooperR50(engineConfiguration, boardConfiguration);
break;
case FORD_ESCORT_GT:
setFordEscortGt(engineConfiguration, boardConfiguration);
break;
case CITROEN_TU3JP:
setCitroenBerlingoTU3JPConfiguration(engineConfiguration, boardConfiguration);
break;
default:
firmwareError("Unexpected engine type: %d", engineType);
}
applyNonPersistentConfiguration(engineConfiguration, engineConfiguration2, engineType);
#if EFI_TUNER_STUDIO
syncTunerStudioCopy();
#endif
}
void applyNonPersistentConfiguration(engine_configuration_s *engineConfiguration, engine_configuration2_s *engineConfiguration2, engine_type_e engineType) {
// todo: this would require 'initThermistors() to re-establish a reference, todo: fix
// memset(engineConfiguration2, 0, sizeof(engine_configuration2_s));
engineConfiguration2->isInjectionEnabledFlag = TRUE;
initializeTriggerShape(engineConfiguration, engineConfiguration2);
chDbgCheck(engineConfiguration2->triggerShape.size != 0, "size is zero");
chDbgCheck(engineConfiguration2->triggerShape.shaftPositionEventCount, "shaftPositionEventCount is zero");
prepareOutputSignals(engineConfiguration, engineConfiguration2);
initializeIgnitionActions(0, engineConfiguration, engineConfiguration2);
}

View File

@ -331,7 +331,7 @@ const char* getConfigurationName(engine_configuration_s *engineConfiguration);
void setDefaultConfiguration(engine_configuration_s *engineConfiguration, board_configuration_s *boardConfiguration);
void setWholeFuelMap(engine_configuration_s *engineConfiguration, float value);
void setConstantDwell(engine_configuration_s *engineConfiguration, float dwellMs);
void printFloatArray(char *prefix, float array[], int size);
void printFloatArray(const char *prefix, float array[], int size);
void incrementGlobalConfigurationVersion(void);

View File

@ -32,7 +32,7 @@ int hasFatalError(void);
void fatal3(char *msg, char *file, int line);
#define fatal(x) (fatal3(x, __FILE__, __LINE__));
void chDbgPanic3(const char *msg, char * file, int line);
void chDbgPanic3(const char *msg, const char * file, int line);
void initErrorHandling(void);

View File

@ -1,74 +0,0 @@
/**
* @file signal_executor_single_timer_algo.c
*
* @date Nov 28, 2013
* @author Andrey Belomutskiy, (c) 2012-2014
*
*
* This file is part of rusEfi - see http://rusefi.com
*
* rusEfi is free software; you can redistribute it and/or modify it under the terms of
* the GNU General Public License as published by the Free Software Foundation; either
* version 3 of the License, or (at your option) any later version.
*
* rusEfi is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without
* even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along with this program.
* If not, see <http://www.gnu.org/licenses/>.
*/
#include "signal_executor.h"
#include "signal_executor_single_timer_algo.h"
#include "main.h"
#include "utlist.h"
#include "io_pins.h"
#if EFI_WAVE_ANALYZER
#include "wave_analyzer.h"
#include "wave_chart.h"
extern WaveChart waveChart;
#endif
#if EFI_SIGNAL_EXECUTOR_SINGLE_TIMER
/**
* @brief Output list
*
* List of all active output signals
* This is actually the head of the list.
* When the list is empty (initial state) the head of the list should be NULL.
* This is by design.
*/
OutputSignal *st_output_list = NULL;
inline void registerSignal(OutputSignal *signal) {
LL_APPEND(st_output_list, signal);
}
void setOutputPinValue(io_pin_e pin, int value);
/**
* @return time of next event within for this signal
* @todo Find better name.
*/
inline time_t toggleSignalIfNeeded(OutputSignal *out, time_t now) {
// chDbgCheck(out!=NULL, "out is NULL");
// chDbgCheck(out->io_pin < IO_PIN_COUNT, "pin assertion");
time_t last = out->last_scheduling_time;
//estimated = last + out->timing[out->status];
time_t estimated = last + GET_DURATION(out);
if (now >= estimated) {
out->status ^= 1; /* toggle status */
//setOutputPinValue(out->io_pin, out->status); /* Toggle output */
palWritePad(GPIOE, 5, out->status);
#if EFI_WAVE_ANALYZER
// addWaveChartEvent(out->name, out->status ? "up" : "down", "");
#endif /* EFI_WAVE_ANALYZER */
// out->last_scheduling_time = now; /* store last update */
estimated = now + GET_DURATION(out); /* update estimation */
}
return estimated - now;
}
#endif /* EFI_SIGNAL_EXECUTOR_SINGLE_TIMER */

View File

@ -1,18 +0,0 @@
/**
* @file signal_executor_single_timer_algo.h
*
* @date Nov 28, 2013
* @author Andrey Belomutskiy, (c) 2012-2014
*/
#ifndef SIGNAL_EXECUTOR_SINGLE_TIMER_ALGO_H_
#define SIGNAL_EXECUTOR_SINGLE_TIMER_ALGO_H_
#include "signal_executor.h"
#define GET_DURATION(o) ((o)->status ? (o)->signalTimerDown.moment : (o)->signalTimerUp.moment)
inline void registerSignal(OutputSignal *signal);
inline time_t toggleSignalIfNeeded(OutputSignal *out, time_t now);
#endif /* SIGNAL_EXECUTOR_SINGLE_TIMER_ALGO_H_ */

View File

@ -1,62 +0,0 @@
/**
* @file alternatorController.c
* @brief alternator controller
*
* @date Apr 6, 2014
* @author Dmitry Sidin
* @author Andrey Belomutskiy (c) 2012-2014
*/
#include "main.h"
#include "rpm_calculator.h"
#include "pwm_generator.h"
#include "wave_math.h"
#include "alternatorController.h"
#include "pin_repository.h"
#include "engine_configuration.h"
#include "voltage.h"
#if 0
extern board_configuration_s *boardConfiguration;
#define ALTERNATOR_VALVE_PWM_FREQUENCY 30000
static PwmConfig alternatorControl;
static WORKING_AREA(ivThreadStack, UTILITY_THREAD_STACK_SIZE);
static msg_t AltCtrlThread(int param) {
chRegSetThreadName("AlternatorController");
int alternatorDutyCycle = 500;
while (TRUE) {
chThdSleepMilliseconds(10);
if ( getVBatt() > 14.2 )
alternatorDutyCycle = alternatorDutyCycle + 1 ;
else
alternatorDutyCycle = alternatorDutyCycle - 1;
if (alternatorDutyCycle < 150 )
alternatorDutyCycle = 150;
if (alternatorDutyCycle > 950)
alternatorDutyCycle = 950;
setSimplePwmDutyCycle(&alternatorControl, 0.001 * alternatorDutyCycle);
}
#if defined __GNUC__
return -1;
#endif
}
void initAlternatorCtrl() {
startSimplePwm(&alternatorControl, "Alternator control",
boardConfiguration->alternatorControlPin,
0.5,
ALTERNATOR_VALVE_PWM_FREQUENCY,
ALTERNATOR_SWITCH
);
chThdCreateStatic(ivThreadStack, sizeof(ivThreadStack), LOWPRIO, (tfunc_t)AltCtrlThread, NULL);
}
#endif

View File

@ -1,97 +0,0 @@
/**
* @file electronic_throttle.c
* @brief Electronic Throttle Module driver L298N
*
* todo: make this more universal if/when we get other hardware options
*
* @date Dec 7, 2013
* @author Andrey Belomutskiy, (c) 2012-2014
*
* This file is part of rusEfi - see http://rusefi.com
*
* rusEfi is free software; you can redistribute it and/or modify it under the terms of
* the GNU General Public License as published by the Free Software Foundation; either
* version 3 of the License, or (at your option) any later version.
*
* rusEfi is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without
* even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along with this program.
* If not, see <http://www.gnu.org/licenses/>.
*/
#include "main.h"
#include "electronic_throttle.h"
#include "boards.h"
#include "pin_repository.h"
#include "idle_controller.h"
#include "tps.h"
#include "io_pins.h"
#include "engine_configuration.h"
#include "pwm_generator.h"
#include "pwm_generator_logic.h"
#if EFI_ELECTRONIC_THROTTLE_BODY
static Logging logger;
/**
* @brief Control Thread stack
*/
static WORKING_AREA(etbTreadStack, UTILITY_THREAD_STACK_SIZE);
/**
* @brief Pulse-Width Modulation state
*/
static PwmConfig etbPwm;
static float prevTps;
extern engine_configuration_s *engineConfiguration;
extern board_configuration_s *boardConfiguration;
static msg_t etbThread(void *arg) {
while (TRUE) {
int tps = (int)getTPS();
if (tps != prevTps) {
prevTps = tps;
scheduleMsg(&logger, "tps=%d", (int) tps);
}
// this thread is activated 10 times per second
chThdSleepMilliseconds(100);
}
#if defined __GNUC__
return -1;
#endif
}
static void setThrottleConsole(int level) {
scheduleMsg(&logger, "setting throttle=%d", level);
etbPwm.multiWave.switchTimes[0] = 0.01 + (min(level, 98)) / 100.0;
print("st = %f\r\n", etbPwm.multiWave.switchTimes[0]);
}
void initElectronicThrottle(void) {
initLogging(&logger, "Electronic Throttle");
engineConfiguration->tpsMin = 140;
engineConfiguration->tpsMax = 898;
// these two lines are controlling direction
// outputPinRegister("etb1", ELECTRONIC_THROTTLE_CONTROL_1, ETB_CONTROL_LINE_1_PORT, ETB_CONTROL_LINE_1_PIN);
// outputPinRegister("etb2", ELECTRONIC_THROTTLE_CONTROL_2, ETB_CONTROL_LINE_2_PORT, ETB_CONTROL_LINE_2_PIN);
// this line used for PWM
startSimplePwm(&etbPwm, "etb",
boardConfiguration->electronicThrottlePin1,
ELECTRONIC_THROTTLE_CONTROL_1,
0.80,
500);
addConsoleActionI("e", setThrottleConsole);
chThdCreateStatic(etbTreadStack, sizeof(etbTreadStack), NORMALPRIO, (tfunc_t) etbThread, NULL);
}
#endif /* EFI_ELECTRONIC_THROTTLE_BODY */

View File

@ -1,114 +0,0 @@
/**
* @file flash_main.c
* @brief Higher-level logic of saving data into internal flash memory
*
*
* @date Sep 19, 2013
* @author Andrey Belomutskiy, (c) 2012-2014
*/
#include <ch.h>
#include <hal.h>
#include <string.h>
#include "flash_main.h"
#include "eficonsole.h"
#include "flash.h"
#include "rusefi.h"
//#include "tunerstudio.h"
#include "engine_controller.h"
#include "datalogging.h"
#include "audi_aan.h"
#include "dodge_neon.h"
#include "ford_aspire.h"
#include "ford_fiesta.h"
#include "ford_1995_inline_6.h"
#include "snow_blower.h"
#include "nissan_primera.h"
#include "honda_accord.h"
#include "GY6_139QMB.h"
static engine_type_e defaultEngineType = FORD_ASPIRE_1996;
//static engine_type_e defaultEngineType = DODGE_NEON_1995;
static Logging logger;
#if defined __GNUC__
FlashState flashState __attribute__((section(".ccm")));
#else
FlashState flashState;
#endif
engine_configuration_s *engineConfiguration = &flashState.persistentConfiguration.engineConfiguration;
board_configuration_s *boardConfiguration = &flashState.persistentConfiguration.boardConfiguration;
extern engine_configuration2_s * engineConfiguration2;
#define FLASH_ADDR 0x08060000
#define FLASH_USAGE sizeof(FlashState)
crc flashStateCrc(FlashState *state) {
return calc_crc((const crc*) &state->persistentConfiguration, sizeof(persistent_config_s));
}
void writeToFlash(void) {
flashState.version = FLASH_DATA_VERSION;
scheduleMsg(&logger, "FLASH_DATA_VERSION=%d", flashState.version);
crc result = flashStateCrc(&flashState);
flashState.value = result;
scheduleMsg(&logger, "Reseting flash=%d", FLASH_USAGE);
flashErase(FLASH_ADDR, FLASH_USAGE);
scheduleMsg(&logger, "Flashing with CRC=%d", result);
efitimems_t nowMs = currentTimeMillis();
result = flashWrite(FLASH_ADDR, (const char *) &flashState, FLASH_USAGE);
scheduleMsg(&logger, "Flash programmed in (ms): %d", currentTimeMillis() - nowMs);
scheduleMsg(&logger, "Flashed: %d", result);
}
static int isValidCrc(FlashState *state) {
if (state->version != FLASH_DATA_VERSION) {
scheduleMsg(&logger, "Unexpected flash version: %d", state->version);
return FALSE;
}
crc result = flashStateCrc(state);
int isValidCrc = result == state->value;
if (!isValidCrc)
scheduleMsg(&logger, "CRC got %d while %d expected", result, state->value);
return isValidCrc;
}
static void doResetConfiguration(void) {
resetConfigurationExt(engineConfiguration->engineType, engineConfiguration, engineConfiguration2, boardConfiguration);
}
static void readFromFlash(void) {
flashRead(FLASH_ADDR, (char *) &flashState, FLASH_USAGE);
setDefaultNonPersistentConfiguration(engineConfiguration2);
if (!isValidCrc(&flashState)) {
scheduleMsg(&logger, "Need to reset flash to default");
resetConfigurationExt(defaultEngineType, engineConfiguration, engineConfiguration2, boardConfiguration);
} else {
scheduleMsg(&logger, "Got valid configuration from flash!");
applyNonPersistentConfiguration(engineConfiguration, engineConfiguration2, engineConfiguration->engineType);
}
// we can only change the state after the CRC check
engineConfiguration->firmwareVersion = getRusEfiVersion();
}
void initFlash(void) {
initLogging(&logger, "Flash memory");
print("initFlash()\r\n");
addConsoleAction("readconfig", readFromFlash);
addConsoleAction("writeconfig", writeToFlash);
addConsoleAction("resetconfig", doResetConfiguration);
readFromFlash();
}

View File

@ -1,137 +0,0 @@
/**
* @file idle_thread.c
* @brief Idle Air Control valve thread.
*
* This thread looks at current RPM and decides if it should increase or decrease IAC duty cycle.
* This file is has the hardware & scheduling logic, desired idle level lives separately
*
*
* @date May 23, 2013
* @author Andrey Belomutskiy, (c) 2012-2014
*
* This file is part of rusEfi - see http://rusefi.com
*
* rusEfi is free software; you can redistribute it and/or modify it under the terms of
* the GNU General Public License as published by the Free Software Foundation; either
* version 3 of the License, or (at your option) any later version.
*
* rusEfi is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without
* even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along with this program.
* If not, see <http://www.gnu.org/licenses/>.
*/
#include "main.h"
#include "idle_controller.h"
#include "rpm_calculator.h"
#include "pwm_generator.h"
#include "wave_math.h"
#include "idle_thread.h"
#include "pin_repository.h"
#include "engine_configuration.h"
#define IDLE_AIR_CONTROL_VALVE_PWM_FREQUENCY 200
static WORKING_AREA(ivThreadStack, UTILITY_THREAD_STACK_SIZE);
static volatile int isIdleControlActive = EFI_IDLE_CONTROL;
extern board_configuration_s *boardConfiguration;
/**
* here we keep the value we got from IDLE SWITCH input
*/
static volatile int idleSwitchState;
static Logging logger;
static PwmConfig idleValve;
/**
* Idle level calculation algorithm lives in idle_controller.c
*/
static IdleValveState idle;
int getIdleSwitch() {
return idleSwitchState;
}
void idleDebug(char *msg, int value) {
printMsg(&logger, "%s%d", msg, value);
scheduleLogging(&logger);
}
static void setIdleControlEnabled(int value) {
isIdleControlActive = value;
scheduleMsg(&logger, "isIdleControlActive=%d", isIdleControlActive);
}
static void setIdleValvePwm(int value) {
// todo: change parameter type, maybe change parameter validation?
if (value < 1 || value > 999)
return;
scheduleMsg(&logger, "setting idle valve PWM %d", value);
/**
* currently IDEL level is an integer per mil (0-1000 range), and PWM takes a fioat in the 0..1 range
* todo: unify?
*/
setSimplePwmDutyCycle(&idleValve, 0.001 * value);
}
static msg_t ivThread(int param) {
chRegSetThreadName("IdleValve");
int currentIdleValve = -1;
while (TRUE) {
chThdSleepMilliseconds(100);
// this value is not used yet
idleSwitchState = palReadPad(getHwPort(boardConfiguration->idleSwitchPin), getHwPin(boardConfiguration->idleSwitchPin));
if (!isIdleControlActive)
continue;
int nowSec = getTimeNowSeconds();
int newValue = getIdle(&idle, getRpm(), nowSec);
if (currentIdleValve != newValue) {
currentIdleValve = newValue;
setIdleValvePwm(newValue);
}
}
#if defined __GNUC__
return -1;
#endif
}
static void setIdleRpmAction(int value) {
setIdleRpm(&idle, value);
scheduleMsg(&logger, "target idle RPM %d", value);
}
void startIdleThread() {
initLogging(&logger, "Idle Valve Control");
startSimplePwm(&idleValve, "Idle Valve",
boardConfiguration->idleValvePin,
0.5,
IDLE_AIR_CONTROL_VALVE_PWM_FREQUENCY,
IDLE_VALVE
);
idleInit(&idle);
scheduleMsg(&logger, "initial idle %d", idle.value);
chThdCreateStatic(ivThreadStack, sizeof(ivThreadStack), NORMALPRIO, (tfunc_t)ivThread, NULL);
// this is idle switch INPUT - sometimes there is a switch on the throttle pedal
// this switch is not used yet
mySetPadMode("idle switch", getHwPort(boardConfiguration->idleSwitchPin), getHwPin(boardConfiguration->idleSwitchPin), PAL_MODE_INPUT);
addConsoleActionI("set_idle_rpm", setIdleRpmAction);
addConsoleActionI("set_idle_pwm", setIdleValvePwm);
addConsoleActionI("set_idle_enabled", setIdleControlEnabled);
}

View File

@ -1,166 +0,0 @@
/**
* @file injector_central.c
* @brief Utility methods related to fuel injection.
*
*
* @date Sep 8, 2013
* @author Andrey Belomutskiy, (c) 2012-2014
*
* This file is part of rusEfi - see http://rusefi.com
*
* rusEfi is free software; you can redistribute it and/or modify it under the terms of
* the GNU General Public License as published by the Free Software Foundation; either
* version 3 of the License, or (at your option) any later version.
*
* rusEfi is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without
* even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along with this program.
* If not, see <http://www.gnu.org/licenses/>.
*/
#include "injector_central.h"
#include "main.h"
#include "engines.h"
#include "io_pins.h"
#include "signal_executor.h"
#include "main_trigger_callback.h"
#include "engine_configuration.h"
#include "pin_repository.h"
static Logging logger;
extern engine_configuration_s *engineConfiguration;
extern engine_configuration2_s *engineConfiguration2;
extern board_configuration_s *boardConfiguration;
static int is_injector_enabled[MAX_INJECTOR_COUNT];
int isInjectionEnabled(void) {
return engineConfiguration2->isInjectionEnabledFlag;
}
void assertCylinderId(int cylinderId, char *msg) {
int isValid = cylinderId >= 1 && cylinderId <= engineConfiguration->cylindersCount;
if (!isValid) {
// we are here only in case of a fatal issue - at this point it is fine to make some blocking i-o
//scheduleSimpleMsg(&logger, "cid=", cylinderId);
print("ERROR [%s] cid=%d\r\n", msg, cylinderId);
chDbgAssert(TRUE, "Cylinder ID", null);
}
}
///**
// * This method schedules asynchronous fuel squirt
// */
/**
* @param cylinderId - from 1 to NUMBER_OF_CYLINDERS
*/
int isInjectorEnabled(int cylinderId) {
assertCylinderId(cylinderId, "isInjectorEnabled");
return is_injector_enabled[cylinderId - 1];
}
static void printStatus(void) {
for (int id = 1; id <= engineConfiguration->cylindersCount; id++) {
resetLogging(&logger);
appendPrintf(&logger, "injector%d%s", id, DELIMETER);
appendPrintf(&logger, "%d", isInjectorEnabled(id));
appendPrintf(&logger, DELIMETER);
scheduleLogging(&logger);
}
}
static void setInjectorEnabled(int id, int value) {
chDbgCheck(id >= 0 && id < engineConfiguration->cylindersCount, "injector id");
is_injector_enabled[id] = value;
printStatus();
}
void runBench(brain_pin_e brainPin, io_pin_e pin, float onTime, float offTime, int count) {
scheduleMsg(&logger, "Running bench: ON_TIME=%f ms OFF_TIME=%fms Counter=%d", onTime, offTime, count);
scheduleMsg(&logger, "output on %s", hwPortname(brainPin));
for (int i = 0; i < count; i++) {
setOutputPinValue(pin, TRUE);
chThdSleep((int) (onTime * CH_FREQUENCY / 1000));
setOutputPinValue(pin, FALSE);
chThdSleep((int) (offTime * CH_FREQUENCY / 1000));
}
scheduleMsg(&logger, "Done!");
}
static volatile int needToRunBench = FALSE;
float onTime;
float offTime;
int count;
brain_pin_e brainPin;
io_pin_e pin;
static void fuelbench(char * onStr, char *offStr, char *countStr) {
onTime = atoff(onStr);
offTime = atoff(offStr);
count = atoi(countStr);
brainPin = boardConfiguration->injectionPins[0];
pin = INJECTOR_1_OUTPUT;
needToRunBench = TRUE;
}
static void sparkbench(char * onStr, char *offStr, char *countStr) {
onTime = atoff(onStr);
offTime = atoff(offStr);
count = atoi(countStr);
brainPin = boardConfiguration->ignitionPins[0];
pin = SPARKOUT_1_OUTPUT;
needToRunBench = TRUE;
}
static WORKING_AREA(benchThreadStack, UTILITY_THREAD_STACK_SIZE);
static msg_t benchThread(int param) {
chRegSetThreadName("BenchThread");
while (TRUE) {
while (!needToRunBench) {
chThdSleepMilliseconds(50);
}
needToRunBench = FALSE;
runBench(brainPin, pin, onTime, offTime, count);
}
return 0;
}
void initInjectorCentral(void) {
initLogging(&logger, "InjectorCentral");
chThdCreateStatic(benchThreadStack, sizeof(benchThreadStack), NORMALPRIO, (tfunc_t) benchThread, NULL);
for (int i = 0; i < engineConfiguration->cylindersCount; i++)
is_injector_enabled[i] = true;
printStatus();
// todo: should we move this code closer to the injection logic?
// todo: dynamic initialization
// todo: consider actual cylinders count
outputPinRegisterExt2("injector1", INJECTOR_1_OUTPUT, boardConfiguration->injectionPins[0],
&boardConfiguration->injectionPinMode);
outputPinRegisterExt2("injector2", INJECTOR_2_OUTPUT, boardConfiguration->injectionPins[1],
&boardConfiguration->injectionPinMode);
outputPinRegisterExt2("injector3", INJECTOR_3_OUTPUT, boardConfiguration->injectionPins[2],
&boardConfiguration->injectionPinMode);
outputPinRegisterExt2("injector4", INJECTOR_4_OUTPUT, boardConfiguration->injectionPins[3],
&boardConfiguration->injectionPinMode);
outputPinRegisterExt2("injector5", INJECTOR_5_OUTPUT, boardConfiguration->injectionPins[4],
&boardConfiguration->injectionPinMode);
outputPinRegisterExt2("injector5", INJECTOR_6_OUTPUT, boardConfiguration->injectionPins[5],
&boardConfiguration->injectionPinMode);
addConsoleActionII("injector", setInjectorEnabled);
addConsoleActionSSS("fuelbench", &fuelbench);
addConsoleActionSSS("sparkbench", &sparkbench);
}

View File

@ -1,167 +0,0 @@
/**
* @file thermistors.c
*
* @date Feb 17, 2013
* @author Andrey Belomutskiy, (c) 2012-2014
*/
/**
* http://en.wikipedia.org/wiki/Thermistor
* http://en.wikipedia.org/wiki/Steinhart%E2%80%93Hart_equation
*/
#include "main.h"
#include "thermistors.h"
#include "adc_inputs.h"
#include "engine_configuration.h"
#include "engine_math.h"
extern engine_configuration_s *engineConfiguration;
extern engine_configuration2_s *engineConfiguration2;
static bool_t initialized = FALSE;
/**
* http://en.wikipedia.org/wiki/Voltage_divider
*/
float getR1InVoltageDividor(float Vout, float Vin, float r2) {
return r2 * Vin / Vout - r2;
}
float getR2InVoltageDividor(float Vout, float Vin, float r1) {
if (Vout == 0)
return NAN;
return r1 / (Vin / Vout - 1);
}
float getVoutInVoltageDividor(float Vin, float r1, float r2) {
return r2 * Vin / (r1 + r2);
}
float convertResistanceToKelvinTemperature(float resistance, ThermistorConf *thermistor) {
if (resistance <= 0) {
//warning("Invalid resistance in convertResistanceToKelvinTemperature=", resistance);
return 0;
}
float logR = log(resistance);
return 1 / (thermistor->s_h_a + thermistor->s_h_b * logR + thermistor->s_h_c * logR * logR * logR);
}
float convertKelvinToC(float tempK) {
return tempK - KELV;
}
float convertCelciustoKelvin(float tempC) {
return tempC + KELV;
}
float convertCelciustoF(float tempC) {
return tempC * 9 / 5 + 32;
}
float convertFtoCelcius(float tempF) {
return (tempF - 32) / 9 * 5;
}
float convertKelvinToFahrenheit(float kelvin) {
float tempC = convertKelvinToC(kelvin);
return convertCelciustoF(tempC);
}
float getKelvinTemperature(float resistance, ThermistorConf *thermistor) {
chDbgCheck(thermistor!=NULL, "thermistor pointer is NULL");
float kelvinTemperature = convertResistanceToKelvinTemperature(resistance, thermistor);
return kelvinTemperature;
}
float getResistance(Thermistor *thermistor) {
float voltage = getVoltageDivided(thermistor->channel);
chDbgCheck(thermistor->config != NULL, "config is null");
float resistance = getR2InVoltageDividor(voltage, _5_VOLTS, thermistor->config->bias_resistor);
return resistance;
}
float getTemperatureC(Thermistor *thermistor) {
chDbgCheck(initialized, "initialized");
float resistance = getResistance(thermistor);
float kelvinTemperature = getKelvinTemperature(resistance, thermistor->config);
return convertKelvinToC(kelvinTemperature);
}
int isValidCoolantTemperature(float temperature) {
// I hope magic constants are appropriate here
return !cisnan(temperature) && temperature > -50 && temperature < 250;
}
int isValidIntakeAirTemperature(float temperature) {
// I hope magic constants are appropriate here
return !cisnan(temperature) && temperature > -50 && temperature < 100;
}
/**
* @return coolant temperature, in Celcius
*/
float getCoolantTemperature(void) {
float temperature = getTemperatureC(&engineConfiguration2->clt);
if (!isValidCoolantTemperature(temperature))
return NAN;
return temperature;
}
void setThermistorConfiguration(ThermistorConf * tc, float tempC1, float r1, float tempC2, float r2, float tempC3,
float r3) {
tc->tempC_1 = tempC1;
tc->resistance_1 = r1;
tc->tempC_2 = tempC2;
tc->resistance_2 = r2;
tc->tempC_3 = tempC3;
tc->resistance_3 = r3;
}
void prepareThermistorCurve(ThermistorConf * config) {
float T1 = config->tempC_1 + KELV;
float T2 = config->tempC_2 + KELV;
float T3 = config->tempC_3 + KELV;
float L1 = log(config->resistance_1);
float L2 = log(config->resistance_2);
float L3 = log(config->resistance_3);
float Y1 = 1 / T1;
float Y2 = 1 / T2;
float Y3 = 1 / T3;
float U2 = (Y2 - Y1) / (L2 - L1);
float U3 = (Y3 - Y1) / (L3 - L1);
config->s_h_c = (U3 - U2) / (L3 - L2) * pow(L1 + L2 + L3, -1);
config->s_h_b = U2 - config->s_h_c * (L1 * L1 + L1 * L2 + L2 * L2);
config->s_h_a = Y1 - (config->s_h_b + L1 * L1 * config->s_h_c) * L1;
}
float getIntakeAirTemperature(void) {
float temperature = getTemperatureC(&engineConfiguration2->iat);
if (!isValidIntakeAirTemperature(temperature)) {
warning(OBD_PCM_Processor_Fault, "unrealistic intake temperature %f", temperature);
return NAN;
}
return temperature;
}
static void initThermistorCurve(Thermistor * t, ThermistorConf *config, int channel) {
prepareThermistorCurve(config);
t->config = config;
t->channel = channel;
}
void initThermistors(void) {
initThermistorCurve(&engineConfiguration2->clt, &engineConfiguration->cltThermistorConf,
engineConfiguration->cltAdcChannel);
initThermistorCurve(&engineConfiguration2->iat, &engineConfiguration->iatThermistorConf,
engineConfiguration->iatAdcChannel);
initialized = TRUE;
}

View File

@ -43,7 +43,7 @@ static void printIntArray(int array[], int size) {
print("\r\n");
}
void printFloatArray(char *prefix, float array[], int size) {
void printFloatArray(const char *prefix, float array[], int size) {
appendMsgPrefix(&logger);
appendPrintf(&logger, prefix);
for (int j = 0; j < size; j++)

View File

@ -1,131 +0,0 @@
/*
* @file pwm_generator_logic.c
*
* @date Mar 2, 2014
* @author Andrey Belomutskiy, (c) 2012-2014
*/
#include "pwm_generator_logic.h"
#include "engine_math.h"
static uint64_t getNextSwitchTimeUs(PwmConfig *state) {
chDbgAssert(state->safe.phaseIndex < PWM_PHASE_MAX_COUNT, "phaseIndex range", NULL);
int iteration = state->safe.iteration;
float switchTime = state->multiWave.switchTimes[state->safe.phaseIndex];
float periodMs = state->safe.periodMs;
#if DEBUG_PWM
scheduleMsg(&logger, "iteration=%d switchTime=%f period=%f", iteration, switchTime, period);
#endif
uint64_t timeToSwitchUs = (iteration + switchTime) * periodMs * 1000;
#if DEBUG_PWM
scheduleMsg(&logger, "start=%d timeToSwitch=%d", state->safe.start, timeToSwitch);
#endif
return state->safe.startUs + timeToSwitchUs;
}
static uint64_t togglePwmState(PwmConfig *state) {
#if DEBUG_PWM
scheduleMsg(&logger, "togglePwmState phaseIndex=%d iteration=%d", state->safe.phaseIndex, state->safe.iteration);
scheduleMsg(&logger, "state->period=%f state->safe.period=%f", state->period, state->safe.period);
#endif
if (state->safe.phaseIndex == 0) {
if (cisnan(state->periodMs)) {
/**
* zero period means PWM is paused
*/
return 1;
}
if (state->cycleCallback != NULL)
state->cycleCallback(state);
chDbgAssert(state->periodMs != 0, "period not initialized", NULL);
if (state->safe.periodMs != state->periodMs) {
/**
* period length has changed - we need to reset internal state
*/
state->safe.startUs = getTimeNowUs();
state->safe.iteration = 0;
state->safe.periodMs = state->periodMs;
#if DEBUG_PWM
scheduleMsg(&logger, "state reset start=%d iteration=%d", state->safe.start, state->safe.iteration);
#endif
}
}
state->stateChangeCallback(state,
state->safe.phaseIndex == 0 ? state->multiWave.phaseCount - 1 : state->safe.phaseIndex - 1);
uint64_t nextSwitchTimeUs = getNextSwitchTimeUs(state);
#if DEBUG_PWM
scheduleMsg(&logger, "%s: nextSwitchTime %d", state->name, nextSwitchTime);
#endif
uint64_t timeToSwitch = nextSwitchTimeUs - getTimeNowUs();
if (timeToSwitch < 1) {
//todo: introduce error and test this error handling warning(OBD_PCM_Processor_Fault, "PWM: negative switch time");
timeToSwitch = 10;
}
state->safe.phaseIndex++;
if (state->safe.phaseIndex == state->multiWave.phaseCount) {
state->safe.phaseIndex = 0; // restart
state->safe.iteration++;
}
return timeToSwitch;
}
static void timerCallback(PwmConfig *state) {
time_t timeToSleepUs = togglePwmState(state);
// parameter here is still in systicks
scheduleTask(&state->scheduling, timeToSleepUs, (schfunc_t) timerCallback, state);
}
/**
* Incoming parameters are potentially just values on current stack, so we have to copy
* into our own permanent storage, right?
*/
void copyPwmParameters(PwmConfig *state, int phaseCount, float *switchTimes, int waveCount, int **pinStates) {
state->multiWave.phaseCount = phaseCount;
for (int phaseIndex = 0; phaseIndex < phaseCount; phaseIndex++) {
state->multiWave.switchTimes[phaseIndex] = switchTimes[phaseIndex];
for (int waveIndex = 0; waveIndex < waveCount; waveIndex++) {
// print("output switch time index (%d/%d) at %f to %d\r\n", phaseIndex,waveIndex,
// switchTimes[phaseIndex], pinStates[waveIndex][phaseIndex]);
state->multiWave.waves[waveIndex].pinStates[phaseIndex] = pinStates[waveIndex][phaseIndex];
}
}
}
void weComplexInit(char *msg, PwmConfig *state, int phaseCount, float *switchTimes, int waveCount, int **pinStates,
pwm_cycle_callback *cycleCallback, pwm_gen_callback *stateChangeCallback) {
chDbgCheck(state->periodMs != 0, "period is not initialized");
chDbgCheck(phaseCount > 1, "count is too small");
if (phaseCount > PWM_PHASE_MAX_COUNT) {
firmwareError("too many phases in PWM");
return;
}
if (switchTimes[phaseCount - 1] != 1) {
firmwareError("last switch time has to be 1");
return;
}
chDbgCheck(waveCount > 0, "waveCount should be positive");
checkSwitchTimes(phaseCount, switchTimes);
state->multiWave.waveCount = waveCount;
copyPwmParameters(state, phaseCount, switchTimes, waveCount, pinStates);
state->cycleCallback = cycleCallback;
state->stateChangeCallback = stateChangeCallback;
state->safe.phaseIndex = 0;
state->safe.periodMs = -1;
state->safe.iteration = -1;
state->name = msg;
timerCallback(state);
}

View File

@ -1,198 +0,0 @@
/**
* @file signal_executor_single_timer.c
* @brief Single timer based implementation of signal executor.
*
* All active outputs are stored in "output_list".
* Closest in time output event is loaded in timer TIM7.
* In TIM7 timer's interrupt next closest in time output event is found and so on.
* This algorithm should reduce jitter in output signal.
*
* @todo Add test code.
*
* @date Nov 27, 2013
* @author Dobrin Georgiev
* @author Andrey Belomutskiy, (c) 2012-2014
*/
#include <stdint.h>
#include "hal.h"
#include "utlist.h"
#include "signal_executor.h"
#include "signal_executor_single_timer_algo.h"
#if EFI_WAVE_ANALYZER
#include <stm32_tim.h>
#include "wave_chart.h"
/**
* Signal executors feed digital events right into WaveChart used by Sniffer tab of Dev Console
*/
extern WaveChart waveChart;
#endif /* EFI_WAVE_ANALYZER */
#if EFI_SIGNAL_EXECUTOR_SINGLE_TIMER || defined(__DOXYGEN__)
static Mutex mtx; /* Mutex declaration */
/**
* @brief Output list
*
* List of all active output signals
* This is actually the head of the list.
* When the list is empty (initial state) the head of the list should be NULL.
* This is by design.
*/
static OutputSignal *output_list = NULL;
#if 0
/**
* @brief Schedule output
*
* Set new parameters to output event.
* When to become active and how long to stay active.
*
* @param [in, out] signal Signal related to an output.
* @param [in] delay the number of ticks before the output signal immediate output if delay is zero.
* @param [in] dwell the number of ticks of output duration.
*/
void scheduleOutput(OutputSignal *signal, int delay, int duration) {
chDbgCheck(signal->initialized, "Signal not initialized");
if(duration < 0) {
firmwareError("duration cannot be negative: %d", duration)
return;
}
signal->duration = duration;
signal->offset = delay;
/* generate an update event to reload timer's counter value, according to new set of output timings */
TIM7->EGR |= TIM_EGR_UG;
}
#endif
void scheduleTask(scheduling_s *scheduling, int delay, schfunc_t callback, void *param)
{
// return;
time_t now;
chMtxLock(&mtx);
#if 0
static bool val = 0;
val ^= 1;
palWritePad(GPIOE, 5, val);
#endif
#if 1
now = chTimeNow();
scheduling->moment = now + delay;
/* generate an update event to reload timer's counter value, according to new set of output timings */
TIM7->EGR |= TIM_EGR_UG;
#endif
chMtxUnlock();
}
#define SOURCE_DIVIDER ((STM32_HCLK) / (STM32_PCLK1))
//#pragma message VAR_NAME_VALUE(DIVIDER)
#define PRESCALLER (84)
/* Convert chSys tick to CPU tick */
#define ST2CT(st) ((st) * ((STM32_SYSCLK) / (CH_FREQUENCY)))
//#pragma message VAR_NAME_VALUE(STM32_SYSCLK)
#define CT2TT(ct) ((ct) / (SOURCE_DIVIDER) / (PRESCALLER))
#define MS2TT CT2TT(ST2CT(MS2ST(1)))
//#pragma message VAR_NAME_VALUE(MS2TT)
/**
* @brief Initialization of output scheduler.
*
* TIM7 timer initial settings.
*/
void initOutputScheduler(void)
{
/**
* @brief TIM7 initialization. Timer should run at 42MHz and before any output event registered should generate ISR event each millisecond.
*/
uint32_t initial_interval = CT2TT(ST2CT(100))-7; /// in timer ticks
//uint32_t initial_interval = CT2TT(ST2CT(MS2ST(1))); /// in timer ticks
//uint32_t initial_interval = 42000-1; /// in timer ticks
//uint32_t initial_interval = (42000/PRESCALLER)-1; /// in timer ticks
//uint32_t initial_interval = (500)-1; /// in timer ticks
#if 0
#pragma message VAR_NAME_VALUE(STM32_PCLK1)" <= "VAR_NAME_VALUE(STM32_PCLK1_MAX)
#pragma message VAR_NAME_VALUE(STM32_PPRE1)
#endif
#if 0
TIM2->PSC = STM32_PCLK1*2 / ((1<<16) * RC_PWM_FREQ); //50Hz frequency
TIM2->CCMR1 |= TIM_CCMR1_CC1S_0;//channel 1 = input on T1
TIM2->DIER |= TIM_DIER_CC1IE;//enable capture/compare interrupt
TIM2->CCER |= TIM_CCER_CC1E;//Capture/Compare output enable
nvicEnableVector(TIM2_IRQn, 12);
TIM2->CR1 |= TIM_CR1_CEN;//counter enable
#endif
RCC->APB1ENR |= RCC_APB1ENR_TIM7EN;
nvicEnableVector(TIM7_IRQn, CORTEX_PRIORITY_MASK(2));
TIM7->ARR = initial_interval; /* Timer's period */
TIM7->PSC = PRESCALLER;
TIM7->CR1 &= ~STM32_TIM_CR1_ARPE; /* ARR register is NOT buffered, allows to update timer's period on-fly. */
TIM7->DIER |= STM32_TIM_DIER_UIE; /* Interrupt enable */
TIM7->CR1 |= STM32_TIM_CR1_CEN; /* Counter enable */
chMtxInit(&mtx); /* Mutex initialization before use */
}
/**
* @brief Timer7 IRQ handler
*
* This is the core of "Single Timer" signal executor.
* Each time closest in time output event is found and TIM7 is loaded to generate IRQ at exact moment.
* FAST IRQ handler is used to minimize the jitter in output signal, caused by RTOS switching threads and by busy threads.
* Timer7 is used as output scheduler (to drive all outputs - spark plugs and fuel injectors).
*/
CH_FAST_IRQ_HANDLER(STM32_TIM7_HANDLER)
{
#define MIN(a, b) (((a) > (b)) ? (b) : (a))
#define GET_DURATION(o) ((o)->status ? (o)->signalTimerDown.moment : (o)->signalTimerUp.moment)
OutputSignal *out;
time_t next; /* Time to next output event */
time_t now;
#if 1
static bool val = 0;
static uint8_t cnt = 0;
cnt++;
cnt %= 2;
if (0 == cnt) {
val ^= 1;
palWritePad(GPIOE, 5, val);
}
#else
now = chTimeNow();
next = 0xFFFF;
LL_FOREACH(output_list, out) {
time_t n = toggleSignalIfNeeded(out, now);
/* Find closest output event in time */
next = MIN(next, n);
}
if (0xFFFF != next) {
TIM7->ARR = CT2TT(ST2CT(next)); /* Update scheduler timing */
}
#endif
TIM7->SR &= ~STM32_TIM_SR_UIF; /* Reset interrupt flag */
}
/**
* @brief Initialize output signal.
*
* @param [in] name Signal name.
* @param [in, out] signal Output signal.
* @param [in] led LED
* @param [in] xor Option to invert output signal.
*/
void initOutputSignal(OutputSignal *signal, io_pin_e ioPin)
{
//initLogging(&signal->logging, name);
signal->name = getPinName(ioPin);
signal->io_pin = ioPin;
signal->status = IDLE;
// signal->duration = 0;
signal->last_scheduling_time = 0;
registerSignal(signal);
signal->initialized = TRUE;
}
#endif /* EFI_SIGNAL_EXECUTOR_SINGLE_TIMER */

View File

@ -1,17 +0,0 @@
/**
* @file signal_executor_single_timer.h
*
* @author Dobrin Georgiev
* @author Andrey Belomutskiy, (c) 2012-2014
* @date Nov 27, 2013
*/
#ifndef SIGNAL_EXECUTOR_SINGLE_TIMER_H_
#define SIGNAL_EXECUTOR_SINGLE_TIMER_H_
#if EFI_SIGNAL_EXECUTOR_SINGLE_TIMER || defined(__DOXYGEN__)
void initOutputScheduler(void);
#endif /* EFI_SIGNAL_EXECUTOR_SINGLE_TIMER */
#endif /* SIGNAL_EXECUTOR_SINGLE_TIMER_H_ */

View File

@ -1,181 +0,0 @@
/**
* @file rpm_calculator.c
* @brief RPM calculator
*
* Here we listen to position sensor events in order to figure our if engine is currently running or not.
* Actual getRpm() is calculated once per crankshaft revolution, based on the amount of time passed
* since the start of previous shaft revolution.
*
* @date Jan 1, 2013
* @author Andrey Belomutskiy, (c) 2012-2014
*/
#include "main.h"
#include "rpm_calculator.h"
#include "trigger_central.h"
#include "engine_configuration.h"
#include "engine_math.h"
#if EFI_PROD_CODE || EFI_SIMULATOR
#include "analog_chart.h"
#endif /* EFI_PROD_CODE */
#include "wave_chart.h"
#include "rfiutil.h"
static rpm_s rpmState;
#define UNREALISTIC_RPM 30000
#define TOP_DEAD_CENTER_MESSAGE "r"
extern engine_configuration_s *engineConfiguration;
extern engine_configuration2_s *engineConfiguration2;
extern WaveChart waveChart;
static Logging logger;
/**
* @return true if there was a full shaft revolution within the last second
*/
int isRunning() {
uint64_t nowUs = getTimeNowUs();
return nowUs - rpmState.lastRpmEventTimeUs < US_PER_SECOND;
}
uint64_t getLastRpmEventTime(void) {
return rpmState.lastRpmEventTimeUs;
}
int isCranking(void) {
int rpm = getRpm();
return isCrankingR(rpm);
}
/**
* @return -1 in case of isNoisySignal(), current RPM otherwise
*/
int getRpm() {
if (!isRunning())
return 0;
return rpmState.rpm;
}
/**
* @return Current crankshaft angle, 0 to 720 for four-stroke
*/
float getCrankshaftAngle(uint64_t timeUs) {
uint64_t timeSinceZeroAngle = timeUs - rpmState.lastRpmEventTimeUs;
float cRevolutionTimeMs = getCrankshaftRevolutionTimeMs(rpmState.rpm);
return 360.0 * timeSinceZeroAngle / cRevolutionTimeMs / 1000;
}
int getRevolutionCounter(void) {
return rpmState.revolutionCounter;
}
/**
* Checks for noise on the trigger input line. Noise is detected by an unexpectedly small time gap between
* current and previous trigger input events.
*
* @return TRUE if noise is detected
*/
static int isNoisySignal(rpm_s * rpmState, uint64_t nowUs) {
uint64_t diff = nowUs - rpmState->lastRpmEventTimeUs;
return diff < 1000; // that's 1ms
}
static char shaft_signal_msg_index[15];
void addWaveChartEvent(char *name, char * msg, char *msg2) {
addWaveChartEvent3(&waveChart, name, msg, msg2);
}
/**
* @brief Shaft position callback used by RPM calculation logic.
*
* This callback is invoked on interrupt thread.
*/
static void shaftPositionCallback(ShaftEvents ckpSignalType, int index) {
itoa10(&shaft_signal_msg_index[1], index);
if (ckpSignalType == SHAFT_PRIMARY_UP) {
addWaveChartEvent("crank", "up", shaft_signal_msg_index);
} else if (ckpSignalType == SHAFT_PRIMARY_DOWN) {
addWaveChartEvent("crank", "down", shaft_signal_msg_index);
} else if (ckpSignalType == SHAFT_SECONDARY_UP) {
addWaveChartEvent("crank2", "up", shaft_signal_msg_index);
} else if (ckpSignalType == SHAFT_SECONDARY_DOWN) {
addWaveChartEvent("crank2", "down", shaft_signal_msg_index);
}
if (index != 0) {
#if EFI_PROD_CODE || EFI_SIMULATOR
if (engineConfiguration->analogChartMode == AC_TRIGGER)
acAddData(getCrankshaftAngle(getTimeNowUs()), 1000 * ckpSignalType + index);
#endif
return;
}
rpmState.revolutionCounter++;
uint64_t nowUs = getTimeNowUs();
int hadRpmRecently = isRunning();
if (hadRpmRecently) {
if (isNoisySignal(&rpmState, nowUs)) {
// unexpected state. Noise?
rpmState.rpm = NOISY_RPM;
} else {
uint64_t diff = nowUs - rpmState.lastRpmEventTimeUs;
// 60000 because per minute
// * 2 because each revolution of crankshaft consists of two camshaft revolutions
// / 4 because each cylinder sends a signal
// need to measure time from the previous non-skipped event
int rpm = (int)(60 * US_PER_SECOND / engineConfiguration->rpmMultiplier / diff);
rpmState.rpm = rpm > UNREALISTIC_RPM ? NOISY_RPM : rpm;
}
}
rpmState.lastRpmEventTimeUs = nowUs;
#if EFI_PROD_CODE || EFI_SIMULATOR
if (engineConfiguration->analogChartMode == AC_TRIGGER)
acAddData(getCrankshaftAngle(nowUs), index);
#endif
}
static scheduling_s tdcScheduler;
static char rpmBuffer[10];
static void onTdcCallback(void) {
itoa10(rpmBuffer, getRpm());
addWaveChartEvent(TOP_DEAD_CENTER_MESSAGE, rpmBuffer, "");
}
static void tdcMarkCallback(ShaftEvents ckpSignalType, int index) {
if (index == 0) {
scheduleByAngle(&tdcScheduler, engineConfiguration->globalTriggerAngleOffset, (schfunc_t) onTdcCallback, NULL);
}
}
void initRpmCalculator(void) {
initLogging(&logger, "rpm calc");
strcpy(shaft_signal_msg_index, "_");
rpmState.rpm = 0;
// we need this initial to have not_running at first invocation
rpmState.lastRpmEventTimeUs = (uint64_t)-10 * US_PER_SECOND;
registerShaftPositionListener(&shaftPositionCallback, "rpm reporter");
registerShaftPositionListener(&tdcMarkCallback, "chart TDC mark");
}
void scheduleByAngle(scheduling_s *timer, float angle, schfunc_t callback, void *param) {
float delayMs = getOneDegreeTimeMs(getRpm()) * angle;
scheduleTask(timer, MS2US(delayMs), callback, param);
}

View File

@ -1,115 +0,0 @@
/*
* @file trigger_central.c
*
* @date Feb 23, 2014
* @author Andrey Belomutskiy, (c) 2012-2014
*/
#include "main.h"
#include "trigger_central.h"
#include "trigger_decoder.h"
#include "main_trigger_callback.h"
#include "engine_configuration.h"
#include "histogram.h"
#include "rfiutil.h"
#include "listener_array.h"
#include "wave_math.h"
#include "data_buffer.h"
#if defined __GNUC__
static histogram_s triggerCallback __attribute__((section(".ccm")));
#else
static histogram_s triggerCallback;
#endif
extern engine_configuration_s *engineConfiguration;
extern engine_configuration2_s *engineConfiguration2;
// we need this initial to have not_running at first invocation
static volatile uint64_t previousShaftEventTime = (efitimems_t) -10 * US_PER_SECOND;
static IntListenerArray triggerListeneres;
static Logging logging;
static trigger_state_s triggerState;
static volatile int shaftEventCounter;
int getCrankEventCounter() {
return shaftEventCounter;
}
void registerShaftPositionListener(ShaftPositionListener handler, char *msg) {
print("registerCkpListener: %s\r\n", msg);
registerCallback(&triggerListeneres, (IntListener) handler, NULL);
}
#define HW_EVENT_TYPES 4
static int hwEventCounters[HW_EVENT_TYPES];
void hwHandleShaftSignal(ShaftEvents signal) {
chDbgCheck(engineConfiguration!=NULL, "engineConfiguration");
chDbgCheck(engineConfiguration2!=NULL, "engineConfiguration2");
int beforeCallback = hal_lld_get_counter_value();
int eventIndex = (int) signal;
chDbgCheck(eventIndex >= 0 && eventIndex < HW_EVENT_TYPES, "signal type");
hwEventCounters[eventIndex]++;
uint64_t nowUs = getTimeNowUs();
if (nowUs - previousShaftEventTime > US_PER_SECOND) {
/**
* We are here if there is a time gap between now and previous shaft event - that means the engine is not runnig.
* That means we have lost synchronization since the engine is not running :)
*/
triggerState.shaft_is_synchronized = FALSE;
}
previousShaftEventTime = nowUs;
// this is not atomic, but it's fine here
shaftEventCounter++;
/**
* This invocation changes the state of
*/
processTriggerEvent(&triggerState, &engineConfiguration2->triggerShape, &engineConfiguration->triggerConfig, signal,
nowUs);
if (!triggerState.shaft_is_synchronized)
return; // we should not propagate event if we do not know where we are
if (triggerState.current_index >= engineConfiguration2->triggerShape.shaftPositionEventCount) {
int f = warning(OBD_PCM_Processor_Fault, "unexpected eventIndex=%d", triggerState.current_index);
if(!f) {
for (int i = 0; i < HW_EVENT_TYPES; i++)
scheduleMsg(&logging, "event type: %d count=%d", i, hwEventCounters[i]);
}
} else {
/**
* Here we invoke all the listeners - the main engine control logic is inside these listeners
*/
invokeIntIntCallbacks(&triggerListeneres, signal, triggerState.current_index);
}
int afterCallback = hal_lld_get_counter_value();
int diff = afterCallback - beforeCallback;
// this counter is only 32 bits so it overflows every minute, let's ignore the value in case of the overflow for simplicity
if (diff > 0)
hsAdd(&triggerCallback, diff);
}
void printAllCallbacksHistogram(void) {
printHistogram(&logging, &triggerCallback);
}
void initTriggerCentral(void) {
initLogging(&logging, "ShaftPosition");
memset(hwEventCounters, 0, sizeof(hwEventCounters));
initHistogram(&triggerCallback, "all callbacks");
initTriggerDecoder();
clearTriggerState(&triggerState);
}

View File

@ -46,7 +46,7 @@ int getCrankEventCounter() {
* Trigger event listener would be invoked on each trigger event. For example, for a 60/2 wheel
* that would be 116 events: 58 SHAFT_PRIMARY_UP and 58 SHAFT_PRIMARY_DOWN events.
*/
void addTriggerEventListener(ShaftPositionListener handler, char *name) {
void addTriggerEventListener(ShaftPositionListener handler, const char *name) {
print("registerCkpListener: %s\r\n", name);
registerCallback(&triggerListeneres, (IntListener) handler, NULL);
}

View File

@ -16,7 +16,7 @@ typedef void (*ShaftPositionListener)(ShaftEvents signal, int index);
extern "C"
{
#endif /* __cplusplus */
void addTriggerEventListener(ShaftPositionListener handler, char *name);
void addTriggerEventListener(ShaftPositionListener handler, const char *name);
int getCrankEventCounter(void);
int isSignalDecoderError(void);
void hwHandleShaftSignal(ShaftEvents signal);

View File

@ -1,104 +0,0 @@
/**
* @file trigger_mazda.c
*
* @date Feb 18, 2014
* @author Andrey Belomutskiy, (c) 2012-2014
*
* This file is part of rusEfi - see http://rusefi.com
*
* rusEfi is free software; you can redistribute it and/or modify it under the terms of
* the GNU General Public License as published by the Free Software Foundation; either
* version 3 of the License, or (at your option) any later version.
*
* rusEfi is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without
* even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along with this program.
* If not, see <http://www.gnu.org/licenses/>.
*/
#include "trigger_mazda.h"
void initializeMazdaMiataNbShape(trigger_shape_s *s) {
triggerShapeInit(s);
/**
* cam sensor is primary, crank sensor is secondary
*/
triggerAddEvent(s, 20, T_PRIMARY, 1);
triggerAddEvent(s, 66, T_SECONDARY, TV_LOW);
triggerAddEvent(s, 70, T_SECONDARY, 1);
triggerAddEvent(s, 136, T_SECONDARY, TV_LOW);
triggerAddEvent(s, 140, T_SECONDARY, 1);
triggerAddEvent(s, 246, T_SECONDARY, TV_LOW);
triggerAddEvent(s, 250, T_SECONDARY, 1);
triggerAddEvent(s, 316, T_SECONDARY, TV_LOW);
triggerAddEvent(s, 320, T_SECONDARY, 1);
triggerAddEvent(s, 340, T_PRIMARY, TV_LOW);
triggerAddEvent(s, 360, T_PRIMARY, 1);
triggerAddEvent(s, 380, T_PRIMARY, TV_LOW);
triggerAddEvent(s, 400, T_PRIMARY, 1);
triggerAddEvent(s, 426, T_SECONDARY, TV_LOW);
triggerAddEvent(s, 430, T_SECONDARY, 1);
triggerAddEvent(s, 496, T_SECONDARY, TV_LOW);
triggerAddEvent(s, 500, T_SECONDARY, 1);
triggerAddEvent(s, 606, T_SECONDARY, TV_LOW);
triggerAddEvent(s, 610, T_SECONDARY, 1);
triggerAddEvent(s, 676, T_SECONDARY, TV_LOW);
triggerAddEvent(s, 680, T_SECONDARY, 1);
triggerAddEvent(s, 720, T_PRIMARY, TV_LOW);
s->shaftPositionEventCount = 6 + 16;
}
void configureMazdaProtegeLx(engine_configuration_s *engineConfiguration,
engine_configuration2_s *engineConfiguration2) {
trigger_shape_s *s = &engineConfiguration2->triggerShape;
triggerShapeInit(s);
// s->initialState[0] = 1;
float w = 720 / 4 * 0.215;
float a = 5;
// triggerAddEvent(s, a, T_SECONDARY, TV_LOW);
// triggerAddEvent(s, a + w, T_SECONDARY, TV_HIGH);
// a += 180;
// triggerAddEvent(s, a, T_SECONDARY, TV_LOW);
// triggerAddEvent(s, a + w, T_SECONDARY, TV_HIGH);
// a += 180;
// triggerAddEvent(s, a, T_SECONDARY, TV_LOW);
// triggerAddEvent(s, a + w, T_SECONDARY, TV_HIGH);
// a += 180;
// triggerAddEvent(s, a, T_SECONDARY, TV_LOW);
// triggerAddEvent(s, a + w, T_SECONDARY, TV_HIGH);
float z = 0.093;
a = 180;
triggerAddEvent(s, a - z * 720, T_PRIMARY, TV_HIGH);
triggerAddEvent(s, a, T_PRIMARY, TV_LOW);
a += 180;
triggerAddEvent(s, a - z * 720, T_PRIMARY, TV_HIGH);
triggerAddEvent(s, a, T_PRIMARY, TV_LOW);
a += 180;
triggerAddEvent(s, a - z * 720, T_PRIMARY, TV_HIGH);
triggerAddEvent(s, a, T_PRIMARY, TV_LOW);
a += 180;
triggerAddEvent(s, a - z * 720, T_PRIMARY, TV_HIGH);
triggerAddEvent(s, a, T_PRIMARY, TV_LOW);
// s->shaftPositionEventCount = 2 + 8;
s->shaftPositionEventCount = 8;
engineConfiguration->triggerConfig.isSynchronizationNeeded = FALSE;
}

View File

@ -1,60 +0,0 @@
/**
* @file trigger_structure.c
*
* @date Jan 20, 2014
* @author Andrey Belomutskiy, (c) 2012-2014
*
* This file is part of rusEfi - see http://rusefi.com
*
* rusEfi is free software; you can redistribute it and/or modify it under the terms of
* the GNU General Public License as published by the Free Software Foundation; either
* version 3 of the License, or (at your option) any later version.
*
* rusEfi is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without
* even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along with this program.
* If not, see <http://www.gnu.org/licenses/>.
*/
#include "main.h"
#include "trigger_structure.h"
void clearTriggerState(trigger_state_s *state) {
state->shaft_is_synchronized = FALSE;
state->toothed_previous_time = 0;
state->toothed_previous_duration = 0;
state->current_index = 0;
}
void triggerShapeInit(trigger_shape_s *trigger) {
memset(trigger, 0, sizeof(trigger_shape_s));
}
void triggerAddEvent(trigger_shape_s *trigger, float angle, trigger_wheel_e waveIndex, trigger_value_e state) {
angle /= 720;
if (trigger->size == 0) {
trigger->size = 1;
for (int i = 0; i < PWM_PHASE_MAX_WAVE_PER_PWM; i++)
trigger->wave.waves[i].pinStates[0] = trigger->initialState[i];
trigger->wave.switchTimes[0] = angle;
trigger->wave.waves[waveIndex].pinStates[0] = state;
return;
}
// if(angle!=trigger->wave.switchTimes[trigger->currentIndex])
int index = trigger->size++;
for (int i = 0; i < PWM_PHASE_MAX_WAVE_PER_PWM; i++)
trigger->wave.waves[i].pinStates[index] = trigger->wave.waves[i].pinStates[index - 1];
trigger->wave.switchTimes[index] = angle;
trigger->wave.waves[waveIndex].pinStates[index] = state;
}
void checkSwitchTimes(int size, float *switchTimes) {
for (int i = 0; i < size - 1; i++)
chDbgCheck(switchTimes[i] < switchTimes[i + 1], "invalid switchTimes");
}

View File

@ -1,171 +0,0 @@
/**
* @file hardware.c
* @brief Hardware package entry point
*
* @date May 27, 2013
* @author Andrey Belomutskiy, (c) 2012-2014
*/
#include "hardware.h"
#include "pin_repository.h"
#include "io_pins.h"
#include "rtc_helper.h"
#include "rfiutil.h"
#include "adc_inputs.h"
#include "trigger_input.h"
#include "eficonsole.h"
#include "board_test.h"
#include "mcp3208.h"
#include "HIP9011.h"
#include "can_hw.h"
#include "histogram.h"
#include "mmc_card.h"
#include "neo6m.h"
#include "lcd_HD44780.h"
#include "eficonsole_logic.h"
#include "flash_main.h"
#include "trigger_central.h"
#include "svnversion.h"
McpAdcState adcState;
static void initSpiModule(SPIDriver *driver, ioportid_t sckPort, ioportmask_t sckPin, ioportid_t misoPort,
ioportmask_t misoPin, ioportid_t mosiPort, ioportmask_t mosiPin, int af) {
mySetPadMode("SPI clock", sckPort, sckPin, PAL_MODE_ALTERNATE(af));
mySetPadMode("SPI master out", mosiPort, mosiPin, PAL_MODE_ALTERNATE(af));
mySetPadMode("SPI master in ", misoPort, misoPin, PAL_MODE_ALTERNATE(af));
}
void initSpiModules(void) {
#if STM32_SPI_USE_SPI2
// scheduleMsg(&logging, "Turning on SPI2 pins");
initSpiModule(&SPID2,
EFI_SPI2_SCK_PORT, EFI_SPI2_SCK_PIN,
EFI_SPI2_MISO_PORT, EFI_SPI2_MISO_PIN,
EFI_SPI2_MOSI_PORT, EFI_SPI2_MOSI_PIN,
EFI_SPI2_AF);
#endif
#if STM32_SPI_USE_SPI3
// scheduleMsg(&logging, "Turning on SPI3 pins");
initSpiModule(&SPID3,
EFI_SPI3_SCK_PORT, EFI_SPI3_SCK_PIN,
EFI_SPI3_MISO_PORT, EFI_SPI3_MISO_PIN,
EFI_SPI3_MOSI_PORT, EFI_SPI3_MOSI_PIN,
EFI_SPI3_AF);
#endif
}
static I2CConfig i2cfg = { OPMODE_I2C, 100000, STD_DUTY_CYCLE, };
void initI2Cmodule(void) {
print("Starting I2C module\r\n");
i2cInit();
i2cStart(&I2CD1, &i2cfg);
mySetPadMode("I2C clock", EFI_I2C_SCL_PORT, EFI_I2C_SCL_PIN,
PAL_MODE_ALTERNATE(EFI_I2C_AF) | PAL_STM32_OTYPE_OPENDRAIN);
mySetPadMode("I2C data", EFI_I2C_SDA_PORT, EFI_I2C_SDA_PIN,
PAL_MODE_ALTERNATE(EFI_I2C_AF) | PAL_STM32_OTYPE_OPENDRAIN);
}
static char txbuf[1];
static void sendI2Cbyte(int addr, int data) {
i2cAcquireBus(&I2CD1);
txbuf[0] = data;
i2cMasterTransmit(&I2CD1, addr, txbuf, 1, NULL, 0);
i2cReleaseBus(&I2CD1);
}
void initHardware() {
// todo: enable protection. it's disabled because it takes
// 10 extra seconds to re-flash the chip
//flashProtect();
/**
* histograms is a data structure for CPU monitor, it does not depend on configuration
*/
initHistogramsModule();
/**
* We need the LED_ERROR pin even before we read configuration
*/
initPrimaryPins();
/**
* this call reads configuration from flash memory or sets default configuration
* if flash state does not look right.
*/
initFlash();
initRtc();
initOutputPins();
initAdcInputs();
#if EFI_HIP_9011
initHip9011();
#endif /* EFI_HIP_9011 */
#if EFI_CAN_SUPPORT
initCan();
#endif /* EFI_CAN_SUPPORT */
// init_adc_mcp3208(&adcState, &SPID2);
// requestAdcValue(&adcState, 0);
// todo: figure out better startup logic
initTriggerCentral();
initShaftPositionInputCapture();
initSpiModules();
#if EFI_FILE_LOGGING
initMmcCard();
#endif /* EFI_FILE_LOGGING */
// initFixedLeds();
// initBooleanInputs();
#if EFI_UART_GPS
initGps();
#endif
#if ADC_SNIFFER
initAdcDriver();
#endif
#if EFI_HD44780_LCD
// initI2Cmodule();
lcd_HD44780_init();
char buffer[16];
itoa10(buffer, SVN_VERSION);
lcd_HD44780_print_string(buffer);
#endif
addConsoleActionII("i2c", sendI2Cbyte);
// while (true) {
// for (int addr = 0x20; addr < 0x28; addr++) {
// sendI2Cbyte(addr, 0);
// int err = i2cGetErrors(&I2CD1);
// print("I2C: err=%x from %d\r\n", err, addr);
// chThdSleepMilliseconds(5);
// sendI2Cbyte(addr, 255);
// chThdSleepMilliseconds(5);
// }
// }
initBoardTest();
}

View File

@ -1,65 +0,0 @@
/**
* @file pwm_generator.c
* @brief software PWM generator
*
* Software PWM implementation. Considering how low all frequencies are, we can totally afford a couple of float multiplications.
* By generating PWM programmatically we are saving the timers for better purposes. This implementation also supports generating
* synchronized waves as needed for example to emulate dual Hall-effect crankshaft position sensors.
*
*
* @date May 28, 2013
* @author Andrey Belomutskiy, (c) 2012-2014
*
*/
#include "pwm_generator.h"
#include "pin_repository.h"
#include "wave_math.h"
#include "datalogging.h"
static Logging logger;
/**
* This method controls the actual hardware pins
*/
void applyPinState(PwmConfig *state, int stateIndex) {
chDbgAssert(state->multiWave.waveCount <= PWM_PHASE_MAX_WAVE_PER_PWM, "invalid waveCount", NULL);
for (int waveIndex = 0; waveIndex < state->multiWave.waveCount; waveIndex++) {
io_pin_e ioPin = state->outputPins[waveIndex];
chDbgAssert(stateIndex < PWM_PHASE_MAX_COUNT, "invalid stateIndex", NULL);
int value = state->multiWave.waves[waveIndex].pinStates[stateIndex];
setOutputPinValue(ioPin, value);
}
}
/**
* @param dutyCycle value between 0 and 1
*/
void setSimplePwmDutyCycle(PwmConfig *state, float dutyCycle) {
state->multiWave.switchTimes[0] = dutyCycle;
}
void startSimplePwm(PwmConfig *state, char *msg, brain_pin_e brainPin, io_pin_e ioPin,
float dutyCycle, float frequency) {
GPIO_TypeDef * port = getHwPort(brainPin);
int pin = getHwPin(brainPin);
float switchTimes[] = { dutyCycle, 1 };
int pinStates0[] = { 0, 1 };
int *pinStates[1] = { pinStates0 };
state->outputPins[0] = ioPin;
outputPinRegister(msg, state->outputPins[0], port, pin);
state->periodMs = frequency2period(frequency);
weComplexInit(msg, state, 2, switchTimes, 1, pinStates, NULL, applyPinState);
}
void initPwmGenerator(void) {
initLogging(&logger, "PWM gen");
}

View File

@ -1,85 +0,0 @@
/**
* @file trigger_input.c
* @brief Position sensor hardware layer
*
* @date Dec 30, 2012
* @author Andrey Belomutskiy, (c) 2012-2014
*/
#include "trigger_input.h"
#include "wave_analyzer_hw.h"
#include "pin_repository.h"
#include "trigger_structure.h"
#include "trigger_central.h"
#include "engine_configuration.h"
static WaveReaderHw primaryCrankInput;
static WaveReaderHw secondaryCrankInput;
extern engine_configuration_s *engineConfiguration;
#if EFI_SHAFT_POSITION_INPUT
/**
* that's hardware timer input capture IRQ entry point
* 'width' events happens before the 'period' event
*/
static void shaft_icu_width_callback(ICUDriver *icup) {
int isPrimary = icup == &PRIMARY_SHAFT_POSITION_INPUT_DRIVER;
if (!isPrimary && !engineConfiguration->needSecondTriggerInput)
return;
// icucnt_t last_width = icuGetWidth(icup); so far we are fine with system time
ShaftEvents signal = isPrimary ? SHAFT_PRIMARY_UP : SHAFT_SECONDARY_UP;
hwHandleShaftSignal(signal);
}
static void shaft_icu_period_callback(ICUDriver *icup) {
int isPrimary = icup == &PRIMARY_SHAFT_POSITION_INPUT_DRIVER;
if (!isPrimary && !engineConfiguration->needSecondTriggerInput)
return;
// icucnt_t last_period = icuGetPeriod(icup); so far we are fine with system time
ShaftEvents signal = isPrimary ? SHAFT_PRIMARY_DOWN : SHAFT_SECONDARY_DOWN;
hwHandleShaftSignal(signal);
}
/**
* the main purpose of this configuration structure is to specify the input interrupt callbacks
*/
static ICUConfig shaft_icucfg = { ICU_INPUT_ACTIVE_LOW, 100000, /* 100kHz ICU clock frequency. */
shaft_icu_width_callback, shaft_icu_period_callback };
#endif
void initShaftPositionInputCapture(void) {
#if EFI_SHAFT_POSITION_INPUT
// initialize primary Input Capture Unit pin
initWaveAnalyzerDriver(&primaryCrankInput, &PRIMARY_SHAFT_POSITION_INPUT_DRIVER, PRIMARY_SHAFT_POSITION_INPUT_PORT,
PRIMARY_SHAFT_POSITION_INPUT_PIN);
/**
* Start primary Input Capture Unit using given configuration
* @see shaft_icucfg for callback entry points
*/
shaft_icucfg.channel = PRIMARY_SHAFT_POSITION_INPUT_CHANNEL;
print("initShaftPositionInputCapture 1 %s:%d\r\n", portname(PRIMARY_SHAFT_POSITION_INPUT_PORT),
PRIMARY_SHAFT_POSITION_INPUT_PIN);
icuStart(&PRIMARY_SHAFT_POSITION_INPUT_DRIVER, &shaft_icucfg);
icuEnable(&PRIMARY_SHAFT_POSITION_INPUT_DRIVER);
// initialize secondary Input Capture Unit pin
initWaveAnalyzerDriver(&secondaryCrankInput, &SECONDARY_SHAFT_POSITION_INPUT_DRIVER,
SECONDARY_SHAFT_POSITION_INPUT_PORT,
SECONDARY_SHAFT_POSITION_INPUT_PIN);
shaft_icucfg.channel = SECONDARY_SHAFT_POSITION_INPUT_CHANNEL;
print("initShaftPositionInputCapture 2 %s:%d\r\n", portname(SECONDARY_SHAFT_POSITION_INPUT_PORT),
SECONDARY_SHAFT_POSITION_INPUT_PIN);
icuStart(&SECONDARY_SHAFT_POSITION_INPUT_DRIVER, &shaft_icucfg);
icuEnable(&SECONDARY_SHAFT_POSITION_INPUT_DRIVER);
#else
print("crank input disabled\r\n");
#endif
}

View File

@ -183,10 +183,10 @@ void scheduleReset(void) {
}
extern "C" {
void onFatalError(const char *msg, char * file, int line);
void onFatalError(const char *msg, const char * file, int line);
}
void onFatalError(const char *msg, char * file, int line) {
void onFatalError(const char *msg, const char * file, int line) {
onDbgPanic();
lcdShowFatalMessage((char *) msg);
if (!main_loop_started) {
@ -235,14 +235,14 @@ int hasFatalError(void);
void onFatalError(const char *msg, char * file, int line);
char *dbg_panic_file;
const char *dbg_panic_file;
int dbg_panic_line;
extern "C" {
void chDbgPanic3(const char *msg, char * file, int line);
void chDbgPanic3(const char *msg, const char * file, int line);
}
void chDbgPanic3(const char *msg, char * file, int line) {
void chDbgPanic3(const char *msg, const char * file, int line) {
if (hasFatalError())
return;
dbg_panic_file = file;
@ -276,5 +276,5 @@ void firmwareError(const char *fmt, ...) {
}
int getRusEfiVersion(void) {
return 20140429;
return 20140430;
}

View File

@ -79,7 +79,7 @@ int histogramGetIndex(int64_t value) {
/**
* @brief Reset histogram_s to orignal state
*/
void initHistogram(histogram_s *h, char *name) {
void initHistogram(histogram_s *h, const char *name) {
if(strlen(name) > sizeof(h->name) - 1)
firmwareError("Histogram name [%s] too long", name);
strcpy(h->name, name);

View File

@ -37,7 +37,7 @@ typedef struct {
void initHistogramsModule(void);
int histogramGetIndex(int64_t value);
void initHistogram(histogram_s *h, char *name);
void initHistogram(histogram_s *h, const char *name);
void hsAdd(histogram_s *h, int64_t value);
int hsReport(histogram_s *h, int* report);