More of the basic infrastructure stuff

This commit is contained in:
Josh Stewart 2013-02-05 08:05:35 +11:00
parent 35ad62298b
commit 66ea47fde5
3 changed files with 74 additions and 12 deletions

View File

@ -11,31 +11,43 @@ Need to calculate the req_fuel figure here, preferably in pre-processor macro
#define engineInjectorSize 100 // In cc/min #define engineInjectorSize 100 // In cc/min
#define engineStoich 14.7 // Stoichiometric ratio of fuel used #define engineStoich 14.7 // Stoichiometric ratio of fuel used
#define engineStrokes 4 //Can be 2 stroke or 4 stroke, any other value will cause problems #define engineStrokes 4 //Can be 2 stroke or 4 stroke, any other value will cause problems
#define triggerTeeth 12 //The full count of teeth on the trigger wheel if there were no gaps
#define triggerMissingTeeth 1 //The size of the tooth gap (ie number of missing teeth)
//The following lines are configurable, but the defaults are probably pretty good for most applications
#define engineInjectorDeadTime 1.5 //Time in ms that the injector takes to open
#define engineSquirtsPerCycle 2 //Probably would be 1 for a 2 stroke
//************************************************************************************************** //**************************************************************************************************
#include "utils.h" #include "utils.h"
#include "table.h"
int req_fuel = ((engineCapacity / engineInjectorSize) / engineCylinders / engineStoich) * 100; // This doesn't seem quite correct, but I can't find why. It will be close enough to start an engine int req_fuel = ((engineCapacity / engineInjectorSize) / engineCylinders / engineStoich) * 100; // This doesn't seem quite correct, but I can't find why. It will be close enough to start an engine
// Setup section // Setup section
// These aren't really configuration options, more so a description of how the hardware is setup. These are things that will be defined in the recommended hardware setup // These aren't really configuration options, more so a description of how the hardware is setup. These are things that will be defined in the recommended hardware setup
int triggerPin = 2; int triggerActualTeeth = triggerTeeth - triggerMissingTeeth; //The number of physical teeth on the wheel. Doing this here saves us a calculation each time in the interrupt
int triggerTeeth = 12;
int triggerMissingTeeth = 1;
int triggerOffset = 120; int triggerOffset = 120;
int injectorPin = 6; // The standard pin for the injector driver int triggerToothAngle = 360 / triggerTeeth; //The number of degrees that passes from tooth to tooth
int pinInjector = 6; // The standard pin for the injector driver
int pinTrigger = 2;
volatile boolean hasSync = false; volatile boolean hasSync = false;
volatile int currentToothCount = 0; //The current volatile int toothCurrentCount = 0; //The current number of teeth (Onec sync has been achieved, this can never actually be 0
volatile unsigned long toothLastToothTime = 0; //The time (micros()) that the last tooth was registered
volatile unsigned long toothLastMinusOneToothTime = 0; //The time (micros()) that the tooth before the last tooth was registered
int rpm = 0; //Stores the last recorded RPM value
struct table fuelTable;
void setup() { void setup() {
//Begin the main crank trigger interttupt setup //Begin the main crank trigger interrupt pin setup
//The interrupt numbering is a bit odd - See here for reference: http://arduino.cc/en/Reference/AttachInterrupt //The interrupt numbering is a bit odd - See here for reference: http://arduino.cc/en/Reference/AttachInterrupt
int triggerInterrupt = 0; // By default, use int triggerInterrupt = 0; // By default, use the first interrupt. The user should always have set things up (Or even better, use the recommended pinouts)
switch (triggerPin) { switch (pinInjector) {
case 2: case 2:
triggerInterrupt = 0; break; triggerInterrupt = 0; break;
case 3: case 3:
@ -66,6 +78,23 @@ void loop()
if (hasSync) if (hasSync)
{ {
//Calculate the RPM based on the time between the last 2 teeth. I have no idea whether this will be accurate AT ALL, but it's fairly efficient and means there doesn't need to be another variable placed into the trigger interrupt
if (toothCurrentCount != 1) //We can't perform the RPM calculation if we're at the first tooth as the timing would be double (Well, we can, but it would need a different calculation and I don't think it's worth it, just use the last RPM value)
{
long revolutionTime = (triggerTeeth * (toothLastToothTime - toothLastMinusOneToothTime)); //The time in us that one revolution would take at current speed
rpm = US_IN_MINUTE / revolutionTime;
}
//Get the current MAP value
int MAP = 1; //Placeholder
//Perform lookup into fuel map for RPM vs MAP value
int VE = getTableValue(fuelTable, rpm, MAP);
//From all of the above, calculate an injector pulsewidth
int pulseWidth = PW(req_fuel, VE, MAP, 100, engineInjectorDeadTime);
} }
else else
{ getSync(); } { getSync(); }
@ -82,13 +111,24 @@ void getSync()
//Interrupts //Interrupts
//These 2 functions simply trigger the injector driver off or on. //These 2 functions simply trigger the injector driver off or on.
void openInjector() { digitalWrite(injectorPin, HIGH); } // Set based on an estimate of when to open the injector void openInjector() { digitalWrite(pinInjector, HIGH); } // Set based on an estimate of when to open the injector
void closeInjector() { digitalWrite(injectorPin, LOW); } // Is called x ms after the open time where x is calculated by the rpm, load and req_fuel void closeInjector() { digitalWrite(pinInjector, LOW); } // Is called x ms after the open time where x is calculated by the rpm, load and req_fuel
//The trigger function is called everytime a crank tooth passes the //The trigger function is called everytime a crank tooth passes the sensor
void trigger() void trigger()
{ {
// http://www.msextra.com/forums/viewtopic.php?f=94&t=22976
// http://www.megamanual.com/ms2/wheel.htm
toothCurrentCount++; //Increment the tooth counter
//Begin the missing tooth detection
unsigned long curTime = micros();
//If the time between the current tooth and the last is greater than 1.5x the time between the last tooth and the tooth before that, we make the assertion that we must be at the first tooth after the gap
if ( (curTime - toothLastToothTime) > (1.5 * (toothLastToothTime - toothLastMinusOneToothTime))) { toothCurrentCount = 1; }
// Update the last few tooth times
toothLastMinusOneToothTime = toothLastToothTime;
toothLastToothTime = curTime;
} }

18
table.h Normal file
View File

@ -0,0 +1,18 @@
/*
This file is used for everything related to maps/tables including their definition, functions etc
*/
struct table {
//All tables must be the same size for simplicity
const static int xSize = 8;
const static int ySize = 8;
int values[xSize][ySize];
//static boolean useInterp = false; //Whether or not interpolation should be used (Assuming we have enough CPU for it)
};
int getTableValue(struct table fromTable, int X, int Y)
{
return 1;
}

View File

@ -2,6 +2,10 @@
These are some utility functions and variables used through the main code These are some utility functions and variables used through the main code
*/ */
#define MS_IN_MINUTE 60000
#define US_IN_MINUTE 60000000
//The following functions help determine the required fuel constant. For more information about these calculations, please refer to http://www.megamanual.com/v22manual/mfuel.htm //The following functions help determine the required fuel constant. For more information about these calculations, please refer to http://www.megamanual.com/v22manual/mfuel.htm
int AIRDEN(int MAP, int temp) int AIRDEN(int MAP, int temp)
{ {