Revert "Merge branch 'master' into pr/5"

This reverts commit d8898db9fe, reversing
changes made to b1e7b854d0.
This commit is contained in:
VitorBoss 2017-08-28 02:01:36 -03:00
parent 8f9619ca96
commit 1ffbad8a43
9 changed files with 2655 additions and 2463 deletions

View File

@ -1,30 +1,30 @@
#ifndef CANCOMMS_H
#define CANCOMMS_H
//These are the page numbers that the Tuner Studio serial protocol uses to transverse the different map and config pages.
#define veMapPage 1
uint8_t currentcanCommand;
uint8_t currentCanPage = 1;//Not the same as the speeduino config page numbers
uint8_t nCanretry = 0; //no of retrys
uint8_t cancmdfail = 0; //command fail yes/no
uint8_t canlisten = 0;
uint8_t Lbuffer[8]; //8 byte buffer to store incomng can data
uint8_t Gdata[9];
uint8_t Glow, Ghigh;
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
HardwareSerial &CANSerial = Serial3;
#elif defined(CORE_STM32)
#if defined(ARDUINO_ARCH_STM32) // STM32GENERIC core
SerialUART &CANSerial = Serial2;
#else //libmaple core aka STM32DUINO
HardwareSerial &CANSerial = Serial2;
#endif
#elif defined(CORE_TEENSY)
HardwareSerial &CANSerial = Serial2;
#endif
void canCommand();//This is the heart of the Command Line Interpeter. All that needed to be done was to make it human readable.
void sendCancommand(uint8_t cmdtype , uint16_t canadddress, uint8_t candata1, uint8_t candata2, uint16_t paramgroup);
#ifndef CANCOMMS_H
#define CANCOMMS_H
//These are the page numbers that the Tuner Studio serial protocol uses to transverse the different map and config pages.
#define veMapPage 1
uint8_t currentcanCommand;
uint8_t currentCanPage = 1;//Not the same as the speeduino config page numbers
uint8_t nCanretry = 0; //no of retrys
uint8_t cancmdfail = 0; //command fail yes/no
uint8_t canlisten = 0;
uint8_t Lbuffer[8]; //8 byte buffer to store incomng can data
uint8_t Gdata[9];
uint8_t Glow, Ghigh;
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
HardwareSerial &CANSerial = Serial3;
#elif defined(CORE_STM32)
#if defined(ARDUINO_ARCH_STM32) // STM32GENERIC core
SerialUART &CANSerial = Serial2;
#else //libmaple core aka STM32DUINO
HardwareSerial &CANSerial = Serial2;
#endif
#elif defined(CORE_TEENSY)
HardwareSerial &CANSerial = Serial2;
#endif
void canCommand();//This is the heart of the Command Line Interpeter. All that needed to be done was to make it human readable.
void sendCancommand(uint8_t cmdtype , uint16_t canadddress, uint8_t candata1, uint8_t candata2, uint16_t paramgroup);
#endif // CANCOMMS_H

View File

@ -2196,7 +2196,6 @@ void triggerSetEndTeeth_Daihatsu()
}
/* -------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------------
Code for decoder.ino
Name: Harley
@ -2336,4 +2335,3 @@ void triggerSetEndTeeth_Harley()
{
}

View File

@ -36,10 +36,6 @@
#define BIT_SET(a,b) ((a) |= (1<<(b)))
#define BIT_CLEAR(a,b) ((a) &= ~(1<<(b)))
#define BIT_CHECK(var,pos) !!((var) & (1<<(pos)))
#define Lo(param) ((char *)&param)[0]
#define Hi(param) ((char *)&param)[1]
#define Higher(param) ((char *)&param)[2]
#define Highest(param) ((char *)&param)[3]
#define MS_IN_MINUTE 60000
#define US_IN_MINUTE 60000000
@ -128,11 +124,7 @@
#define OFFSET_FUELTRIM 127 //The fuel trim tables are offset by 128 to allow for -128 to +128 values
#define OFFSET_IGNITION 40 //Ignition values from the main spark table are offset 40 degrees downards to allow for negative spark timing
#if defined(CORE_STM32)
#define SERIAL_BUFFER_THRESHOLD 64 // When the serial buffer is filled to greater than this threshold value, the serial processing operations will be performed more urgently in order to avoid it overflowing. Serial buffer is 128 bytes long, so the threshold is set at half this as a reasonable figure
#else
#define SERIAL_BUFFER_THRESHOLD 32 // When the serial buffer is filled to greater than this threshold value, the serial processing operations will be performed more urgently in order to avoid it overflowing. Serial buffer is 64 bytes long, so the threshold is set at half this as a reasonable figure
#endif
#define SERIAL_BUFFER_THRESHOLD 32 // When the serial buffer is filled to greater than this threshold value, the serial processing operations will be performed more urgently in order to avoid it overflowing. Serial buffer is 64 bytes long, so the threshold is set at half this as a reasonable figure
#define FUEL_PUMP_ON() *pump_pin_port |= (pump_pin_mask)
#define FUEL_PUMP_OFF() *pump_pin_port &= ~(pump_pin_mask)
@ -215,9 +207,6 @@ int ignition4EndAngle = 0;
//This is used across multiple files
unsigned long revolutionTime; //The time in uS that one revolution would take at current speed (The time tooth 1 was last seen, minus the time it was seen prior to that)
volatile byte TIMER_mask;
volatile byte LOOP_TIMER;
//The status struct contains the current values for all 'live' variables
//In current version this is 64 bytes
struct statuses {

View File

@ -1,108 +1,107 @@
#ifndef SENSORS_H
#define SENSORS_H
#include "Arduino.h"
// The following are alpha values for the ADC filters.
// Their values are from 0 to 255 with 0 being no filtering and 255 being maximum
#define ADCFILTER_TPS 128
#define ADCFILTER_CLT 180
#define ADCFILTER_IAT 180
#define ADCFILTER_O2 128
#define ADCFILTER_BAT 128
#define ADCFILTER_MAP 20 //This is only used on Instantaneous MAP readings and is intentionally very weak to allow for faster response
#define ADCFILTER_BARO 64
#define BARO_MIN 87
#define BARO_MAX 108
/*
#if defined(CORE_AVR)
#define ANALOG_ISR
#endif
*/
volatile byte flexCounter = 0;
volatile int AnChannel[15];
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; //Tracks which revolution we're sampling on
/*
* Simple low pass IIR filter macro for the analog inputs
* This is effectively implementing the smooth filter from http://playground.arduino.cc/Main/Smooth
* But removes the use of floats and uses 8 bits of fixed precision.
*/
#define ADC_FILTER(input, alpha, prior) (((long)input * (256 - alpha) + ((long)prior * alpha))) >> 8
void instanteneousMAPReading();
void readMAP();
void flexPulse();
#if defined(ANALOG_ISR)
//Analog ISR interrupt routine
/*
ISR(ADC_vect)
{
byte nChannel;
int result = ADCL | (ADCH << 8);
//ADCSRA = 0x6E; // ADC disabled by clearing bit 7(ADEN)
//BIT_CLEAR(ADCSRA, ADIE);
nChannel = ADMUX & 0x07;
#if defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__)
if (nChannel==7) { ADMUX = 0x40; }
#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
if(ADCSRB & 0x08) { nChannel += 8; } //8 to 15
if(nChannel == 15)
{
ADMUX = 0x40; //channel 0
ADCSRB = 0x00; //clear MUX5 bit
}
else if (nChannel == 7) //channel 7
{
ADMUX = 0x40;
ADCSRB = 0x08; //Set MUX5 bit
}
#endif
else { ADMUX++; }
AnChannel[nChannel-1] = result;
//BIT_SET(ADCSRA, ADIE);
//ADCSRA = 0xEE; // ADC Interrupt Flag enabled
}
*/
ISR(ADC_vect)
{
byte nChannel = ADMUX & 0x07;
int result = ADCL | (ADCH << 8);
BIT_CLEAR(ADCSRA, ADEN); //Disable ADC for Changing Channel (see chapter 26.5 of datasheet)
#if defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__)
if (nChannel==7) { ADMUX = 0x40; }
#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
if( (ADCSRB & 0x08) > 0) { nChannel += 8; } //8 to 15
if(nChannel == 15)
{
ADMUX = 0x40; //channel 0
ADCSRB = 0x00; //clear MUX5 bit
}
else if (nChannel == 7) //channel 7
{
ADMUX = 0x40;
ADCSRB = 0x08; //Set MUX5 bit
}
#endif
else { ADMUX++; }
AnChannel[nChannel] = result;
BIT_SET(ADCSRA, ADEN); //Enable ADC
}
#endif
#endif // SENSORS_H
#ifndef SENSORS_H
#define SENSORS_H
#include "Arduino.h"
// The following are alpha values for the ADC filters.
// Their values are from 0 to 255 with 0 being no filtering and 255 being maximum
#define ADCFILTER_TPS 128
#define ADCFILTER_CLT 180
#define ADCFILTER_IAT 180
#define ADCFILTER_O2 128
#define ADCFILTER_BAT 128
#define ADCFILTER_MAP 20 //This is only used on Instantaneous MAP readings and is intentionally very weak to allow for faster response
#define ADCFILTER_BARO 64
#define BARO_MIN 87
#define BARO_MAX 108
/*
#if defined(CORE_AVR)
#define ANALOG_ISR
#endif
*/
volatile byte flexCounter = 0;
volatile int AnChannel[15];
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; //Tracks which revolution we're sampling on
/*
* Simple low pass IIR filter macro for the analog inputs
* This is effectively implementing the smooth filter from http://playground.arduino.cc/Main/Smooth
* But removes the use of floats and uses 8 bits of fixed precision.
*/
#define ADC_FILTER(input, alpha, prior) (((long)input * (256 - alpha) + ((long)prior * alpha))) >> 8
void instanteneousMAPReading();
void readMAP();
void flexPulse();
#if defined(ANALOG_ISR)
//Analog ISR interrupt routine
/*
ISR(ADC_vect)
{
byte nChannel;
int result = ADCL | (ADCH << 8);
//ADCSRA = 0x6E; // ADC disabled by clearing bit 7(ADEN)
//BIT_CLEAR(ADCSRA, ADIE);
nChannel = ADMUX & 0x07;
#if defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__)
if (nChannel==7) { ADMUX = 0x40; }
#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
if(ADCSRB & 0x08) { nChannel += 8; } //8 to 15
if(nChannel == 15)
{
ADMUX = 0x40; //channel 0
ADCSRB = 0x00; //clear MUX5 bit
}
else if (nChannel == 7) //channel 7
{
ADMUX = 0x40;
ADCSRB = 0x08; //Set MUX5 bit
}
#endif
else { ADMUX++; }
AnChannel[nChannel-1] = result;
//BIT_SET(ADCSRA, ADIE);
//ADCSRA = 0xEE; // ADC Interrupt Flag enabled
}
*/
ISR(ADC_vect)
{
byte nChannel = ADMUX & 0x07;
int result = ADCL | (ADCH << 8);
BIT_CLEAR(ADCSRA, ADEN); //Disable ADC for Changing Channel (see chapter 26.5 of datasheet)
#if defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__)
if (nChannel==7) { ADMUX = 0x40; }
#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
if( (ADCSRB & 0x08) > 0) { nChannel += 8; } //8 to 15
if(nChannel == 15)
{
ADMUX = 0x40; //channel 0
ADCSRB = 0x00; //clear MUX5 bit
}
else if (nChannel == 7) //channel 7
{
ADMUX = 0x40;
ADCSRB = 0x08; //Set MUX5 bit
}
#endif
else { ADMUX++; }
AnChannel[nChannel] = result;
BIT_SET(ADCSRA, ADEN); //Enable ADC
}
#endif
#endif // SENSORS_H

View File

@ -268,4 +268,3 @@ void flexPulse()
{
++flexCounter;
}

File diff suppressed because it is too large Load Diff

View File

@ -1,3 +1,4 @@
<<<<<<< HEAD
/*
Speeduino - Simple engine management for the Arduino Mega 2560 platform
Copyright (C) Josh Stewart
@ -209,4 +210,214 @@ void oneMSInterval() //Most ARM chips can simply call a function
TCNT2 = 131; //Preload timer2 with 100 cycles, leaving 156 till overflow.
TIFR2 = 0x00; //Timer2 INT Flag Reg: Clear Timer Overflow Flag
#endif
=======
/*
Speeduino - Simple engine management for the Arduino Mega 2560 platform
Copyright (C) Josh Stewart
A full copy of the license may be found in the projects root directory
*/
/*
Timers are used for having actions performed repeatedly at a fixed interval (Eg every 100ms)
They should not be confused with Schedulers, which are for performing an action once at a given point of time in the future
Timers are typically low resolution (Compared to Schedulers), with maximum frequency currently being approximately every 10ms
*/
#include "timers.h"
#include "globals.h"
#include "sensors.h"
#if defined(CORE_AVR)
#include <avr/wdt.h>
#endif
void initialiseTimers()
{
#if defined(CORE_AVR) //AVR chips use the ISR for this
//Configure Timer2 for our low-freq interrupt code.
TCCR2B = 0x00; //Disbale Timer2 while we set it up
TCNT2 = 131; //Preload timer2 with 131 cycles, leaving 125 till overflow. As the timer runs at 125Khz, this causes overflow to occur at 1Khz = 1ms
TIFR2 = 0x00; //Timer2 INT Flag Reg: Clear Timer Overflow Flag
TIMSK2 = 0x01; //Timer2 Set Overflow Interrupt enabled.
TCCR2A = 0x00; //Timer2 Control Reg A: Wave Gen Mode normal
/* Now configure the prescaler to CPU clock divided by 128 = 125Khz */
TCCR2B |= (1<<CS22) | (1<<CS20); // Set bits
TCCR2B &= ~(1<<CS21); // Clear bit
//Enable the watchdog timer for 2 second resets (Good reference: https://tushev.org/articles/arduino/5/arduino-and-watchdog-timer)
//Boooooooooo WDT is currently broken on Mega 2560 bootloaders :(
//wdt_enable(WDTO_2S);
#elif defined (CORE_TEENSY)
//Uses the PIT timer on Teensy.
lowResTimer.begin(oneMSInterval, 1000);
#elif defined(CORE_STM32)
Timer4.setPeriod(1000); // Set up period
// Set up an interrupt
Timer4.setMode(1, TIMER_OUTPUT_COMPARE);
Timer4.attachInterrupt(1, oneMSInterval);
Timer4.resume(); //Start Timer
#endif
dwellLimit_uS = (1000 * configPage2.dwellLimit);
lastRPM_100ms = 0;
}
//Timer2 Overflow Interrupt Vector, called when the timer overflows.
//Executes every ~1ms.
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) //AVR chips use the ISR for this
ISR(TIMER2_OVF_vect, ISR_NOBLOCK)
#elif defined (CORE_TEENSY) || defined(CORE_STM32)
void oneMSInterval() //Most ARM chips can simply call a function
#endif
{
//Increment Loop Counters
loop33ms++;
loop66ms++;
loop100ms++;
loop250ms++;
loopSec++;
unsigned long targetOverdwellTime;
//Overdwell check
targetOverdwellTime = micros() - dwellLimit_uS; //Set a target time in the past that all coil charging must have begun after. If the coil charge began before this time, it's been running too long
bool isCrankLocked = configPage2.ignCranklock && (currentStatus.RPM < currentStatus.crankRPM); //Dwell limiter is disabled during cranking on setups using the locked cranking timing. WE HAVE to do the RPM check here as relying on the engine cranking bit can be potentially too slow in updating
//Check first whether each spark output is currently on. Only check it's dwell time if it is
if(ignitionSchedule1.Status == RUNNING) { if( (ignitionSchedule1.startTime < targetOverdwellTime) && (configPage2.useDwellLim) && (isCrankLocked != true) ) { endCoil1Charge(); } }
if(ignitionSchedule2.Status == RUNNING) { if( (ignitionSchedule2.startTime < targetOverdwellTime) && (configPage2.useDwellLim) && (isCrankLocked != true) ) { endCoil2Charge(); } }
if(ignitionSchedule3.Status == RUNNING) { if( (ignitionSchedule3.startTime < targetOverdwellTime) && (configPage2.useDwellLim) && (isCrankLocked != true) ) { endCoil3Charge(); } }
if(ignitionSchedule4.Status == RUNNING) { if( (ignitionSchedule4.startTime < targetOverdwellTime) && (configPage2.useDwellLim) && (isCrankLocked != true) ) { endCoil4Charge(); } }
if(ignitionSchedule5.Status == RUNNING) { if( (ignitionSchedule5.startTime < targetOverdwellTime) && (configPage2.useDwellLim) && (isCrankLocked != true) ) { endCoil5Charge(); } }
//15Hz loop
if (loop66ms == 66)
{
loop66ms = 0;
BIT_SET(TIMER_mask, BIT_TIMER_15HZ);
}
//30Hz loop
if (loop33ms == 33)
{
loop33ms = 0;
BIT_SET(TIMER_mask, BIT_TIMER_30HZ);
}
//Loop executed every 100ms loop
//Anything inside this if statement will run every 100ms.
if (loop100ms == 100)
{
loop100ms = 0; //Reset counter
BIT_SET(TIMER_mask, BIT_TIMER_10HZ);
#if defined(CORE_STM32) //debug purpose, only visal for running code
digitalWrite(LED_BUILTIN, !digitalRead(LED_BUILTIN));
#endif
currentStatus.rpmDOT = (currentStatus.RPM - lastRPM_100ms) * 10; //This is the RPM per second that the engine has accelerated/decelleratedin the last loop
lastRPM_100ms = currentStatus.RPM; //Record the current RPM for next calc
}
//Loop executed every 250ms loop (1ms x 250 = 250ms)
//Anything inside this if statement will run every 250ms.
if (loop250ms == 250)
{
loop250ms = 0; //Reset Counter
BIT_SET(TIMER_mask, BIT_TIMER_4HZ);
#if defined(CORE_AVR)
//Reset watchdog timer (Not active currently)
//wdt_reset();
//DIY watchdog
if( (initialisationComplete == true) && (last250msLoopCount == mainLoopCount) ) { setup(); } //This is a sign of a crash.
else { last250msLoopCount = mainLoopCount; }
#endif
}
//Loop executed every 1 second (1ms x 1000 = 1000ms)
if (loopSec == 1000)
{
loopSec = 0; //Reset counter.
BIT_SET(TIMER_mask, BIT_TIMER_1HZ);
dwellLimit_uS = (1000 * configPage2.dwellLimit); //Update uS value incase setting has changed
currentStatus.crankRPM = ((unsigned int)configPage2.crankRPM * 100);
//**************************************************************************************************************************************************
//This updates the runSecs variable
//If the engine is running or cranking, we need ot update the run time counter.
if (BIT_CHECK(currentStatus.engine, BIT_ENGINE_RUN))
{ //NOTE - There is a potential for a ~1sec gap between engine crank starting and ths runSec number being incremented. This may delay ASE!
if (currentStatus.runSecs <= 254) //Ensure we cap out at 255 and don't overflow. (which would reset ASE)
{ currentStatus.runSecs++; } //Increment our run counter by 1 second.
}
//**************************************************************************************************************************************************
//This records the number of main loops the system has completed in the last second
currentStatus.loopsPerSecond = mainLoopCount;
mainLoopCount = 0;
//**************************************************************************************************************************************************
//increament secl (secl is simply a counter that increments every second and is used to track whether the system has unexpectedly reset
currentStatus.secl++;
//**************************************************************************************************************************************************
//Check the fan output status
if (configPage4.fanEnable == 1)
{
fanControl(); // Fucntion to turn the cooling fan on/off
}
//Check whether fuel pump priming is complete
if(!fpPrimed)
{
if(currentStatus.secl >= configPage1.fpPrime)
{
fpPrimed = true; //Mark the priming as being completed
if(currentStatus.RPM == 0) { digitalWrite(pinFuelPump, LOW); fuelPumpOn = false; } //If we reach here then the priming is complete, however only turn off the fuel pump if the engine isn't running
}
}
//**************************************************************************************************************************************************
//Set the flex reading (if enabled). The flexCounter is updated with every pulse from the sensor. If cleared once per second, we get a frequency reading
if(configPage1.flexEnabled == true)
{
if(flexCounter < 50)
{
currentStatus.ethanolPct = 0; //Standard GM Continental sensor reads from 50Hz (0 ethanol) to 150Hz (Pure ethanol). Subtracting 50 from the frequency therefore gives the ethanol percentage.
flexCounter = 0;
}
else if (flexCounter > 151) //1 pulse buffer
{
if(flexCounter < 169)
{
currentStatus.ethanolPct = 100;
flexCounter = 0;
}
else
{
//This indicates an error condition. Spec of the sensor is that errors are above 170Hz)
currentStatus.ethanolPct = 0;
flexCounter = 0;
}
}
else
{
currentStatus.ethanolPct = flexCounter - 50; //Standard GM Continental sensor reads from 50Hz (0 ethanol) to 150Hz (Pure ethanol). Subtracting 50 from the frequency therefore gives the ethanol percentage.
flexCounter = 0;
}
//Off by 1 error check
if (currentStatus.ethanolPct == 1) { currentStatus.ethanolPct = 0; }
}
}
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) //AVR chips use the ISR for this
//Reset Timer2 to trigger in another ~1ms
TCNT2 = 131; //Preload timer2 with 100 cycles, leaving 156 till overflow.
TIFR2 = 0x00; //Timer2 INT Flag Reg: Clear Timer Overflow Flag
#endif
>>>>>>> parent of d8898db... Merge branch 'master' into pr/5
}

View File

@ -62,4 +62,3 @@ void doUpdates()
}
}

File diff suppressed because it is too large Load Diff