limit baro corretion
Check if engine isn't running. Others minor code changes.
This commit is contained in:
parent
68aae53766
commit
dabbf872c2
|
@ -35,8 +35,9 @@ void initialiseAuxPWM()
|
|||
vvt_pin_port = portOutputRegister(digitalPinToPort(pinVVT_1));
|
||||
vvt_pin_mask = digitalPinToBitMask(pinVVT_1);
|
||||
|
||||
boost_pwm_max_count = 1000000L / (16 * configPage3.boostFreq * 2); //Converts the frequency in Hz to the number of ticks (at 16uS) it takes to complete 1 cycle. The x2 is there because the frequency is stored at half value (in a byte) to allow freqneucies up to 511Hz
|
||||
vvt_pwm_max_count = 1000000L / (16 * configPage3.vvtFreq * 2); //Converts the frequency in Hz to the number of ticks (at 16uS) it takes to complete 1 cycle
|
||||
//(16 * configPage3.boostFreq * 2) = (configPage3.boostFreq * 16 * 2) = (configPage3.boostFreq * 32) = (configPage3.boostFreq << 5)
|
||||
boost_pwm_max_count = 1000000L / (configPage3.boostFreq << 5); //Converts the frequency in Hz to the number of ticks (at 16uS) it takes to complete 1 cycle. The x2 is there because the frequency is stored at half value (in a byte) to allow freqneucies up to 511Hz
|
||||
vvt_pwm_max_count = 1000000L / (configPage3.vvtFreq << 5); //Converts the frequency in Hz to the number of ticks (at 16uS) it takes to complete 1 cycle
|
||||
//TIMSK1 |= (1 << OCIE1A); //Turn on the A compare unit (ie turn on the interrupt) //Shouldn't be needed with closed loop as its turned on below
|
||||
TIMSK1 |= (1 << OCIE1B); //Turn on the B compare unit (ie turn on the interrupt)
|
||||
|
||||
|
|
|
@ -0,0 +1,217 @@
|
|||
/*
|
||||
Optimized digital functions for AVR microcontrollers
|
||||
by Watterott electronic (www.watterott.com)
|
||||
based on http://code.google.com/p/digitalwritefast
|
||||
*/
|
||||
|
||||
#ifndef __digitalWriteFast_h_
|
||||
#define __digitalWriteFast_h_ 1
|
||||
|
||||
#define ERROR_SEQUENCE 0b10101010 //digitalReadFast will return this value if pin number is not constant
|
||||
// general macros/defines
|
||||
#ifndef BIT_READ
|
||||
# define BIT_READ(value, bit) ((value) & (1UL << (bit)))
|
||||
#endif
|
||||
#ifndef BIT_SET
|
||||
# define BIT_SET(value, bit) ((value) |= (1UL << (bit)))
|
||||
#endif
|
||||
#ifndef BIT_CLEAR
|
||||
# define BIT_CLEAR(value, bit) ((value) &= ~(1UL << (bit)))
|
||||
#endif
|
||||
#ifndef BIT_WRITE
|
||||
# define BIT_WRITE(value, bit, bitvalue) (bitvalue ? BIT_SET(value, bit) : BIT_CLEAR(value, bit))
|
||||
#endif
|
||||
|
||||
#ifndef SWAP
|
||||
#define SWAP(x,y) do{ (x)=(x)^(y); (y)=(x)^(y); (x)=(x)^(y); }while(0)
|
||||
#endif
|
||||
|
||||
// workarounds for ARM microcontrollers
|
||||
#if (!defined(__AVR__) || defined(ARDUINO_ARCH_SAM))
|
||||
#ifndef PROGMEM
|
||||
# define PROGMEM
|
||||
#endif
|
||||
#ifndef PGM_P
|
||||
# define PGM_P const char *
|
||||
#endif
|
||||
#ifndef PSTR
|
||||
# define PSTR(str) (str)
|
||||
#endif
|
||||
|
||||
#ifndef memcpy_P
|
||||
# define memcpy_P(dest, src, num) memcpy((dest), (src), (num))
|
||||
#endif
|
||||
#ifndef strcpy_P
|
||||
# define strcpy_P(dst, src) strcpy((dst), (src))
|
||||
#endif
|
||||
#ifndef strcat_P
|
||||
# define strcat_P(dst, src) strcat((dst), (src))
|
||||
#endif
|
||||
#ifndef strcmp_P
|
||||
# define strcmp_P(a, b) strcmp((a), (b))
|
||||
#endif
|
||||
#ifndef strcasecmp_P
|
||||
# define strcasecmp_P(a, b) strcasecmp((a), (b))
|
||||
#endif
|
||||
#ifndef strncmp_P
|
||||
# define strncmp_P(a, b, n) strncmp((a), (b), (n))
|
||||
#endif
|
||||
#ifndef strncasecmp_P
|
||||
# define strncasecmp_P(a, b, n) strncasecmp((a), (b), (n))
|
||||
#endif
|
||||
#ifndef strstr_P
|
||||
# define strstr_P(a, b) strstr((a), (b))
|
||||
#endif
|
||||
#ifndef strlen_P
|
||||
# define strlen_P(a) strlen((a))
|
||||
#endif
|
||||
#ifndef sprintf_P
|
||||
# define sprintf_P(s, f, ...) sprintf((s), (f), __VA_ARGS__)
|
||||
#endif
|
||||
|
||||
#ifndef pgm_read_byte
|
||||
# define pgm_read_byte(addr) (*(const unsigned char *)(addr))
|
||||
#endif
|
||||
#ifndef pgm_read_word
|
||||
# define pgm_read_word(addr) (*(const unsigned short *)(addr))
|
||||
#endif
|
||||
#ifndef pgm_read_dword
|
||||
# define pgm_read_dword(addr) (*(const unsigned long *)(addr))
|
||||
#endif
|
||||
|
||||
#endif
|
||||
|
||||
|
||||
// digital functions
|
||||
// --- Arduino Mega ---
|
||||
#if (defined(ARDUINO_AVR_MEGA) || \
|
||||
defined(ARDUINO_AVR_MEGA1280) || \
|
||||
defined(ARDUINO_AVR_MEGA2560) || \
|
||||
defined(__AVR_ATmega1280__) || \
|
||||
defined(__AVR_ATmega1281__) || \
|
||||
defined(__AVR_ATmega2560__) || \
|
||||
defined(__AVR_ATmega2561__))
|
||||
|
||||
#define UART_RX_PIN (0) //PE0
|
||||
#define UART_TX_PIN (1) //PE1
|
||||
|
||||
#define I2C_SDA_PIN (20)
|
||||
#define I2C_SCL_PIN (21)
|
||||
|
||||
#define SPI_HW_SS_PIN (53) //PB0
|
||||
#define SPI_HW_MOSI_PIN (51) //PB2
|
||||
#define SPI_HW_MISO_PIN (50) //PB3
|
||||
#define SPI_HW_SCK_PIN (52) //PB1
|
||||
|
||||
#define __digitalPinToPortReg(P) \
|
||||
(((P) >= 22 && (P) <= 29) ? &PORTA : \
|
||||
((((P) >= 10 && (P) <= 13) || ((P) >= 50 && (P) <= 53)) ? &PORTB : \
|
||||
(((P) >= 30 && (P) <= 37) ? &PORTC : \
|
||||
((((P) >= 18 && (P) <= 21) || (P) == 38) ? &PORTD : \
|
||||
((((P) >= 0 && (P) <= 3) || (P) == 5) ? &PORTE : \
|
||||
(((P) >= 54 && (P) <= 61) ? &PORTF : \
|
||||
((((P) >= 39 && (P) <= 41) || (P) == 4) ? &PORTG : \
|
||||
((((P) >= 6 && (P) <= 9) || (P) == 16 || (P) == 17) ? &PORTH : \
|
||||
(((P) == 14 || (P) == 15) ? &PORTJ : \
|
||||
(((P) >= 62 && (P) <= 69) ? &PORTK : &PORTL))))))))))
|
||||
|
||||
#define __digitalPinToDDRReg(P) \
|
||||
(((P) >= 22 && (P) <= 29) ? &DDRA : \
|
||||
((((P) >= 10 && (P) <= 13) || ((P) >= 50 && (P) <= 53)) ? &DDRB : \
|
||||
(((P) >= 30 && (P) <= 37) ? &DDRC : \
|
||||
((((P) >= 18 && (P) <= 21) || (P) == 38) ? &DDRD : \
|
||||
((((P) >= 0 && (P) <= 3) || (P) == 5) ? &DDRE : \
|
||||
(((P) >= 54 && (P) <= 61) ? &DDRF : \
|
||||
((((P) >= 39 && (P) <= 41) || (P) == 4) ? &DDRG : \
|
||||
((((P) >= 6 && (P) <= 9) || (P) == 16 || (P) == 17) ? &DDRH : \
|
||||
(((P) == 14 || (P) == 15) ? &DDRJ : \
|
||||
(((P) >= 62 && (P) <= 69) ? &DDRK : &DDRL))))))))))
|
||||
|
||||
#define __digitalPinToPINReg(P) \
|
||||
(((P) >= 22 && (P) <= 29) ? &PINA : \
|
||||
((((P) >= 10 && (P) <= 13) || ((P) >= 50 && (P) <= 53)) ? &PINB : \
|
||||
(((P) >= 30 && (P) <= 37) ? &PINC : \
|
||||
((((P) >= 18 && (P) <= 21) || (P) == 38) ? &PIND : \
|
||||
((((P) >= 0 && (P) <= 3) || (P) == 5) ? &PINE : \
|
||||
(((P) >= 54 && (P) <= 61) ? &PINF : \
|
||||
((((P) >= 39 && (P) <= 41) || (P) == 4) ? &PING : \
|
||||
((((P) >= 6 && (P) <= 9) || (P) == 16 || (P) == 17) ? &PINH : \
|
||||
(((P) == 14 || (P) == 15) ? &PINJ : \
|
||||
(((P) >= 62 && (P) <= 69) ? &PINK : &PINL))))))))))
|
||||
|
||||
#define __digitalPinToBit(P) \
|
||||
(((P) >= 7 && (P) <= 9) ? (P) - 3 : \
|
||||
(((P) >= 10 && (P) <= 13) ? (P) - 6 : \
|
||||
(((P) >= 22 && (P) <= 29) ? (P) - 22 : \
|
||||
(((P) >= 30 && (P) <= 37) ? 37 - (P) : \
|
||||
(((P) >= 39 && (P) <= 41) ? 41 - (P) : \
|
||||
(((P) >= 42 && (P) <= 49) ? 49 - (P) : \
|
||||
(((P) >= 50 && (P) <= 53) ? 53 - (P) : \
|
||||
(((P) >= 54 && (P) <= 61) ? (P) - 54 : \
|
||||
(((P) >= 62 && (P) <= 69) ? (P) - 62 : \
|
||||
(((P) == 0 || (P) == 15 || (P) == 17 || (P) == 21) ? 0 : \
|
||||
(((P) == 1 || (P) == 14 || (P) == 16 || (P) == 20) ? 1 : \
|
||||
(((P) == 19) ? 2 : \
|
||||
(((P) == 5 || (P) == 6 || (P) == 18) ? 3 : \
|
||||
(((P) == 2) ? 4 : \
|
||||
(((P) == 3 || (P) == 4) ? 5 : 7)))))))))))))))
|
||||
|
||||
// --- Other ---
|
||||
#else
|
||||
|
||||
#define SPI_HW_SS_PIN SS
|
||||
#define SPI_HW_MOSI_PIN MOSI
|
||||
#define SPI_HW_MISO_PIN MISO
|
||||
#define SPI_HW_SCK_PIN SCK
|
||||
|
||||
#endif
|
||||
//#endif //#ifndef digitalPinToPortReg
|
||||
|
||||
|
||||
//ref: http://forum.arduino.cc/index.php?topic=140409.msg1054868#msg1054868
|
||||
//void OutputsErrorIfCalled( void ) __attribute__ (( error( "Line: "__line__ "Variable used for digitalWriteFast") ));
|
||||
void NonConstantUsed( void ) __attribute__ (( error("") ));
|
||||
|
||||
|
||||
#ifndef digitalWriteFast
|
||||
#if (defined(__AVR__) || defined(ARDUINO_ARCH_AVR))
|
||||
#define digitalWriteFast(P, V) \
|
||||
if (__builtin_constant_p(P) && __builtin_constant_p(V)) { \
|
||||
BIT_WRITE(*__digitalPinToPortReg(P), __digitalPinToBit(P), (V)); \
|
||||
} else { \
|
||||
NonConstantUsed(); \
|
||||
}
|
||||
#else
|
||||
#define digitalWriteFast digitalWrite
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
#ifndef pinModeFast
|
||||
#if (defined(__AVR__) || defined(ARDUINO_ARCH_AVR))
|
||||
#define pinModeFast(P, V) \
|
||||
if (__builtin_constant_p(P) && __builtin_constant_p(V)) { \
|
||||
BIT_WRITE(*__digitalPinToDDRReg(P), __digitalPinToBit(P), (V)); \
|
||||
} else { \
|
||||
NonConstantUsed(); \
|
||||
}
|
||||
#else
|
||||
#define pinModeFast pinMode
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
||||
#ifndef digitalReadFast
|
||||
#if (defined(__AVR__) || defined(ARDUINO_ARCH_AVR))
|
||||
#define digitalReadFast(P) ( (byte) __digitalReadFast((P)) )
|
||||
#define __digitalReadFast(P ) \
|
||||
(__builtin_constant_p(P) ) ? ( \
|
||||
( BIT_READ(*__digitalPinToPINReg(P), __digitalPinToBit(P))) ) : \
|
||||
ERROR_SEQUENCE
|
||||
#else
|
||||
#define digitalReadFast digitalRead
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#endif //__digitalWriteFast_h_
|
||||
|
|
@ -147,10 +147,9 @@ struct statuses {
|
|||
unsigned int PW; //In uS
|
||||
volatile byte runSecs; //Counter of seconds since cranking commenced (overflows at 255 obviously)
|
||||
volatile byte secl; //Continous
|
||||
volatile unsigned int loopsPerSecond;
|
||||
volatile int loopsPerSecond;
|
||||
boolean launchingSoft; //True when in launch control soft limit mode
|
||||
boolean launchingHard; //True when in launch control hard limit mode
|
||||
float adv;
|
||||
int freeRAM;
|
||||
|
||||
//Helpful bitwise operations:
|
||||
|
|
5
idle.ino
5
idle.ino
|
@ -52,7 +52,8 @@ void initialiseIdle()
|
|||
idle_pin_mask = digitalPinToBitMask(pinIdle1);
|
||||
idle2_pin_port = portOutputRegister(digitalPinToPort(pinIdle2));
|
||||
idle2_pin_mask = digitalPinToBitMask(pinIdle2);
|
||||
idle_pwm_max_count = 1000000L / (16 * configPage3.idleFreq * 2); //Converts the frequency in Hz to the number of ticks (at 16uS) it takes to complete 1 cycle. Note that the frequency is divided by 2 coming from TS to allow for up to 512hz
|
||||
//(16 * configPage3.idleFreq * 2) = (configPage3.idleFreq * 16 * 2) = (configPage3.idleFreq * 32) = (configPage3.idleFreq << 5)
|
||||
idle_pwm_max_count = 1000000L / (configPage3.idleFreq << 5); //Converts the frequency in Hz to the number of ticks (at 16uS) it takes to complete 1 cycle. Note that the frequency is divided by 2 coming from TS to allow for up to 512hz
|
||||
enableIdle();
|
||||
break;
|
||||
|
||||
|
@ -72,7 +73,7 @@ void initialiseIdle()
|
|||
idle_pin_mask = digitalPinToBitMask(pinIdle1);
|
||||
idle2_pin_port = portOutputRegister(digitalPinToPort(pinIdle2));
|
||||
idle2_pin_mask = digitalPinToBitMask(pinIdle2);
|
||||
idle_pwm_max_count = 1000000L / (16 * configPage3.idleFreq * 2); //Converts the frequency in Hz to the number of ticks (at 16uS) it takes to complete 1 cycle. Note that the frequency is divided by 2 coming from TS to allow for up to 512hz
|
||||
idle_pwm_max_count = 1000000L / (configPage3.idleFreq << 5); //Converts the frequency in Hz to the number of ticks (at 16uS) it takes to complete 1 cycle. Note that the frequency is divided by 2 coming from TS to allow for up to 512hz
|
||||
idlePID.SetOutputLimits(0, idle_pwm_max_count);
|
||||
idlePID.SetTunings(configPage3.idleKP, configPage3.idleKI, configPage3.idleKD);
|
||||
idlePID.SetMode(AUTOMATIC); //Turn PID on
|
||||
|
|
2
math.h
2
math.h
|
@ -11,7 +11,7 @@ int fastMap(unsigned long x, int in_min, int in_max, int out_min, int out_max)
|
|||
//This is a dedicated function that specifically handles the case of mapping 0-1023 values into a 0 to X range
|
||||
//This is a common case because it means converting from a standard 10-bit analog input to a byte or 10-bit analog into 0-511 (Eg the temperature readings)
|
||||
//int fastMap1023toX(unsigned long x, int in_min, int in_max, int out_min, int out_max)
|
||||
//removed unused variables, in_min and out_min is aways 0, in_max is aways 1023
|
||||
//removed ununsed variables, in_min and out_min is aways 0, in_max is aways 1023
|
||||
int fastMap1023toX(unsigned long x, int out_max)
|
||||
{
|
||||
return (x * out_max) >> 10;
|
||||
|
|
|
@ -4,7 +4,7 @@ Copyright (C) Josh Stewart
|
|||
A full copy of the license may be found in the projects root directory
|
||||
*/
|
||||
|
||||
unsigned int tempReading;
|
||||
int tempReading;
|
||||
|
||||
void instanteneousMAPReading()
|
||||
{
|
||||
|
|
|
@ -96,6 +96,7 @@ unsigned long previousLoopTime; //The time the previous loop started (uS)
|
|||
unsigned long MAPrunningValue; //Used for tracking either the total of all MAP readings in this cycle (Event average) or the lowest value detected in this cycle (event minimum)
|
||||
unsigned int MAPcount; //Number of samples taken in the current MAP cycle
|
||||
byte MAPcurRev = 0; //Tracks which revolution we're sampling on
|
||||
int LastBaro; //Used for ignore correction if powered on a ruuning engine
|
||||
|
||||
int CRANK_ANGLE_MAX = 720;
|
||||
int CRANK_ANGLE_MAX_IGN = 360, CRANK_ANGLE_MAX_INJ = 360; // The number of crank degrees that the system track over. 360 for wasted / timed batch and 720 for sequential
|
||||
|
@ -201,25 +202,33 @@ void setup()
|
|||
//Need to check early on whether the coil charging is inverted. If this is not set straight away it can cause an unwanted spark at bootup
|
||||
if(configPage2.IgInv == 1) { coilHIGH = LOW, coilLOW = HIGH; }
|
||||
else { coilHIGH = HIGH, coilLOW = LOW; }
|
||||
endCoil1Charge(); //digitalWrite(pinCoil1, coilLOW);
|
||||
endCoil2Charge(); //digitalWrite(pinCoil2, coilLOW);
|
||||
endCoil3Charge(); //digitalWrite(pinCoil3, coilLOW);
|
||||
endCoil4Charge(); //digitalWrite(pinCoil4, coilLOW);
|
||||
endCoil5Charge(); //digitalWrite(pinCoil5, coilLOW);
|
||||
endCoil1Charge();
|
||||
endCoil2Charge();
|
||||
endCoil3Charge();
|
||||
endCoil4Charge();
|
||||
endCoil5Charge();
|
||||
|
||||
//Similar for injectors, make sure they're turned off
|
||||
closeInjector1(); //digitalWrite(pinInjector1, HIGH);
|
||||
closeInjector2(); //digitalWrite(pinInjector2, HIGH);
|
||||
closeInjector3(); //digitalWrite(pinInjector3, HIGH);
|
||||
closeInjector4(); //digitalWrite(pinInjector4, HIGH);
|
||||
closeInjector5(); //digitalWrite(pinInjector5, HIGH);
|
||||
closeInjector1();
|
||||
closeInjector2();
|
||||
closeInjector3();
|
||||
closeInjector4();
|
||||
closeInjector5();
|
||||
|
||||
//Set the tacho output default state
|
||||
digitalWrite(pinTachOut, HIGH);
|
||||
|
||||
//Lookup the current MAP reading for barometric pressure
|
||||
readMAP();
|
||||
currentStatus.baro = currentStatus.MAP;
|
||||
/*
|
||||
* The highest sea-level pressure on Earth occurs in Siberia, where the Siberian High often attains a sea-level pressure above 105 kPa;
|
||||
* with record highs close to 108.5 kPa.
|
||||
* The lowest measurable sea-level pressure is found at the centers of tropical cyclones and tornadoes, with a record low of 87 kPa;
|
||||
*/
|
||||
if ((currentStatus.MAP >= 87) && (currentStatus.MAP <= 108)) //Check if engine isn't running
|
||||
LastBaro = currentStatus.baro = currentStatus.MAP;
|
||||
else
|
||||
currentStatus.baro = LastBaro; //last baro correction
|
||||
|
||||
//Perform all initialisations
|
||||
initialiseSchedulers();
|
||||
|
@ -925,7 +934,6 @@ void loop()
|
|||
currentStatus.VE = get3DTableValue(&fuelTable, currentStatus.MAP, currentStatus.RPM); //Perform lookup into fuel map for RPM vs MAP value
|
||||
currentStatus.PW = PW_SD(req_fuel_uS, currentStatus.VE, currentStatus.MAP, currentStatus.corrections, inj_opentime_uS);
|
||||
currentStatus.advance = get3DTableValue(&ignitionTable, currentStatus.MAP, currentStatus.RPM); //As above, but for ignition advance
|
||||
currentStatus.adv = get3DTableValue2(&ignitionTable, currentStatus.MAP, currentStatus.RPM); //As above, but for ignition advance
|
||||
}
|
||||
else
|
||||
{
|
||||
|
@ -933,7 +941,6 @@ void loop()
|
|||
currentStatus.VE = get3DTableValue(&fuelTable, currentStatus.TPS, currentStatus.RPM); //Perform lookup into fuel map for RPM vs TPS value
|
||||
currentStatus.PW = PW_AN(req_fuel_uS, currentStatus.VE, currentStatus.TPS, currentStatus.corrections, inj_opentime_uS); //Calculate pulsewidth using the Alpha-N algorithm (in uS)
|
||||
currentStatus.advance = get3DTableValue(&ignitionTable, currentStatus.TPS, currentStatus.RPM); //As above, but for ignition advance
|
||||
currentStatus.adv = get3DTableValue2(&ignitionTable, currentStatus.MAP, currentStatus.RPM); //As above, but for ignition advance
|
||||
}
|
||||
|
||||
//Check for fixed ignition angles
|
||||
|
@ -1453,7 +1460,7 @@ void loop()
|
|||
inline void endCoil4Charge() { digitalWrite(pinCoil4, coilLOW); }
|
||||
|
||||
inline void openInjector5() { digitalWrite(pinInjector5, HIGH); }
|
||||
inline void closeInjector5() { digitalWrite(pinInjector5, LOW); }
|
||||
inline void closeInjector5() { digitalWrite(pinInjector5, LOW); }
|
||||
inline void beginCoil5Charge() { digitalWrite(pinCoil5, coilHIGH); digitalWrite(pinTachOut, LOW); }
|
||||
inline void endCoil5Charge() { digitalWrite(pinCoil5, coilLOW); }
|
||||
|
||||
|
@ -1473,3 +1480,6 @@ void beginCoil2and4Charge() { digitalWrite(pinCoil2, coilHIGH); digitalWrite(pin
|
|||
void endCoil2and4Charge() { digitalWrite(pinCoil2, coilLOW); digitalWrite(pinCoil4, coilLOW); }
|
||||
|
||||
void nullCallback() { return; }
|
||||
|
||||
|
||||
|
||||
|
|
82
table.ino
82
table.ino
|
@ -9,7 +9,6 @@ Because the size of the table is dynamic, this functino is required to reallocat
|
|||
Note that this may clear some of the existing values of the table
|
||||
*/
|
||||
#include "table.h"
|
||||
#include "globals.h"
|
||||
|
||||
void table2D_setSize(struct table2D* targetTable, byte newSize)
|
||||
{
|
||||
|
@ -213,52 +212,6 @@ int table2D_getValue(struct table2D *fromTable, int X)
|
|||
}
|
||||
|
||||
|
||||
//This function pulls a value from a 3D table given a target for X and Y coordinates.
|
||||
//It fix a 2D linear interpolation as descibred in: http://www.megamanual.com/v22manual/ve_tuner.pdf
|
||||
float get3DTableValue2(struct table3D *fromTable, int Y, int X)
|
||||
{
|
||||
float m, n, o ,p, q, r;
|
||||
byte xMin, xMax;
|
||||
byte yMin, yMax;
|
||||
|
||||
for (xMin = fromTable->xSize-1; xMin>=0; xMin--) if(X>fromTable->axisX[xMin]) break;
|
||||
for (yMin = fromTable->ySize-1; yMin>=0; yMin--) if(Y>fromTable->axisY[yMin]) break;
|
||||
if (xMin>fromTable->xSize-1) xMin = fromTable->xSize-1; //Overflow protection
|
||||
if (yMin>fromTable->ySize-1) yMin = fromTable->ySize-1; //Overflow protection
|
||||
|
||||
xMax = xMin + 1;
|
||||
yMax = yMin + 1;
|
||||
if (xMax>fromTable->xSize-1) xMax = fromTable->xSize-1; //Overflow protection
|
||||
if (yMax>fromTable->ySize-1) yMax = fromTable->ySize-1; //Overflow protection
|
||||
|
||||
p = float(X-fromTable->axisX[xMin]) / float(fromTable->axisX[xMax] - fromTable->axisX[xMin]);
|
||||
q = float(Y-fromTable->axisY[yMin]) / float(fromTable->axisY[yMax] - fromTable->axisY[yMin]);
|
||||
|
||||
/* On http://www.megamanual.com/v22manual/ve_tuner.pdf the interpolation image is fliped
|
||||
Eg: | ve_turner.pdf | | should be | cause y and x axis is in that order
|
||||
VE(1,1) VE(1,2) VE(2,1) VE(2,2) ^
|
||||
y|
|
||||
|
|
||||
VE(2,1) VE(2,2) VE(1,1) VE(1,2) +------------> x
|
||||
|
||||
At this point we have the 4 corners of the map where the interpolated value will fall in
|
||||
Eg: A=(yMax,xMin) B=(yMax,xMax)
|
||||
|
||||
C=(yMin,xMin) D=(yMin,xMax)
|
||||
*/
|
||||
int A = fromTable->values[yMax][xMin];
|
||||
int B = fromTable->values[yMax][xMax];
|
||||
int C = fromTable->values[yMin][xMin];
|
||||
int D = fromTable->values[yMin][xMax];
|
||||
|
||||
m = (1.0-p) * (1.0-q);
|
||||
n = p * (1-q);
|
||||
o = (1-p) * q;
|
||||
r = p * q;
|
||||
|
||||
return ( (A * m) + (B * n) + (C * o) + (D * r) );
|
||||
}
|
||||
|
||||
//This function pulls a value from a 3D table given a target for X and Y coordinates.
|
||||
//It performs a 2D linear interpolation as descibred in: http://www.megamanual.com/v22manual/ve_tuner.pdf
|
||||
int get3DTableValue(struct table3D *fromTable, int Y, int X)
|
||||
|
@ -406,46 +359,23 @@ int get3DTableValue(struct table3D *fromTable, int Y, int X)
|
|||
//Create some normalised position values
|
||||
//These are essentially percentages (between 0 and 1) of where the desired value falls between the nearest bins on each axis
|
||||
|
||||
// Float version
|
||||
/*
|
||||
float p, q;
|
||||
if (xMaxValue == xMinValue)
|
||||
{ p = (float)(X-xMinValue); }
|
||||
else { p = ((float)(X - xMinValue)) / (float)(xMaxValue - xMinValue); }
|
||||
|
||||
if (yMaxValue == yMinValue)
|
||||
{ q = (float)(Y - yMinValue); }
|
||||
else { q = 1- (((float)(Y - yMaxValue)) / (float)(yMinValue - yMaxValue)); }
|
||||
|
||||
float m = (1.0-p) * (1.0-q);
|
||||
float n = p * (1-q);
|
||||
float o = (1-p) * q;
|
||||
float r = p * q;
|
||||
|
||||
|
||||
return ( (A * m) + (B * n) + (C * o) + (D * r) );
|
||||
*/
|
||||
|
||||
// Non-Float version:
|
||||
//Initial check incase the values were hit straight on
|
||||
long p;
|
||||
if (xMaxValue == xMinValue)
|
||||
{ p = ((long)(X - xMinValue) << 8); } //This only occurs if the requested X value was equal to one of the X axis bins
|
||||
else
|
||||
{
|
||||
p = ((long)(X - xMinValue) << 8); //This only occurs if the requested X value was equal to one of the X axis bins
|
||||
else
|
||||
p = ((long)(X - xMinValue) << 8) / (xMaxValue - xMinValue); //This is the standard case
|
||||
}
|
||||
|
||||
long q;
|
||||
if (yMaxValue == yMinValue)
|
||||
{ q = ((long)(Y - yMinValue) << 8); }
|
||||
q = ((long)(Y - yMinValue) << 8);
|
||||
else
|
||||
{
|
||||
q = 256 - (((long)(Y - yMaxValue) << 8) / (yMinValue - yMaxValue));
|
||||
}
|
||||
q = 256 - (((long)(Y - yMaxValue) << 8) / (yMinValue - yMaxValue));
|
||||
|
||||
int m = ((256-p) * (256-q)) >> 8;
|
||||
int n = (p * (256-q)) >> 8;
|
||||
int o = ((256-p) * q) >> 8;
|
||||
int r = (p * q) >> 8;
|
||||
return ( (A * m) + (B * n) + (C * o) + (D * r) ) >> 8;
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue