Skip to content

Commit cff3806

Browse files
committed
After tests ... commit
1 parent 8a52429 commit cff3806

File tree

10 files changed

+295
-649
lines changed

10 files changed

+295
-649
lines changed

MID/MID.ino

Lines changed: 19 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515

1616
#include <Arduino.h>
1717
#include <SPI.h>
18+
#include <Wire.h>
1819
#include <OneWire.h>
1920
#include <MenuBackend.h>
2021
#include <DallasTemperature.h>
@@ -51,12 +52,16 @@ const uint8_t SAV_PIN_DTC = A7; // Plug:16 Detect ignition key off stat
5152
//
5253
// Engine pins
5354
const uint8_t ENG_CLT_PIN = A0; // Plug:31 Engine Temp. [may be capacitor is needed]
55+
const uint8_t BRK_LGH_PIN = 11; // Plug: Brake light detection
5456
const uint8_t RPM_SNS_PIN = 2; // Plug:6 RPM [attachInterrupt]
5557
const uint8_t SPD_SNS_PIN = 3; // Plug:12 Speed sensor hub [attachInterrupt]
5658
const uint8_t ECU_SGN_PIN = 19; // Plug:27 ECU signal
5759
//
58-
// lpg old pin: A4
59-
const uint8_t LPG_LVL_PIN = A5; // None Fuel LPG switch
60+
// 4 Pins LPG fuel switch/gauge
61+
// Two wires are for power supply, other two wires is for displayed information.
62+
// * Check wiring diagram in order to determine wiring
63+
const uint8_t LPG_LVL_PIN = A5; // None Tank fuel level
64+
const uint8_t LPG_SWT_PIN = A4; // None Fuel switcher
6065
//
6166
// Display dim pins
6267
const uint8_t DIM_PIN_VAL = A10; // Plug:7 Display back-light
@@ -80,13 +85,15 @@ const uint8_t ALP_PIN_VOL = 14;
8085
// volatile Vehicle time travel
8186
//volatile float CUR_VTT = 0;
8287
float TTL_TTD; // Total travel distance
83-
float TTL_TLC; // Total Liters per hour consumed
84-
float TTL_CLC; // Total Consumption trip
88+
float TTL_LPG; // Total LPG Travel Liters
89+
float TTL_BNZ; // Total BNZ Travel Liters
90+
float CRT_LPG; // Current LPG Consumption trip
91+
float CRT_BNZ; // Current BNZ Consumption trip
8592
float TTL_WRD; // Total Work distance [changing the timing belt wear collection ]
86-
8793
//
8894
// Change state of shutdown "press to save"
8995
#define SHUTDOWN_SAVE_STATE LOW
96+
#define SHUTDOWN_SAVE_BUTTON 9
9097
//
9198
// LiquidCrystal library
9299
// Including from Arduino IDE
@@ -159,7 +166,7 @@ void setup() {
159166

160167
//
161168
// Shutdown setupEngine
162-
shutDown.setup(SAV_PIN_CTR, SAV_PIN_DTC, BTN_PIN_UP, ADT_ALR_PIN);
169+
shutDown.setup(SAV_PIN_CTR, SAV_PIN_DTC, ADT_ALR_PIN);
163170
//
164171
// Turn lcdDisplay off
165172
lcd.noDisplay();
@@ -211,10 +218,15 @@ void setup() {
211218
eepRom.loadCurrentData();
212219

213220
pinMode(18, INPUT_PULLUP);
221+
222+
pinMode(LPG_LVL_PIN, INPUT);
223+
pinMode(LPG_SWT_PIN, INPUT);
214224
}
215225

216226

217227
void loop() {
228+
229+
218230
//
219231
// Set new time every begin
220232
ampInt.setTimer(millis());
@@ -226,6 +238,7 @@ void loop() {
226238
Serial.print("Window washer value: ");
227239
Serial.println(digitalRead(18));
228240
}
241+
229242
//
230243
// Listen engine
231244
carSens.listener();
@@ -314,5 +327,3 @@ static void playWelcomeScreen() {
314327
delay(1500);
315328
lcd.clear();
316329
}
317-
318-

MID/lib/CarSens.h

Lines changed: 20 additions & 38 deletions
Original file line numberDiff line numberDiff line change
@@ -38,10 +38,11 @@
3838
//
3939
// ECU Consumption signal mul by *10
4040
// next 3815
41-
#define ECU_CORRECTION 376 // <sens:200> 168 || <sens:150> 224 || <sens:100> 336 || <sens:50> 648
41+
#define ENG_CORRECTION 4 // Divider pure voltage
42+
#define ECU_CORRECTION 346 // <sens:200> 168 || <sens:150> 224 || <sens:100> 336 || <sens:50> 648
4243
#define VSS_CORRECTION 3.767 // <sens:200> 3.835232 || <sens:150> 5 || <sens:100> 7.670464 || <sens:50> 15.340928
4344
#define RPM_CORRECTION 33.767 // <sens:200> 33.767 || <sens:150> 50 || <sens:100> 67.534 || <sens:50> 135.068
44-
#define DST_CORRECTION 15400.11 // <sens:200> 15260.11 || <sens:150> 20266.66 || <sens:100> 30400 || <sens:50> 60791.24
45+
#define DST_CORRECTION 15600.11 // <sens:200> 15260.11 || <sens:150> 20266.66 || <sens:100> 30400 || <sens:50> 60791.24
4546
// DST
4647
// ===============
4748
// cur test +40 = 15240.11
@@ -207,6 +208,7 @@ class CarSens {
207208
//
208209
// LPG tank
209210
int CUR_LTK;
211+
int FUEL_STATE = 0;
210212
//
211213
unsigned long
212214
CUR_VTT,// Travel time
@@ -487,15 +489,8 @@ class CarSens {
487489
}
488490

489491
int getTnkLpgPer() {
490-
//
491-
// I received some additional information from the manufacturer of the fuel gauge if this changes anything:
492-
// The fuel input is approximately 4.5V through 150 ohm.
493-
// 73 ohm sender voltage would be 4.5*73/(150+73) = 1.5V
494-
// 10 ohm sender voltage would be 4.5*10/(150+10) = 0.3V
495-
// 240 ohm sender voltage would be 4.5*240/(150+240) = 2.8V
496-
// 33 ohm sender voltage would be 4.5*33/(150+33) = 0.8V
497-
// So in my case 20k fuel gauge
498-
return (int) map(CUR_LTK, 10, 55, 0, 100);
492+
493+
return (int) CUR_LTK;/* map(CUR_LTK, 10, 100, 0, 100)*/
499494
}
500495

501496
int getTnkBnz() {
@@ -789,15 +784,15 @@ void CarSens::speedingAlarms() {
789784
speedAlarmCursor = ENABLE_SPEED_HW;
790785
}
791786

792-
if (_amp->isSec() && CUR_VSS > VSS_ALARM_CITY_SPEED && speedAlarmCursor == ENABLE_SPEED_CT) {
787+
if (_amp->is5Seconds() && CUR_VSS > VSS_ALARM_CITY_SPEED && speedAlarmCursor == ENABLE_SPEED_CT) {
793788
tone(ADT_ALR_PIN, 4000, 200);
794789
}
795790

796-
if (_amp->isSec() && CUR_VSS > VSS_ALARM_VWAY_SPEED && speedAlarmCursor == ENABLE_SPEED_VW) {
791+
if (_amp->is10Seconds() && CUR_VSS > VSS_ALARM_VWAY_SPEED && speedAlarmCursor == ENABLE_SPEED_VW) {
797792
tone(ADT_ALR_PIN, 4000, 200);
798793
}
799794

800-
if (_amp->isSec() && CUR_VSS > VSS_ALARM_HWAY_SPEED && speedAlarmCursor == ENABLE_SPEED_HW) {
795+
if (_amp->isMinute() && CUR_VSS > VSS_ALARM_HWAY_SPEED && speedAlarmCursor == ENABLE_SPEED_HW) {
801796
tone(ADT_ALR_PIN, 4000, 200);
802797
}
803798

@@ -870,12 +865,16 @@ void CarSens::sensDim() {
870865
*/
871866
void CarSens::sensTnk() {
872867

868+
//
869+
// LPG tank
870+
// Full tank reading 805
871+
// Empty tank reading ---
873872
if (_amp->isMax()) {
874873
indexLpgTank++;
875874
int lpgTankLevel = analogRead(pinLpgTank);
876875
Serial.print("Tank level: ");
877876
Serial.println(lpgTankLevel);
878-
lpgTankLevel = (int) ((5.00 / 1023.00) * lpgTankLevel) * 10;
877+
lpgTankLevel = int(lpgTankLevel - 805);
879878

880879

881880
Serial.print("after tank level: ");
@@ -884,7 +883,6 @@ void CarSens::sensTnk() {
884883
if (lpgTankLevel > 0) {
885884
containerLpgTank = containerLpgTank + lpgTankLevel;
886885
CUR_LTK = int(containerLpgTank / indexLpgTank);
887-
888886
CUR_LTK = lpgTankLevel;
889887

890888
}
@@ -899,34 +897,17 @@ void CarSens::sensTnk() {
899897
* Engine temperature
900898
*/
901899
void CarSens::sensEnt() {
902-
// if (_amp->isLow()) {
903-
904-
int val = analogRead(pinTemp);
905-
if (val > 800) {
906-
engineTempHigh++;
907-
}
908-
engineTempIndex++;
909-
910-
911900
if (_amp->isSens()) {
912-
CUR_ENT = int(engineTempIndex - engineTempHigh);
901+
int val = analogRead(pinTemp);
902+
CUR_ENT = int(val / ENG_CORRECTION);
913903

914904
#ifdef DEBUG_ENG_TEMP
915905

916906
Serial.print("Engine temperature: ");
917907
Serial.print(val);
918-
Serial.print(" / index: ");
919-
Serial.print(engineTempIndex);
920-
Serial.print(" / high: ");
921-
Serial.print(engineTempHigh);
922908
Serial.print(" / result:");
923909
Serial.println(CUR_ENT);
924910
#endif
925-
926-
engineTempIndex = 0;
927-
engineTempHigh = 0;
928-
929-
930911
}
931912
}
932913

@@ -1103,7 +1084,7 @@ void CarSens::sensCns() {
11031084
}
11041085
//
11051086
// Convert to float
1106-
TTL_CLC = float(TTL_FL_CNS * 0.00001);// L/h, comes from the /10000*100
1087+
CRT_LPG = float(TTL_FL_CNS * 0.00001);// L/h, comes from the /10000*100
11071088
}
11081089

11091090

@@ -1136,9 +1117,10 @@ void CarSens::sensIfc() {
11361117

11371118
// if maf is 0 it will just output 0
11381119
if (CUR_VSS < CONS_TGL_VSS) {
1139-
cons = long(long(maf * getIfcFuelVal()) / 1000 * 0.001); // L/h, do not use float so mul first then divide
1120+
cons = long(
1121+
long(maf * getIfcFuelVal() / 2) / 1000 * 0.001); // L/h, do not use float so mul first then divide
11401122
} else {
1141-
cons = long(maf * getIfcFuelVal()) / delta_dist; // L/100kmh, 100 comes from the /10000*100
1123+
cons = long(maf * getIfcFuelVal() / 2) / delta_dist; // L/100kmh, 100 comes from the /10000*100
11421124
}
11431125
// pass
11441126
// Current Instance consumption

0 commit comments

Comments
 (0)