Skip to content

Commit

Permalink
pre-alpha
Browse files Browse the repository at this point in the history
Initial, uncalibrated values for basic gauges (no tach or mp).

Ready for thermocouple test.
  • Loading branch information
tomcourt authored and tomcourt committed Jun 26, 2017
1 parent d926332 commit b51171e
Show file tree
Hide file tree
Showing 6 changed files with 183 additions and 53 deletions.
18 changes: 10 additions & 8 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ Browse to 192.168.0.111, confirm Engiuno panel shows up.

### Arduino

The Leonardo is rated to run from 6-20 volts although they suggest keeping it between 7-12 volts. They claim to worry about the voltage regulator overheating and 'damaging the board', but the regulator chip (88% efficient) does have a thermal shutdown feature at 150 deg C. The text appears to be a carry over from previous Arduino's which used a linear supply. **TBD** if heating is a problem. **TBD** if voltage sag during starting is a problem.
The Leonardo is rated to run from 6-20 volts although they suggest keeping it between 7-12 volts. They claim to worry about the voltage regulator overheating and 'damaging the board', but the regulator chip (88% efficient) does have a thermal shutdown feature at 150 deg C. The text appears to be a carry over from previous Arduino's which used a linear supply. Typical power draw is 70mA for Arduino, no more than 90mA for pull ups, TBD for auxiliary display. **TBD** if heating is a problem. **TBD** if voltage sag during starting is a problem.

The supply is rated for 1000 ma. The Leonardo uses 82 mA. Testing will need to be done to determine actual power used.

Expand Down Expand Up @@ -125,17 +125,17 @@ The main webpage has a timer running in Javascript on the tablet that invokes a

### Sensors

The sensor system is fairly generic but currently only Van's Aircraft engine sensors have predefined configurations. The resistive sensors will have a 240 ohm(1%) pull up to Vcc. This will require up to 18 ma per sensor, or for the typical 5 sensors (fuel x 2, oil-p, oil-t, fuel-p) 90 ma total. This provides a good compromise between power usage, heat and loss of resolution. This provides 9 bits of resolution. To limit resistor heating to reasonable levels, .5 watt resistors should be used. Resistor temp. rise should be no more than 100 deg. C in free air. A resistance < 16 ohms will register as a short failure. > 480 ohms will register as an open failure. To convert from ADC units to ohms use this formula `ohms = 240 * (adc / (1024-adc))`, this will require long divided by long division unfortunately or a lookup/interpolation table.
The sensor system is fairly generic but currently only Van's Aircraft engine sensors have predefined configurations. The resistive sensors will have a 240 ohm(1%) pull up to +5V. This will require up to 18 ma per sensor, or for the typical 5 sensors (fuel x 2, oil-p, oil-t, fuel-p) 90 ma total. This provides a good compromise between power usage, heat and loss of resolution. This provides 9 bits of resolution. To limit resistor heating to reasonable levels, .5 watt resistors should be used. Resistor temp. rise should be no more than 100 deg. C in free air. A resistance significantly out of range will mark the sensor inoperative. To convert from ADC units to ohms use this formula `ohms = 240 * (adc / (1024-adc))`, this will require long divided by long division unfortunately or a lookup/interpolation table.

All but the oil-temp sensor are 33.5-240 ohm sensors. These usually scale linearly by resistance. Some may scale closer to ADC counts as follow: zero=240ohm/511adc, half=103ohm/716adc, full=33.5ohm/898adc. The oil temperature sensor (for a Rochester 3080-37) as follows (degF=ohms): 100=497, 150=179, 200=72, 250=34. This is a thermistor. Using a Steinhar-Hart calculator the conversion formula becomes `degrees Kelvin = 1 / (0.0016207535760566691 + 0.0002609330007304247 * log(R) + -1.0278556187396396e-7 * log(R)^3)`. A lookup table will certainly be required.
All but the oil-temp sensor are 240-33.5 ohm sensors. These usually scale linearly by resistance. For those that don't, a custom interpolation table may be required. The oil temperature sensor (for a Rochester 3080-37) as follows (degF=ohms): 100=497, 150=179, 200=72, 250=34. This is a thermistor. Using a Steinhar-Hart calculator the conversion formula becomes `degrees Kelvin = 1 / (0.0016207535760566691 + 0.0002609330007304247 * log(R) + -1.0278556187396396e-7 * log(R)^3)`. An interpolation table is used to convert this.

For resistive sensors still attached to the gauge, the gauge itself provides the pull up resistance and voltage. For Vans Aircraft engine instruments the pull up is 5 volts and the resistor is about 227 ohms(measured externally, internally the resistor appears to be 240 ohms, 5%). The pin can be directly connected if the voltage can't exceed Vcc by more than .5v. Otherwise a series resistor as discussed later could be attached to isolate the pin.
For resistive sensors still attached to the gauge, the gauge itself provides the pull up resistance and voltage. For Vans Aircraft engine instruments the pull up is 5 volts and the resistor is about 227 ohms(measured externally, internally the resistor appears to be 240 ohms, 5%). The pin can be directly connected if the voltage can't exceed Vcc by more than .5v. Otherwise a 15K series resistor could be attached to help isolate the pin.

For thermocouple sensors the board will detect both open and short. It directly reads out in degrees C (.25 resolution). This will optionally be converted to F. To support J style thermocouples, the C output will be adjusted by taking the thermocouple reading (before the CJT adjustment) `newC = oldC * 46677 / 65536`

For the voltage sensor a 4:1 voltage divider consisting of a 1k and 3.01k (1%) resistor is used. This limits the draw to .1 watt at 20 volts or .05 at 14 volts.

Typical sensors are Stewart Warner. The tachometer is supplied with 12 volts, a hall effect sensor that returns 5 volt pulses, 8/16 PPR, TBD. The manifold pressure sensor is believed to be 0-100mV ratio-metric.
Typical sensors are Stewart Warner. The tachometer is supplied with 12 volts, a hall effect sensor that returns 5 volt pulses, 8/16 PPR, TBD. The manifold pressure sensor is believed to be 0-100mV ratio-metric. Either a better ADC (Adafruit ADS1015) will be needed or a new manifold pressure sensor.

For a sensor that might contain a voltage higher than Vcc using a voltage divider as used on the voltage sensor will cause a significant load which could create issues if still attached to a backup gauge. Alternatively a 15K ohm resistor between the sensor and the pin will safely clip voltages between 20.5 and -15.5 volts. The goal here is to limit the internal clamping diodes to no more than 1ma after the .7 volt diode drop.

Expand Down Expand Up @@ -173,8 +173,7 @@ Other messages would include:
* `Ot`
* `FP`
* `Cht`
* `Shrt` short circuit, shown on second line
* `OPEn` open circuit, shown on second line
* `inoP` open or short circuit, shown on second line

To prevent having to re-acknowledge warnings there would be both temporal and range hysteresis built in.

Expand All @@ -189,18 +188,21 @@ To prevent having to re-acknowledge warnings there would be both temporal and ra
* 3K ohm 1% resistor - Digikey 3.01KXBK-ND
* 1k ohm 1% resistor - Digikey 1.00KXBK-ND
* 10 input screw terminal block - Digikey ED10567-ND
* .025 square breakaway headers - Digikey 929647-04-35-ND - will probably work well on the thermocouple board w/o a header extension.
* .025 square breakaway headers - Digikey 929834-04-36-ND (tin) or 929647-04-36-ND (gold) - will probably work well on the thermocouple board w/o a header extension.
* jack for auxiliary display 6 pin - Digikey 455-2271-ND
* header for auxiliary display 6 pin - Digikey 455-2218-ND
* contacts for header x 10 - Digikey 455-1135-1-ND
* pushbutton switch - Digikey EG2015-ND
* K style thermocouple wire, 24-26 gauge, EBay
* Bigger filter caps?, thermocouples Digikey 1276-1246-1-ND
* Enclosure - Electrical box - B108R - Home Depot

### Future stuff
* It may be possible to support 2 thermocouples without the thermocouple multiplexer shield by using the differential mode ADC, 40x gain and a thermistor. Only 8 bits are usable with 40x. 488 uV per count works out to 21.5 deg. F resolution with a K type thermocouple. The 2.56 volt internal reference would double the resolution and oversampling could probably double it again.
* The Arduino Yun would support airplanes lacking a Stratux. The code would need to use the 'bridge' objects instead of the ethernet objects. Use #ifdef AVR_YUN to flex the code.
* Themes - a dark theme could be created easily enough by adjusting the styles. A larger text theme for the gauges would involve more defines and stringizing them for the SVG.
* Warning lights instead of auxillary display? A board with 4 caution/warning LEDs (red/green common cathode [bicolor LED]). Turning red and green on produces yellow. Alternatively use a module like the [BOB-13884] to provide 3 RGB LED's.
* Create another TCP or UDP port that can be read from the Stratux (perhaps with netcat). This would be a comma separated text stream of engine data to be logged.
* Use digitalFastWrite for smaller code - https://github.com/NicksonYap/digitalWriteFast
* Create mult16x16to32 function for smaller code - https://github.com/rekka/avrmultiplication

Expand Down
19 changes: 11 additions & 8 deletions enguino/config.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,10 @@ const char *red = "red";
#define MX(x) (int)((x)*(1<<divisor) + 0.5)
#define GMX(range) (int)(1000.0 / (range) * (1<<divisor) + 0.5)
#define GB(low) (int)(-((low) + 0.5))
#define ADCtoV (5.0/1023.0) // multiply this by divider to get DC volts
#define ADCtoDivV (5.0/1023.0) // multiply this by adc input to get DC volts
#define ADCtoV10 (57 * ADCtoDivV) // Using 1:5.7 divider for now !!!
#define V10toADC (1/(57 * ADCtoDivV)) // Using 1:5.7 divider for now !!!


const int thermistorADC[] = {};
const int thermistorC10[] = {};
Expand All @@ -25,14 +28,14 @@ const int resist240p1000[] = {};
// Use GB() and GMX to set the graphs b and m values based on lowest input and input range (hi-low) respectively.
//
const Sensor opS = { st_r240to33, 0, MX(0.1), 0, MX(1.0)}; // 0 - 100
const Sensor otS = { st_r240to33, 50, MX(0.2), 0, MX(1.0)}; // 50 - 250
const Sensor vtS = { st_volts, 0, MX(ADCtoV*40), 0, 8008}; // 100 - 160 (10 - 16)
const Sensor otS = { st_thermistor, 32, MX(1.8*.1), GB((50-32)*5./9.*10), GMX(200*10*5./9.)}; // 50 - 250
const Sensor vtS = { st_volts, 0, MX(ADCtoV10), GB(100*V10toADC), GMX(60*V10toADC)}; // 100 - 160 (10 - 16)
const Sensor fpS = { st_r240to33, 0, MX(0.1), 0, MX(1.0)}; // 0 - 100 (0 - 10)
const Sensor flS = { st_r240to33, 0, MX(0.16), 0, MX(1.0)}; // 0 - 160 (0 - 16)
const Sensor taS = { st_tachometer, 0, 12000, 0, 8008 }; // 0 - 3000
const Sensor maS = { st_volts, 100, 2000, 0, 8008}; // 100 - 350 (10 - 35)
const Sensor chS = { st_thermocouple, 32, MX(1.8/4), GB((100-32)*5./9.*4), GMX(400*5./9.*4)}; // 100 - 500, input is .25 C, convert to whole F
const Sensor egS = { st_thermocouple, 32, MX(1.8/4), GB((1000-32)*5./9.*4), GMX(600*5./9.*4)}; // 1000 - 1600,input is .25 C, convert to to whole F
const Sensor chS = { st_k_type_tc, 32, MX(1.8/4), GB((100-32)*5./9.*4), GMX(400*5./9.*4)}; // 100 - 500, input is .25 C, convert to whole F
const Sensor egS = { st_k_type_tc, 32, MX(1.8/4), GB((1000-32)*5./9.*4), GMX(600*5./9.*4)}; // 1000 - 1600,input is .25 C, convert to to whole F

// Labels
// ------
Expand Down Expand Up @@ -79,9 +82,9 @@ int chRP[] = { 1000, 6000, 7940, 8000 };
#define bank 3500 // bank of misc vertical gauges
const Gauge gauges[] = {
// x, y, style, decimal, label1, label2, units, labVal, labPt,num, regClr, regPt, num, sensor, pin
{bank+0, 0, gs_vert, 0, "OIL", "PRES", "psi", opLV, opLP, N(opLV), opRC, opRP, N(opRC), &opS, 0},
{bank+1750, 0, gs_vert, 0, "OIL", "TEMP", "&deg;F", otLV, otLP, N(otLV), otRC, otRP, N(otRC), &otS, 1},
{bank+3500, 0, gs_vert, 1, "", "VOLT", "volt", vtLV, vtLP, N(vtLV), vtRC, vtRP, N(vtRC), &vtS, 2},
{bank+0, 0, gs_vert, 0, "OIL", "PRES", "psi", opLV, opLP, N(opLV), opRC, opRP, N(opRC), &opS, 1},
{bank+1750, 0, gs_vert, 0, "OIL", "TEMP", "&deg;F", otLV, otLP, N(otLV), otRC, otRP, N(otRC), &otS, 2},
{bank+3500, 0, gs_vert, 1, "", "VOLT", "volt", vtLV, vtLP, N(vtLV), vtRC, vtRP, N(vtRC), &vtS, 0},
{bank+5250, 0, gs_vert, 1, "FUEL", "PRES", "psi", fpLV, fpLP, N(fpLV), fpRC, fpRP, N(fpRC), &fpS, 3},
{bank+7000, 0, gs_pair, 1, "FUEL", "", "gal", flLV, flLP, N(flLV), flRC, flRP, N(flRC), &flS, 4}, // pins 4 and 5
{100, 0, gs_round, 0, "TACH", "", "rpm", 0, 0, 0, taRC, taRP, N(taRC), &taS, -1},
Expand Down
16 changes: 13 additions & 3 deletions enguino/egTypes.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,15 +2,25 @@

#define N(x) sizeof(x)/sizeof(x[0])

#define FAULT -32768

typedef const char * string;

enum SensorType {st_r240to33, st_thermistor, st_volts, st_thermocouple, st_tachometer, st_fuelflow};
typedef struct {
int start;
byte n;
const byte *log2diff;
const int *result;
} InterpolateTable;

enum SensorType {st_r240to33, st_thermistor, st_volts, st_k_type_tc, st_j_type_tc, st_tachometer, st_fuel_flow};
// st_r240to33 - 0 - 1000 proportional resistive sensor
// st_thermistor - 0 - 1500 degrees C. in tenths
// st_volts - 0 - 1023 ADC units 4.88 mV/per
// st_thermocouple - 0 - 4000 0-1000 degrees C. in quarters
// st_k_type_tc - 0 - 4000 0-1000 degrees C. in quarters
// st_j_type_tc - 0 - 4000 0-1000 degrees C. in quarters
// st_tachometer
// st_fuelflow
// st_fuel_flow

// for K style in deg. C, use a multiply of 4096 (0.25), offset 0
// for K style in deg. F, use a multiplier of 7373 (0.25 * 1.8), offset -32
Expand Down
82 changes: 56 additions & 26 deletions enguino/enguino.ino
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,8 @@
// sketches don't like typdef's so they are in in this header file instead
#include "egTypes.h"

#include "utility.h"

// configuration of sensors and layout of the gauges
#include "config.h"

Expand All @@ -25,9 +27,7 @@ IPAddress ip(192, 168, 0, 111);
EthernetServer server(80);
EthernetClient client;

int readPin(int p);

#define FAULT -32768
int readGauge(const Gauge *g, byte n = 0);

// Performance 'print' functions to ethernet 'client' (includes flush)
#include "printEthernet.h"
Expand All @@ -41,38 +41,68 @@ int readPin(int p);
// Measure thermocouple tempertaures in the background
#include "tcTemp.h"


int readPin(int p) {
if (p < 0)
return FAULT;

#ifdef RANDOM_SENSORS
InterpolateTable thermistor = {
64, 32,
(byte []) {
3, 3, 3, 3, 3, 3, 4, 4, 4, 4, 4, 4, 4, 5, 5,
5, 5, 5, 6, 6, 7, 6, 6, 5, 5, 5, 5, 4, 4, 4, 4
},
(int []) {
1538, 1480, 1428, 1382, 1341, 1303, 1269, 1208,
1154, 1107, 1064, 1026, 990, 957, 897, 844,
796, 752, 711, 635, 564, 431, 363, 291,
252, 210, 164, 112, 83, 50, 13, -30
},
};

InterpolateTable r240to33 = {
48, 28,
(byte []){
5, 5, 5, 5, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4,
4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4
},
(int []){
1105, 1064, 1019, 972, 921, 894, 866,
837, 806, 775, 742, 707, 671, 634,
595, 553, 510, 465, 417, 367, 314,
258, 199, 137, 70, 0, -75, -155
},
};

int readGauge(const Gauge *g, byte n = 0) {
int p = g->pin + n;

#ifdef RANDOM_SENSORS
if (p < 16)
return rand() & 0x3ff;
if (p < 20) // CHT
return rand() & 0x1ff;
return rand() & 0x1ff + 1000; // EGT
if (p < 24)
return rand() & 0x1ff + 1000; // EGT
return FAULT;

#else

if (p < 16)
return analogRead(p);

noInterrupts();
int t = tcTemp[p-16];
interrupts();
return t;
int v;
if (p < 0)
return FAULT;

if (p < 16) {
v = analogRead(p);
int t = g->sensor->type;
if (t == st_r240to33)
v = interpolate(&r240to33, v);
else if (t == st_thermistor)
v = interpolate(&thermistor, v);
}
else if (p < 24) {
noInterrupts();
v = tcTemp[p-16];
interrupts();
}
return v;
#endif
}

void logTime(unsigned long start, const char *description) {
Serial.print(description);
Serial.print(' ');
Serial.print(int(millis()-start));
Serial.print("ms\n");
}

void serveUpWebPage(char url) {
// unsigned long start = millis();
Expand All @@ -92,14 +122,14 @@ void serveUpWebPage(char url) {


void setup() {
// Serial.begin(9600);
Serial.begin(9600);
// while (!Serial)
// ; // wait for serial port to connect. Stops here until Serial Monitor is started. Good for debugging setup

tcTempSetup();
printLEDSetup();
printLED(0,LED_TEXT(h,o,b,b));
printLED(1,readPin(0),0); // replace this with a value read from EEPROM
printLED(1,1234,1); // replace this with a value read from EEPROM
delay(1000); // replace this with LED self test sequence

// start the Ethernet connection and the server:
Expand Down
16 changes: 8 additions & 8 deletions enguino/printGauges.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
/// Implementation for printPrefix and pringGauge

int scaleMark(const Sensor *s, int val) {
int mark = (int)(((long)s->mfactor * (long)val) >> divisor) + s->moffset;
int mark = int(multiply(s->mfactor, val+s->moffset) >> divisor);
if (mark < 0)
mark = 0;
if (mark > 1000)
Expand All @@ -12,7 +12,7 @@ int scaleMark(const Sensor *s, int val) {
int scaleValue(const Sensor *s, int val) {
if (val == FAULT)
return val;
return (int)(((long)s->vfactor * (long)val) >> divisor) + s->voffset;
return int(multiply(s->vfactor,val) >> divisor) + s->voffset;
}

// vertical gauge is
Expand All @@ -22,7 +22,7 @@ void printVertical(const Gauge *g, bool showLabels) {
// starts at 1100, 4000 high
print_P(F("<rect x='400' y='1100' width='400' height='4000' class='rectgauge'/>\n"));

int val = readPin(g->pin);
int val = readGauge(g);
int mark = scaleMark(g->sensor, val) << 2;

const char *color = 0;
Expand Down Expand Up @@ -99,7 +99,7 @@ void printHorizontal(const Gauge *g, int count) {
print(600+offset);
print_P(F("' width='8000' height='400' class='rectgauge'/>\n"));

int val = readPin(g->pin + n);
int val = readGauge(g, n);
int mark = scaleMark(g->sensor, val) << 3;

const char *color = 0;
Expand Down Expand Up @@ -174,10 +174,10 @@ void printAuxHoriz(const Gauge *g, int count) {
// starts at ..., 8000 wide
int offset = 0;
for (int n=0; n<count; n++) {
int val = readPin(g->pin + n);
int val = readGauge(g, n);
int mark = scaleMark(g->sensor, val) << 3;

if (val == FAULT) {
if (val == FAULT) {
print_P(F("<rect x='9200' y='"));
print(offset+550);
print_P(F("' width='1000' height='500' rx='90' ry='90' fill='yellow'/>"));
Expand Down Expand Up @@ -277,7 +277,7 @@ void printRound(const Gauge *g) {
print_P(F("<text x='0' y='5900' 700='unit'>"));
print_text_close(g->units);

int val = readPin(g->pin);
int val = readGauge(g);
int mark = (scaleMark(g->sensor, val) * 24) / 10;

int scale = scaleValue(g->sensor, val);
Expand Down
Loading

0 comments on commit b51171e

Please sign in to comment.