auto-sync

This commit is contained in:
rusEfi 2016-12-27 11:01:26 -05:00
parent d8ce0556c4
commit cae31c8b67
6 changed files with 14 additions and 14 deletions

View File

@ -533,14 +533,14 @@ extern pin_output_mode_e DEFAULT_OUTPUT;
static void initStatisLeds() {
#if EFI_PROD_CODE || defined(__DOXYGEN__)
outputPinRegisterExt2("communication status 1", &communicationPin,
outputPinRegisterExt2("led: comm status", &communicationPin,
engineConfiguration->communicationPin, &DEFAULT_OUTPUT);
#endif
#if EFI_WARNING_LED || defined(__DOXYGEN__)
outputPinRegister("warning", &warningPin, LED_WARNING_PORT,
outputPinRegister("led: warning status", &warningPin, LED_WARNING_PORT,
LED_WARNING_PIN);
outputPinRegisterExt2("is running status", &runningPin, engineConfiguration->runningPin,
outputPinRegisterExt2("led: running status", &runningPin, engineConfiguration->runningPin,
&DEFAULT_OUTPUT);
#endif /* EFI_WARNING_LED */
}

View File

@ -59,6 +59,7 @@ public:
void setConfig(thermistor_conf_s *config);
void prepareThermistorCurve(thermistor_conf_s *tc);
bool isLinearSensor();
float getKelvinTemperatureByResistance(float resistance);
float s_h_a;
float s_h_b;
float s_h_c;

View File

@ -49,14 +49,13 @@ float getVoutInVoltageDividor(float Vin, float r1, float r2) {
return r2 * Vin / (r1 + r2);
}
float getKelvinTemperature(float resistance, ThermistorMath *tm) {
float ThermistorMath::getKelvinTemperatureByResistance(float resistance) {
if (resistance <= 0) {
//warning("Invalid resistance in getKelvinTemperature=", resistance);
return 0.0f;
}
float logR = logf(resistance);
return 1 / (tm->s_h_a + tm->s_h_b * logR + tm->s_h_c * logR * logR * logR);
return 1 / (s_h_a + s_h_b * logR + s_h_c * logR * logR * logR);
}
float convertCelsiustoF(float tempC) {
@ -90,7 +89,7 @@ float getTemperatureC(ThermistorConf *config, ThermistorMath *tm) {
float voltage = getVoltageDivided("term", config->adcChannel);
float resistance = getResistance(config, voltage);
float kelvinTemperature = getKelvinTemperature(resistance, tm);
float kelvinTemperature = tm->getKelvinTemperatureByResistance(resistance);
return convertKelvinToCelcius(kelvinTemperature);
}
@ -216,7 +215,7 @@ void setCommonNTCSensor(ThermistorConf *thermistorConf) {
#if EFI_PROD_CODE
static void testCltByR(float resistance) {
// we expect slowPeriodicCallback to already update configuration in the curve helper class see setConfig
float kTemp = getKelvinTemperature(resistance, &engine->engineState.cltCurve);
float kTemp = engine->engineState.cltCurve.getKelvinTemperatureByResistance(resistance);
scheduleMsg(logger, "for R=%f we have %f", resistance, (kTemp - KELV));
}
#endif

View File

@ -41,13 +41,13 @@ void initTriggerEmulator(Logging *sharedLogger, Engine *engine) {
#if EFI_PROD_CODE
// todo: refactor, make this a loop
outputPinRegisterExt2("distributor ch1", triggerSignal.outputPins[0], boardConfiguration->triggerSimulatorPins[0],
outputPinRegisterExt2("trg emulator ch1", triggerSignal.outputPins[0], boardConfiguration->triggerSimulatorPins[0],
&boardConfiguration->triggerSimulatorPinModes[0]);
outputPinRegisterExt2("distributor ch2", triggerSignal.outputPins[1], boardConfiguration->triggerSimulatorPins[1],
outputPinRegisterExt2("trg emulator ch2", triggerSignal.outputPins[1], boardConfiguration->triggerSimulatorPins[1],
&boardConfiguration->triggerSimulatorPinModes[1]);
outputPinRegisterExt2("distributor ch3", triggerSignal.outputPins[2], boardConfiguration->triggerSimulatorPins[2],
outputPinRegisterExt2("trg emulator ch3", triggerSignal.outputPins[2], boardConfiguration->triggerSimulatorPins[2],
&boardConfiguration->triggerSimulatorPinModes[2]);
#endif /* EFI_PROD_CODE */

View File

@ -96,7 +96,7 @@ void outputPinRegister(const char *msg, OutputPin *output, ioportid_t port, uint
extern OutputPin checkEnginePin;
void initPrimaryPins(void) {
outputPinRegister("LED_ERROR", &enginePins.errorLedPin, LED_ERROR_PORT, LED_ERROR_PIN);
outputPinRegister("led: ERROR status", &enginePins.errorLedPin, LED_ERROR_PORT, LED_ERROR_PIN);
}
void initOutputPins(void) {

View File

@ -92,7 +92,7 @@ void testSensors(void) {
{
setThermistorConfiguration(&tc, 32, 9500, 75, 2100, 120, 1000);
tm.setConfig(&tc.config);
float t = getKelvinTemperature(2100, &tm);
float t = tm.getKelvinTemperatureByResistance(2100);
assertEquals(75 + KELV, t);
assertEquals(-0.003, tm.s_h_a);
@ -106,7 +106,7 @@ void testSensors(void) {
setThermistorConfiguration(&tc, 0, 32500, 30, 7550, 100, 700);
tm.setConfig(&tc.config);
float t = getKelvinTemperature(38000, &tm);
float t = tm.getKelvinTemperatureByResistance(38000);
assertEquals(-2.7983, t - KELV);
assertEqualsM("A", 0.0009, tm.s_h_a);