Rename all ino files to cpp (Excluding speeduino.ino).

Confirmed this compiles OK in Arduino IDE 2.x
Frees up 8 bytes of RAM
This commit is contained in:
Josh Stewart 2023-10-06 18:10:20 +11:00
parent 977ffa3119
commit fc536d15f0
49 changed files with 508 additions and 624 deletions

View File

@ -4,8 +4,8 @@
* The command handler manages all the inputs FROM TS which are issued when a command button is clicked by the user
*/
#include "TS_CommandButtonHandler.h"
#include "globals.h"
#include "TS_CommandButtonHandler.h"
#include "utilities.h"
#include "scheduledIO.h"
#include "sensors.h"

66
speeduino/acc_mc33810.cpp Normal file
View File

@ -0,0 +1,66 @@
#include "acc_mc33810.h"
#include "globals.h"
#include <SPI.h>
uint8_t MC33810_BIT_INJ1 = 1;
uint8_t MC33810_BIT_INJ2 = 2;
uint8_t MC33810_BIT_INJ3 = 3;
uint8_t MC33810_BIT_INJ4 = 4;
uint8_t MC33810_BIT_INJ5 = 5;
uint8_t MC33810_BIT_INJ6 = 6;
uint8_t MC33810_BIT_INJ7 = 7;
uint8_t MC33810_BIT_INJ8 = 8;
uint8_t MC33810_BIT_IGN1 = 1;
uint8_t MC33810_BIT_IGN2 = 2;
uint8_t MC33810_BIT_IGN3 = 3;
uint8_t MC33810_BIT_IGN4 = 4;
uint8_t MC33810_BIT_IGN5 = 5;
uint8_t MC33810_BIT_IGN6 = 6;
uint8_t MC33810_BIT_IGN7 = 7;
uint8_t MC33810_BIT_IGN8 = 8;
volatile PORT_TYPE *mc33810_1_pin_port;
volatile PINMASK_TYPE mc33810_1_pin_mask;
volatile PORT_TYPE *mc33810_2_pin_port;
volatile PINMASK_TYPE mc33810_2_pin_mask;
void initMC33810(void)
{
//Set pin port/masks
mc33810_1_pin_port = portOutputRegister(digitalPinToPort(pinMC33810_1_CS));
mc33810_1_pin_mask = digitalPinToBitMask(pinMC33810_1_CS);
mc33810_2_pin_port = portOutputRegister(digitalPinToPort(pinMC33810_2_CS));
mc33810_2_pin_mask = digitalPinToBitMask(pinMC33810_2_CS);
//Set the output states of both ICs to be off to fuel and ignition
mc33810_1_requestedState = 0;
mc33810_2_requestedState = 0;
mc33810_1_returnState = 0;
mc33810_2_returnState = 0;
pinMode(pinMC33810_1_CS, OUTPUT);
pinMode(pinMC33810_2_CS, OUTPUT);
SPI.begin();
//These are the SPI settings per the datasheet
SPI.beginTransaction(SPISettings(6000000, MSBFIRST, SPI_MODE0));
//Set the ignition outputs to GPGD mode
/*
0001 = Mode select command
1111 = Set all 1 GD[0...3] outputs to use GPGD mode
00000000 = All remaining values are unused (For us)
*/
//uint16_t cmd = 0b000111110000;
uint16_t cmd = 0b0001111100000000;
//IC1
MC33810_1_ACTIVE();
SPI.transfer16(cmd);
MC33810_1_INACTIVE();
//IC2
MC33810_2_ACTIVE();
SPI.transfer16(cmd);
MC33810_2_INACTIVE();
}

View File

@ -2,18 +2,20 @@
#define MC33810_H
#include <SPI.h>
#include "globals.h"
#include BOARD_H //Note that this is not a real file, it is defined in globals.h.
volatile PORT_TYPE *mc33810_1_pin_port;
volatile PINMASK_TYPE mc33810_1_pin_mask;
volatile PORT_TYPE *mc33810_2_pin_port;
volatile PINMASK_TYPE mc33810_2_pin_mask;
extern volatile PORT_TYPE *mc33810_1_pin_port;
extern volatile PINMASK_TYPE mc33810_1_pin_mask;
extern volatile PORT_TYPE *mc33810_2_pin_port;
extern volatile PINMASK_TYPE mc33810_2_pin_mask;
//#define MC33810_ONOFF_CMD 3
static uint8_t MC33810_ONOFF_CMD = 0x30; //48 in decimal
volatile uint8_t mc33810_1_requestedState; //Current binary state of the 1st ICs IGN and INJ values
volatile uint8_t mc33810_2_requestedState; //Current binary state of the 2nd ICs IGN and INJ values
volatile uint8_t mc33810_1_returnState; //Current binary state of the 1st ICs IGN and INJ values
volatile uint8_t mc33810_2_returnState; //Current binary state of the 2nd ICs IGN and INJ values
static const uint8_t MC33810_ONOFF_CMD = 0x30; //48 in decimal
static volatile uint8_t mc33810_1_requestedState; //Current binary state of the 1st ICs IGN and INJ values
static volatile uint8_t mc33810_2_requestedState; //Current binary state of the 2nd ICs IGN and INJ values
static volatile uint8_t mc33810_1_returnState; //Current binary state of the 1st ICs IGN and INJ values
static volatile uint8_t mc33810_2_returnState; //Current binary state of the 2nd ICs IGN and INJ values
void initMC33810(void);
@ -24,23 +26,23 @@ void initMC33810(void);
//These are default values for which injector is attached to which output on the IC.
//They may (Probably will) be changed during init by the board specific config in init.ino
uint8_t MC33810_BIT_INJ1 = 1;
uint8_t MC33810_BIT_INJ2 = 2;
uint8_t MC33810_BIT_INJ3 = 3;
uint8_t MC33810_BIT_INJ4 = 4;
uint8_t MC33810_BIT_INJ5 = 5;
uint8_t MC33810_BIT_INJ6 = 6;
uint8_t MC33810_BIT_INJ7 = 7;
uint8_t MC33810_BIT_INJ8 = 8;
extern uint8_t MC33810_BIT_INJ1;
extern uint8_t MC33810_BIT_INJ2;
extern uint8_t MC33810_BIT_INJ3;
extern uint8_t MC33810_BIT_INJ4;
extern uint8_t MC33810_BIT_INJ5;
extern uint8_t MC33810_BIT_INJ6;
extern uint8_t MC33810_BIT_INJ7;
extern uint8_t MC33810_BIT_INJ8;
uint8_t MC33810_BIT_IGN1 = 1;
uint8_t MC33810_BIT_IGN2 = 2;
uint8_t MC33810_BIT_IGN3 = 3;
uint8_t MC33810_BIT_IGN4 = 4;
uint8_t MC33810_BIT_IGN5 = 5;
uint8_t MC33810_BIT_IGN6 = 6;
uint8_t MC33810_BIT_IGN7 = 7;
uint8_t MC33810_BIT_IGN8 = 8;
extern uint8_t MC33810_BIT_IGN1;
extern uint8_t MC33810_BIT_IGN2;
extern uint8_t MC33810_BIT_IGN3;
extern uint8_t MC33810_BIT_IGN4;
extern uint8_t MC33810_BIT_IGN5;
extern uint8_t MC33810_BIT_IGN6;
extern uint8_t MC33810_BIT_IGN7;
extern uint8_t MC33810_BIT_IGN8;
#define openInjector1_MC33810() MC33810_1_ACTIVE(); BIT_SET(mc33810_1_requestedState, MC33810_BIT_INJ1); mc33810_1_returnState = SPI.transfer16(word(MC33810_ONOFF_CMD, mc33810_1_requestedState)); MC33810_1_INACTIVE()
#define openInjector2_MC33810() MC33810_1_ACTIVE(); BIT_SET(mc33810_1_requestedState, MC33810_BIT_INJ2); mc33810_1_returnState = SPI.transfer16(word(MC33810_ONOFF_CMD, mc33810_1_requestedState)); MC33810_1_INACTIVE()

View File

@ -1,37 +0,0 @@
#include "acc_mc33810.h"
#include "globals.h"
#include <SPI.h>
void initMC33810(void)
{
//Set the output states of both ICs to be off to fuel and ignition
mc33810_1_requestedState = 0;
mc33810_2_requestedState = 0;
mc33810_1_returnState = 0;
mc33810_2_returnState = 0;
pinMode(pinMC33810_1_CS, OUTPUT);
pinMode(pinMC33810_2_CS, OUTPUT);
SPI.begin();
//These are the SPI settings per the datasheet
SPI.beginTransaction(SPISettings(6000000, MSBFIRST, SPI_MODE0));
//Set the ignition outputs to GPGD mode
/*
0001 = Mode select command
1111 = Set all 1 GD[0...3] outputs to use GPGD mode
00000000 = All remaining values are unused (For us)
*/
//uint16_t cmd = 0b000111110000;
uint16_t cmd = 0b0001111100000000;
//IC1
MC33810_1_ACTIVE();
SPI.transfer16(cmd);
MC33810_1_INACTIVE();
//IC2
MC33810_2_ACTIVE();
SPI.transfer16(cmd);
MC33810_2_INACTIVE();
}

View File

@ -10,12 +10,77 @@ A full copy of the license may be found in the projects root directory
#include "decoders.h"
#include "timers.h"
static long vvt1_pwm_value;
static long vvt2_pwm_value;
volatile unsigned int vvt1_pwm_cur_value;
volatile unsigned int vvt2_pwm_cur_value;
static long vvt_pid_target_angle;
static long vvt2_pid_target_angle;
static long vvt_pid_current_angle;
static long vvt2_pid_current_angle;
volatile bool vvt1_pwm_state;
volatile bool vvt2_pwm_state;
volatile bool vvt1_max_pwm;
volatile bool vvt2_max_pwm;
volatile char nextVVT;
byte boostCounter;
byte vvtCounter;
volatile PORT_TYPE *boost_pin_port;
volatile PINMASK_TYPE boost_pin_mask;
volatile PORT_TYPE *n2o_stage1_pin_port;
volatile PINMASK_TYPE n2o_stage1_pin_mask;
volatile PORT_TYPE *n2o_stage2_pin_port;
volatile PINMASK_TYPE n2o_stage2_pin_mask;
volatile PORT_TYPE *n2o_arming_pin_port;
volatile PINMASK_TYPE n2o_arming_pin_mask;
volatile PORT_TYPE *aircon_comp_pin_port;
volatile PINMASK_TYPE aircon_comp_pin_mask;
volatile PORT_TYPE *aircon_fan_pin_port;
volatile PINMASK_TYPE aircon_fan_pin_mask;
volatile PORT_TYPE *aircon_req_pin_port;
volatile PINMASK_TYPE aircon_req_pin_mask;
volatile PORT_TYPE *vvt1_pin_port;
volatile PINMASK_TYPE vvt1_pin_mask;
volatile PORT_TYPE *vvt2_pin_port;
volatile PINMASK_TYPE vvt2_pin_mask;
volatile PORT_TYPE *fan_pin_port;
volatile PINMASK_TYPE fan_pin_mask;
#if defined(PWM_FAN_AVAILABLE)//PWM fan not available on Arduino MEGA
volatile bool fan_pwm_state;
unsigned int fan_pwm_max_count; //Used for variable PWM frequency
volatile unsigned int fan_pwm_cur_value;
long fan_pwm_value;
#endif
bool acIsEnabled;
bool acStandAloneFanIsEnabled;
uint8_t acStartDelay;
uint8_t acTPSLockoutDelay;
uint8_t acRPMLockoutDelay;
uint8_t acAfterEngineStartDelay;
bool waitedAfterCranking; // This starts false and prevents the A/C from running until a few seconds after cranking
long boost_pwm_target_value;
volatile bool boost_pwm_state;
volatile unsigned int boost_pwm_cur_value = 0;
uint32_t vvtWarmTime;
bool vvtIsHot;
bool vvtTimeHold;
unsigned int vvt_pwm_max_count; //Used for variable PWM frequency
unsigned int boost_pwm_max_count; //Used for variable PWM frequency
//Old PID method. Retained in case the new one has issues
//integerPID boostPID(&MAPx100, &boost_pwm_target_value, &boostTargetx100, configPage6.boostKP, configPage6.boostKI, configPage6.boostKD, DIRECT);
integerPID_ideal boostPID(&currentStatus.MAP, &currentStatus.boostDuty , &currentStatus.boostTarget, &configPage10.boostSens, &configPage10.boostIntv, configPage6.boostKP, configPage6.boostKI, configPage6.boostKD, DIRECT); //This is the PID object if that algorithm is used. Needs to be global as it maintains state outside of each function call
integerPID vvtPID(&vvt_pid_current_angle, &currentStatus.vvt1Duty, &vvt_pid_target_angle, configPage10.vvtCLKP, configPage10.vvtCLKI, configPage10.vvtCLKD, configPage6.vvtPWMdir); //This is the PID object if that algorithm is used. Needs to be global as it maintains state outside of each function call
integerPID vvt2PID(&vvt2_pid_current_angle, &currentStatus.vvt2Duty, &vvt2_pid_target_angle, configPage10.vvtCLKP, configPage10.vvtCLKI, configPage10.vvtCLKD, configPage4.vvt2PWMdir); //This is the PID object if that algorithm is used. Needs to be global as it maintains state outside of each function call
static inline void checkAirConCoolantLockout(void);
static inline void checkAirConTPSLockout(void);
static inline void checkAirConRPMLockout(void);
/*
Air Conditioning Control

View File

@ -20,10 +20,6 @@ void airConControl(void);
bool READ_AIRCON_REQUEST(void);
void wmiControl(void);
static inline void checkAirConCoolantLockout(void);
static inline void checkAirConTPSLockout(void);
static inline void checkAirConRPMLockout(void);
#define SIMPLE_BOOST_P 1
#define SIMPLE_BOOST_I 1
#define SIMPLE_BOOST_D 1
@ -97,69 +93,23 @@ static inline void checkAirConRPMLockout(void);
#define WMI_TANK_IS_EMPTY() ((configPage10.wmiEmptyEnabled) ? ((configPage10.wmiEmptyPolarity) ? digitalRead(pinWMIEmpty) : !digitalRead(pinWMIEmpty)) : 1)
volatile PORT_TYPE *boost_pin_port;
volatile PINMASK_TYPE boost_pin_mask;
volatile PORT_TYPE *vvt1_pin_port;
volatile PINMASK_TYPE vvt1_pin_mask;
volatile PORT_TYPE *vvt2_pin_port;
volatile PINMASK_TYPE vvt2_pin_mask;
volatile PORT_TYPE *fan_pin_port;
volatile PINMASK_TYPE fan_pin_mask;
volatile PORT_TYPE *n2o_stage1_pin_port;
volatile PINMASK_TYPE n2o_stage1_pin_mask;
volatile PORT_TYPE *n2o_stage2_pin_port;
volatile PINMASK_TYPE n2o_stage2_pin_mask;
volatile PORT_TYPE *n2o_arming_pin_port;
volatile PINMASK_TYPE n2o_arming_pin_mask;
volatile PORT_TYPE *aircon_comp_pin_port;
volatile PINMASK_TYPE aircon_comp_pin_mask;
volatile PORT_TYPE *aircon_fan_pin_port;
volatile PINMASK_TYPE aircon_fan_pin_mask;
volatile PORT_TYPE *aircon_req_pin_port;
volatile PINMASK_TYPE aircon_req_pin_mask;
extern volatile PORT_TYPE *vvt1_pin_port;
extern volatile PINMASK_TYPE vvt1_pin_mask;
extern volatile PORT_TYPE *vvt2_pin_port;
extern volatile PINMASK_TYPE vvt2_pin_mask;
extern volatile PORT_TYPE *fan_pin_port;
extern volatile PINMASK_TYPE fan_pin_mask;
volatile bool boost_pwm_state;
unsigned int boost_pwm_max_count; //Used for variable PWM frequency
volatile unsigned int boost_pwm_cur_value;
long boost_pwm_target_value;
long boost_cl_target_boost;
byte boostCounter;
byte vvtCounter;
#if defined(PWM_FAN_AVAILABLE)//PWM fan not available on Arduino MEGA
volatile bool fan_pwm_state;
unsigned int fan_pwm_max_count; //Used for variable PWM frequency
volatile unsigned int fan_pwm_cur_value;
long fan_pwm_value;
extern unsigned int fan_pwm_max_count; //Used for variable PWM frequency
void fanInterrupt(void);
#endif
uint32_t vvtWarmTime;
bool vvtIsHot;
bool vvtTimeHold;
volatile bool vvt1_pwm_state;
volatile bool vvt2_pwm_state;
volatile bool vvt1_max_pwm;
volatile bool vvt2_max_pwm;
volatile char nextVVT;
unsigned int vvt_pwm_max_count; //Used for variable PWM frequency
volatile unsigned int vvt1_pwm_cur_value;
volatile unsigned int vvt2_pwm_cur_value;
long vvt1_pwm_value;
long vvt2_pwm_value;
long vvt_pid_target_angle;
long vvt2_pid_target_angle;
long vvt_pid_current_angle;
long vvt2_pid_current_angle;
extern unsigned int vvt_pwm_max_count; //Used for variable PWM frequency
extern unsigned int boost_pwm_max_count; //Used for variable PWM frequency
void boostInterrupt(void);
void vvtInterrupt(void);
bool acIsEnabled;
bool acStandAloneFanIsEnabled;
uint8_t acStartDelay;
uint8_t acTPSLockoutDelay;
uint8_t acRPMLockoutDelay;
uint8_t acAfterEngineStartDelay;
bool waitedAfterCranking; // This starts false and prevents the A/C from running until a few seconds after cranking
#endif

View File

@ -1,6 +1,5 @@
#if defined(CORE_AVR)
#include "globals.h"
#if defined(CORE_AVR)
#include "auxiliaries.h"
// Prescaler values for timers 1-3-4-5. Refer to www.instructables.com/files/orig/F3T/TIKL/H3WSA4V7/F3TTIKLH3WSA4V7.jpg

View File

@ -1,5 +1,7 @@
#ifndef AVR2560_H
#define AVR2560_H
#include "globals.h"
#if defined(CORE_AVR)
#include <avr/interrupt.h>

View File

@ -1,10 +1,12 @@
#include "board_stm32_official.h"
#if defined(STM32_CORE_VERSION_MAJOR)
#include "globals.h"
#if defined(STM32_CORE_VERSION_MAJOR)
#include "auxiliaries.h"
#include "idle.h"
#include "scheduler.h"
#include "HardwareTimer.h"
#include "timers.h"
#if HAL_CAN_MODULE_ENABLED
//This activates CAN1 interface on STM32, but it's named as Can0, because that's how Teensy implementation is done

View File

@ -1,9 +1,11 @@
#include "globals.h"
#if defined(CORE_TEENSY) && defined(CORE_TEENSY35)
#include "board_teensy35.h"
#include "globals.h"
#include "auxiliaries.h"
#include "idle.h"
#include "scheduler.h"
#include "timers.h"
#if defined(__MK64FX512__) // use for Teensy 3.5 only
FlexCAN_T4<CAN0, RX_SIZE_256, TX_SIZE_16> Can0;

View File

@ -1,14 +1,21 @@
#include "globals.h"
#if defined(CORE_TEENSY) && defined(__IMXRT1062__)
#include "board_teensy41.h"
#include "globals.h"
#include "auxiliaries.h"
#include "idle.h"
#include "scheduler.h"
#include "timers.h"
FlexCAN_T4<CAN1, RX_SIZE_256, TX_SIZE_16> Can0;
FlexCAN_T4<CAN2, RX_SIZE_256, TX_SIZE_16> Can1;
FlexCAN_T4<CAN3, RX_SIZE_256, TX_SIZE_16> Can2;
static void PIT_isr();
static void TMR1_isr(void);
static void TMR2_isr(void);
static void TMR3_isr(void);
static void TMR4_isr(void);
void initBoard()
{
/*

View File

@ -1,5 +1,6 @@
#ifndef TEENSY41_H
#define TEENSY41_H
#if defined(CORE_TEENSY) && defined(__IMXRT1062__)
/*
@ -31,6 +32,7 @@
//#define PWM_FAN_AVAILABLE
#define pinIsReserved(pin) ( ((pin) == 0) || ((pin) == 42) || ((pin) == 43) || ((pin) == 44) || ((pin) == 45) || ((pin) == 46) || ((pin) == 47) ) //Forbidden pins like USB
/*
***********************************************************************************************************
* Schedules

View File

@ -1,5 +1,6 @@
#if defined(CORE_TEMPLATE)
#include "globals.h"
#if defined(CORE_TEMPLATE)
void initBoard()
{

View File

@ -7,8 +7,9 @@ A full copy of the license may be found in the projects root directory
/*
This is for handling the data broadcasted to various CAN dashes and instrument clusters.
*/
#if defined(NATIVE_CAN_AVAILABLE)
#include "globals.h"
#if defined(NATIVE_CAN_AVAILABLE)
#include "canBroadcast.h"
// Forward declare
void DashMessage(uint16_t DashMessageID);

View File

@ -19,6 +19,7 @@ A full copy of the license may be found in the projects root directory
#include "page_crc.h"
#include "logger.h"
#include "table3d_axis_io.h"
#include BOARD_H
#ifdef RTC_ENABLED
#include "rtc_common.h"
#endif

View File

@ -2,6 +2,7 @@
#define CRANKMATHS_H
#include "maths.h"
#include "globals.h"
#define CRANKMATH_METHOD_INTERVAL_DEFAULT 0
#define CRANKMATH_METHOD_INTERVAL_REV 1

View File

@ -1,6 +0,0 @@
#include <SPI.h>
#include <Wire.h>
void initialiseDisplay();

View File

@ -1,196 +0,0 @@
/*
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
*/
#ifdef USE_DISPLAY
#include <SPI.h>
#include <Wire.h>
#include "src/Adafruit_SSD1306/Adafruit_GFX.h"
#include "src/Adafruit_SSD1306/Adafruit_SSD1306.h"
Adafruit_SSD1306 display(pinDisplayReset);
void initialiseDisplay()
{
//Protection against older pin mappings where the crank/cam signals were on the SDA and SCL pins. This will cause the Arduino to lock hard if you try to initialise i2c devices when a crank signal is coming in
if(pinTrigger == 20 || pinTrigger == 21 || pinTrigger2 == 20 || pinTrigger2 == 21) { return; }
switch(configPage1.displayType)
{
case 1:
display.SSD1306_SETCOMPINS_V = 0x02;
break;
case 2:
display.SSD1306_SETCOMPINS_V = 0x12;
break;
case 3:
display.SSD1306_SETCOMPINS_V = 0x12;
break;
case 4:
display.SSD1306_SETCOMPINS_V = 0x12;
break;
}
display.begin(SSD1306_SWITCHCAPVCC, 0x3C); // initialise with the I2C addr 0x3C (for the 128x32)
display.clearDisplay();
display.setTextSize(1);
display.setTextColor(WHITE);
display.setCursor(0,0);
display.print("RPM: ");
display.setCursor(0,16);
display.print("CPU: ");
}
void updateDisplay()
{
display.clearDisplay();
display.setCursor(0,0);
switch(configPage1.display1)
{
case 0:
display.print("RPM: ");
display.setCursor(28,0);
display.print(currentStatus.RPM);
break;
case 1:
display.print("PW: ");
display.setCursor(28,0);
display.print(currentStatus.PW1);
break;
case 2:
display.print("Adv: ");
display.setCursor(28,0);
display.print(currentStatus.advance);
break;
case 3:
display.print("VE: ");
display.setCursor(28,0);
display.print(currentStatus.VE);
break;
case 4:
display.print("GamE: ");
display.setCursor(28,0);
display.print(currentStatus.corrections);
break;
case 5:
display.print("TPS: ");
display.setCursor(28,0);
display.print(currentStatus.TPS);
break;
case 6:
display.print("IAT: ");
display.setCursor(28,0);
display.print(currentStatus.IAT);
break;
case 7:
display.print("CLT: ");
display.setCursor(28,0);
display.print(currentStatus.coolant);
break;
}
display.setCursor(0,11);
switch(configPage1.display3)
{
case 0:
display.print("RPM: ");
display.setCursor(28,11);
display.print(currentStatus.RPM);
break;
case 1:
display.print("PW: ");
display.setCursor(28,11);
display.print(currentStatus.PW1);
break;
case 2:
display.print("Adv: ");
display.setCursor(28,11);
display.print(currentStatus.advance);
break;
case 3:
display.print("VE: ");
display.setCursor(28,11);
display.print(currentStatus.VE);
break;
case 4:
display.print("GamE: ");
display.setCursor(28,11);
display.print(currentStatus.corrections);
break;
case 5:
display.print("TPS: ");
display.setCursor(28,11);
display.print(currentStatus.TPS);
break;
case 6:
display.print("IAT: ");
display.setCursor(28,11);
display.print(currentStatus.IAT);
break;
case 7:
display.print("CLT: ");
display.setCursor(28,11);
display.print(currentStatus.coolant);
break;
}
display.setCursor(64,0);
switch(configPage1.display2)
{
case 0:
display.print("O2: ");
display.setCursor(92,0);
display.print(currentStatus.O2);
break;
case 1:
display.print("Vdc: ");
display.setCursor(92,0);
display.print(currentStatus.battery10);
break;
case 2:
display.print("CPU: ");
display.setCursor(92,0);
display.print(currentStatus.loopsPerSecond);
break;
case 3:
display.print("Mem: ");
display.setCursor(92,0);
display.print(currentStatus.freeRAM);
break;
}
display.setCursor(64,11);
switch(configPage1.display4)
{
case 0:
display.print("O2: ");
display.setCursor(92,11);
display.print(currentStatus.O2);
break;
case 1:
display.print("Vdc: ");
display.setCursor(92,11);
display.print(currentStatus.battery10);
break;
case 2:
display.print("CPU: ");
display.setCursor(92,11);
display.print(currentStatus.loopsPerSecond);
break;
case 3:
display.print("Mem: ");
display.setCursor(92,11);
display.print(currentStatus.freeRAM);
break;
}
int barWidth = ldiv(((unsigned long)currentStatus.RPM * 128), 9000).quot;
//int barWidth = map(currentStatus.RPM, 0, 9000, 0, 128);
display.fillRect(0, 20, barWidth, 10, 1);
display.display();
}
#endif

View File

@ -260,7 +260,7 @@ uint8_t o2Calibration_values[32];
struct table2D o2CalibrationTable;
//These function do checks on a pin to determine if it is already in use by another (higher importance) active function
inline bool pinIsOutput(byte pin)
bool pinIsOutput(byte pin)
{
bool used = false;
bool isIdlePWM = (configPage6.iacAlgorithm > 0) && ((configPage6.iacAlgorithm <= 3) || (configPage6.iacAlgorithm == 6));
@ -313,7 +313,7 @@ inline bool pinIsOutput(byte pin)
return used;
}
inline bool pinIsUsed(byte pin)
bool pinIsUsed(byte pin)
{
bool used = false;

View File

@ -8,6 +8,40 @@ A full copy of the license may be found in the projects root directory
#include "timers.h"
#include "src/PID_v1/PID_v1.h"
byte idleUpOutputHIGH = HIGH; // Used to invert the idle Up Output
byte idleUpOutputLOW = LOW; // Used to invert the idle Up Output
byte idleCounter; //Used for tracking the number of calls to the idle control function
uint8_t idleTaper;
struct StepperIdle idleStepper;
bool idleOn; //Simply tracks whether idle was on last time around
byte idleInitComplete = 99; //Tracks which idle method was initialised. 99 is a method that will never exist
unsigned int iacStepTime_uS;
unsigned int iacCoolTime_uS;
unsigned int completedHomeSteps;
volatile bool idle_pwm_state;
bool lastDFCOValue;
unsigned int idle_pwm_max_count; //Used for variable PWM frequency
volatile unsigned int idle_pwm_cur_value;
long idle_pid_target_value;
long FeedForwardTerm;
unsigned long idle_pwm_target_value;
long idle_cl_target_rpm;
volatile PORT_TYPE *idle_pin_port;
volatile PINMASK_TYPE idle_pin_mask;
volatile PORT_TYPE *idle2_pin_port;
volatile PINMASK_TYPE idle2_pin_mask;
volatile PORT_TYPE *idleUpOutput_pin_port;
volatile PINMASK_TYPE idleUpOutput_pin_mask;
struct table2D iacPWMTable;
struct table2D iacStepTable;
//Open loop tables specifically for cranking
struct table2D iacCrankStepsTable;
struct table2D iacCrankDutyTable;
/*
These functions cover the PWM and stepper idle control
*/

View File

@ -36,39 +36,8 @@ struct StepperIdle
byte moreAirDirection;
};
struct table2D iacPWMTable;
struct table2D iacStepTable;
//Open loop tables specifically for cranking
struct table2D iacCrankStepsTable;
struct table2D iacCrankDutyTable;
struct StepperIdle idleStepper;
bool idleOn; //Simply tracks whether idle was on last time around
byte idleInitComplete = 99; //Tracks which idle method was initialised. 99 is a method that will never exist
unsigned int iacStepTime_uS;
unsigned int iacCoolTime_uS;
unsigned int completedHomeSteps;
volatile PORT_TYPE *idle_pin_port;
volatile PINMASK_TYPE idle_pin_mask;
volatile PORT_TYPE *idle2_pin_port;
volatile PINMASK_TYPE idle2_pin_mask;
volatile PORT_TYPE *idleUpOutput_pin_port;
volatile PINMASK_TYPE idleUpOutput_pin_mask;
volatile bool idle_pwm_state;
bool lastDFCOValue;
unsigned int idle_pwm_max_count; //Used for variable PWM frequency
volatile unsigned int idle_pwm_cur_value;
long idle_pid_target_value;
long FeedForwardTerm;
unsigned long idle_pwm_target_value;
long idle_cl_target_rpm;
byte idleCounter; //Used for tracking the number of calls to the idle control function
uint8_t idleTaper;
byte idleUpOutputHIGH = HIGH; // Used to invert the idle Up Output
byte idleUpOutputLOW = LOW; // Used to invert the idle Up Output
extern unsigned int idle_pwm_max_count; //Used for variable PWM frequency
extern long FeedForwardTerm;
void initialiseIdle(bool forcehoming);
void idleControl(void);

View File

@ -20,7 +20,9 @@
#include "table2d.h"
#include "acc_mc33810.h"
#include BOARD_H //Note that this is not a real file, it is defined in globals.h.
#include EEPROM_LIB_H
#if defined(EEPROM_RESET_PIN)
#include EEPROM_LIB_H
#endif
#ifdef SD_LOGGING
#include "SD_logger.h"
#include "rtc_common.h"
@ -2916,11 +2918,6 @@ void setPinMapping(byte boardID)
if( (ignitionOutputControl == OUTPUT_CONTROL_MC33810) || (injectorOutputControl == OUTPUT_CONTROL_MC33810) )
{
mc33810_1_pin_port = portOutputRegister(digitalPinToPort(pinMC33810_1_CS));
mc33810_1_pin_mask = digitalPinToBitMask(pinMC33810_1_CS);
mc33810_2_pin_port = portOutputRegister(digitalPinToPort(pinMC33810_2_CS));
mc33810_2_pin_mask = digitalPinToBitMask(pinMC33810_2_CS);
initMC33810();
}

View File

@ -5,6 +5,7 @@
#include "init.h"
#include "maths.h"
#include "utilities.h"
#include BOARD_H
/**
* Returns a numbered byte-field (partial field in case of multi-byte fields) from "current status" structure in the format expected by TunerStudio

View File

@ -1,6 +1,8 @@
#ifndef MATH_H
#define MATH_H
#include "globals.h"
unsigned long percentage(uint8_t x, unsigned long y);
unsigned long halfPercentage(uint8_t x, unsigned long y);
inline long powint(int factor, unsigned int exponent);

132
speeduino/scheduledIO.cpp Normal file
View File

@ -0,0 +1,132 @@
#include "scheduledIO.h"
#include "scheduler.h"
#include "globals.h"
#include "timers.h"
#include "acc_mc33810.h"
/** @file
* Injector and Coil (toggle/open/close) control (under various situations, eg with particular cylinder count, rotary engine type or wasted spark ign, etc.).
* Also accounts for presence of MC33810 injector/ignition (dwell, etc.) control circuit.
* Functions here are typically assigned (at initialisation) to callback function variables (e.g. inj1StartFunction or inj1EndFunction)
* form where they are called (by scheduler.ino).
*/
void openInjector1(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector1_DIRECT(); } else { openInjector1_MC33810(); } }
void closeInjector1(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector1_DIRECT(); } else { closeInjector1_MC33810(); } }
void openInjector2(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector2_DIRECT(); } else { openInjector2_MC33810(); } }
void closeInjector2(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector2_DIRECT(); } else { closeInjector2_MC33810(); } }
void openInjector3(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector3_DIRECT(); } else { openInjector3_MC33810(); } }
void closeInjector3(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector3_DIRECT(); } else { closeInjector3_MC33810(); } }
void openInjector4(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector4_DIRECT(); } else { openInjector4_MC33810(); } }
void closeInjector4(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector4_DIRECT(); } else { closeInjector4_MC33810(); } }
void openInjector5(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector5_DIRECT(); } else { openInjector5_MC33810(); } }
void closeInjector5(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector5_DIRECT(); } else { closeInjector5_MC33810(); } }
void openInjector6(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector6_DIRECT(); } else { openInjector6_MC33810(); } }
void closeInjector6(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector6_DIRECT(); } else { closeInjector6_MC33810(); } }
void openInjector7(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector7_DIRECT(); } else { openInjector7_MC33810(); } }
void closeInjector7(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector7_DIRECT(); } else { closeInjector7_MC33810(); } }
void openInjector8(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector8_DIRECT(); } else { openInjector8_MC33810(); } }
void closeInjector8(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector8_DIRECT(); } else { closeInjector8_MC33810(); } }
void injector1Toggle(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector1Toggle_DIRECT(); } else { injector1Toggle_MC33810(); } }
void injector2Toggle(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector2Toggle_DIRECT(); } else { injector2Toggle_MC33810(); } }
void injector3Toggle(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector3Toggle_DIRECT(); } else { injector3Toggle_MC33810(); } }
void injector4Toggle(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector4Toggle_DIRECT(); } else { injector4Toggle_MC33810(); } }
void injector5Toggle(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector5Toggle_DIRECT(); } else { injector5Toggle_MC33810(); } }
void injector6Toggle(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector6Toggle_DIRECT(); } else { injector6Toggle_MC33810(); } }
void injector7Toggle(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector7Toggle_DIRECT(); } else { injector7Toggle_MC33810(); } }
void injector8Toggle(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector8Toggle_DIRECT(); } else { injector8Toggle_MC33810(); } }
void coil1Toggle(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil1Toggle_DIRECT(); } else { coil1Toggle_MC33810(); } }
void coil2Toggle(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil2Toggle_DIRECT(); } else { coil2Toggle_MC33810(); } }
void coil3Toggle(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil3Toggle_DIRECT(); } else { coil3Toggle_MC33810(); } }
void coil4Toggle(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil4Toggle_DIRECT(); } else { coil4Toggle_MC33810(); } }
void coil5Toggle(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil5Toggle_DIRECT(); } else { coil5Toggle_MC33810(); } }
void coil6Toggle(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil6Toggle_DIRECT(); } else { coil6Toggle_MC33810(); } }
void coil7Toggle(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil7Toggle_DIRECT(); } else { coil7Toggle_MC33810(); } }
void coil8Toggle(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil8Toggle_DIRECT(); } else { coil8Toggle_MC33810(); } }
// These are for Semi-Sequential and 5 Cylinder injection
//Standard 4 cylinder pairings
void openInjector1and3(void) { openInjector1(); openInjector3(); }
void closeInjector1and3(void) { closeInjector1(); closeInjector3(); }
void openInjector2and4(void) { openInjector2(); openInjector4(); }
void closeInjector2and4(void) { closeInjector2(); closeInjector4(); }
//Alternative output pairings
void openInjector1and4(void) { openInjector1(); openInjector4(); }
void closeInjector1and4(void) { closeInjector1(); closeInjector4(); }
void openInjector2and3(void) { openInjector2(); openInjector3(); }
void closeInjector2and3(void) { closeInjector2(); closeInjector3(); }
void openInjector3and5(void) { openInjector3(); openInjector5(); }
void closeInjector3and5(void) { closeInjector3(); closeInjector5(); }
void openInjector2and5(void) { openInjector2(); openInjector5(); }
void closeInjector2and5(void) { closeInjector2(); closeInjector5(); }
void openInjector3and6(void) { openInjector3(); openInjector6(); }
void closeInjector3and6(void) { closeInjector3(); closeInjector6(); }
void openInjector1and5(void) { openInjector1(); openInjector5(); }
void closeInjector1and5(void) { closeInjector1(); closeInjector5(); }
void openInjector2and6(void) { openInjector2(); openInjector6(); }
void closeInjector2and6(void) { closeInjector2(); closeInjector6(); }
void openInjector3and7(void) { openInjector3(); openInjector7(); }
void closeInjector3and7(void) { closeInjector3(); closeInjector7(); }
void openInjector4and8(void) { openInjector4(); openInjector8(); }
void closeInjector4and8(void) { closeInjector4(); closeInjector8(); }
void beginCoil1Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil1Charging_DIRECT(); } else { coil1Charging_MC33810(); } tachoOutputOn(); }
void endCoil1Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil1StopCharging_DIRECT(); } else { coil1StopCharging_MC33810(); } tachoOutputOff(); }
void beginCoil2Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil2Charging_DIRECT(); } else { coil2Charging_MC33810(); } tachoOutputOn(); }
void endCoil2Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil2StopCharging_DIRECT(); } else { coil2StopCharging_MC33810(); } tachoOutputOff(); }
void beginCoil3Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil3Charging_DIRECT(); } else { coil3Charging_MC33810(); } tachoOutputOn(); }
void endCoil3Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil3StopCharging_DIRECT(); } else { coil3StopCharging_MC33810(); } tachoOutputOff(); }
void beginCoil4Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil4Charging_DIRECT(); } else { coil4Charging_MC33810(); } tachoOutputOn(); }
void endCoil4Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil4StopCharging_DIRECT(); } else { coil4StopCharging_MC33810(); } tachoOutputOff(); }
void beginCoil5Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil5Charging_DIRECT(); } else { coil5Charging_MC33810(); } tachoOutputOn(); }
void endCoil5Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil5StopCharging_DIRECT(); } else { coil5StopCharging_MC33810(); } tachoOutputOff(); }
void beginCoil6Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil6Charging_DIRECT(); } else { coil6Charging_MC33810(); } tachoOutputOn(); }
void endCoil6Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil6StopCharging_DIRECT(); } else { coil6StopCharging_MC33810(); } tachoOutputOff(); }
void beginCoil7Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil7Charging_DIRECT(); } else { coil7Charging_MC33810(); } tachoOutputOn(); }
void endCoil7Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil7StopCharging_DIRECT(); } else { coil7StopCharging_MC33810(); } tachoOutputOff(); }
void beginCoil8Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil8Charging_DIRECT(); } else { coil8Charging_MC33810(); } tachoOutputOn(); }
void endCoil8Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil8StopCharging_DIRECT(); } else { coil8StopCharging_MC33810(); } tachoOutputOff(); }
//The below 3 calls are all part of the rotary ignition mode
void beginTrailingCoilCharge(void) { beginCoil2Charge(); }
void endTrailingCoilCharge1(void) { endCoil2Charge(); beginCoil3Charge(); } //Sets ign3 (Trailing select) high
void endTrailingCoilCharge2(void) { endCoil2Charge(); endCoil3Charge(); } //sets ign3 (Trailing select) low
//As above but for ignition (Wasted COP mode)
void beginCoil1and3Charge(void) { beginCoil1Charge(); beginCoil3Charge(); }
void endCoil1and3Charge(void) { endCoil1Charge(); endCoil3Charge(); }
void beginCoil2and4Charge(void) { beginCoil2Charge(); beginCoil4Charge(); }
void endCoil2and4Charge(void) { endCoil2Charge(); endCoil4Charge(); }
//For 6cyl wasted COP mode)
void beginCoil1and4Charge(void) { beginCoil1Charge(); beginCoil4Charge(); }
void endCoil1and4Charge(void) { endCoil1Charge(); endCoil4Charge(); }
void beginCoil2and5Charge(void) { beginCoil2Charge(); beginCoil5Charge(); }
void endCoil2and5Charge(void) { endCoil2Charge(); endCoil5Charge(); }
void beginCoil3and6Charge(void) { beginCoil3Charge(); beginCoil6Charge(); }
void endCoil3and6Charge(void) { endCoil3Charge(); endCoil6Charge(); }
//For 8cyl wasted COP mode)
void beginCoil1and5Charge(void) { beginCoil1Charge(); beginCoil5Charge(); }
void endCoil1and5Charge(void) { endCoil1Charge(); endCoil5Charge(); }
void beginCoil2and6Charge(void) { beginCoil2Charge(); beginCoil6Charge(); }
void endCoil2and6Charge(void) { endCoil2Charge(); endCoil6Charge(); }
void beginCoil3and7Charge(void) { beginCoil3Charge(); beginCoil7Charge(); }
void endCoil3and7Charge(void) { endCoil3Charge(); endCoil7Charge(); }
void beginCoil4and8Charge(void) { beginCoil4Charge(); beginCoil8Charge(); }
void endCoil4and8Charge(void) { endCoil4Charge(); endCoil8Charge(); }
void tachoOutputOn(void) { if(configPage6.tachoMode) { TACHO_PULSE_LOW(); } else { tachoOutputFlag = READY; } }
void tachoOutputOff(void) { if(configPage6.tachoMode) { TACHO_PULSE_HIGH(); } }
void nullCallback(void) { return; }

View File

@ -3,29 +3,29 @@
#include <Arduino.h>
inline void openInjector1(void);
inline void closeInjector1(void);
void openInjector1(void);
void closeInjector1(void);
inline void openInjector2(void);
inline void closeInjector2(void);
void openInjector2(void);
void closeInjector2(void);
inline void openInjector3(void);
inline void closeInjector3(void);
void openInjector3(void);
void closeInjector3(void);
inline void openInjector4(void);
inline void closeInjector4(void);
void openInjector4(void);
void closeInjector4(void);
inline void openInjector5(void);
inline void closeInjector5(void);
void openInjector5(void);
void closeInjector5(void);
inline void openInjector6(void);
inline void closeInjector6(void);
void openInjector6(void);
void closeInjector6(void);
inline void openInjector7(void);
inline void closeInjector7(void);
void openInjector7(void);
void closeInjector7(void);
inline void openInjector8(void);
inline void closeInjector8(void);
void openInjector8(void);
void closeInjector8(void);
// These are for Semi-Sequential and 5 Cylinder injection
void openInjector1and3(void);
@ -63,34 +63,34 @@ void injector6Toggle(void);
void injector7Toggle(void);
void injector8Toggle(void);
inline void beginCoil1Charge(void);
inline void endCoil1Charge(void);
void beginCoil1Charge(void);
void endCoil1Charge(void);
inline void beginCoil2Charge(void);
inline void endCoil2Charge(void);
void beginCoil2Charge(void);
void endCoil2Charge(void);
inline void beginCoil3Charge(void);
inline void endCoil3Charge(void);
void beginCoil3Charge(void);
void endCoil3Charge(void);
inline void beginCoil4Charge(void);
inline void endCoil4Charge(void);
void beginCoil4Charge(void);
void endCoil4Charge(void);
inline void beginCoil5Charge(void);
inline void endCoil5Charge(void);
void beginCoil5Charge(void);
void endCoil5Charge(void);
inline void beginCoil6Charge(void);
inline void endCoil6Charge(void);
void beginCoil6Charge(void);
void endCoil6Charge(void);
inline void beginCoil7Charge(void);
inline void endCoil7Charge(void);
void beginCoil7Charge(void);
void endCoil7Charge(void);
inline void beginCoil8Charge(void);
inline void endCoil8Charge(void);
void beginCoil8Charge(void);
void endCoil8Charge(void);
//The following functions are used specifically for the trailing coil on rotary engines. They are separate as they also control the switching of the trailing select pin
inline void beginTrailingCoilCharge(void);
inline void endTrailingCoilCharge1(void);
inline void endTrailingCoilCharge2(void);
void beginTrailingCoilCharge(void);
void endTrailingCoilCharge1(void);
void endTrailingCoilCharge2(void);
//And the combined versions of the above for simplicity
void beginCoil1and3Charge(void);

View File

@ -1,132 +0,0 @@
#include "scheduledIO.h"
#include "scheduler.h"
#include "globals.h"
#include "timers.h"
#include "acc_mc33810.h"
/** @file
* Injector and Coil (toggle/open/close) control (under various situations, eg with particular cylinder count, rotary engine type or wasted spark ign, etc.).
* Also accounts for presence of MC33810 injector/ignition (dwell, etc.) control circuit.
* Functions here are typically assigned (at initialisation) to callback function variables (e.g. inj1StartFunction or inj1EndFunction)
* form where they are called (by scheduler.ino).
*/
inline void openInjector1(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector1_DIRECT(); } else { openInjector1_MC33810(); } }
inline void closeInjector1(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector1_DIRECT(); } else { closeInjector1_MC33810(); } }
inline void openInjector2(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector2_DIRECT(); } else { openInjector2_MC33810(); } }
inline void closeInjector2(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector2_DIRECT(); } else { closeInjector2_MC33810(); } }
inline void openInjector3(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector3_DIRECT(); } else { openInjector3_MC33810(); } }
inline void closeInjector3(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector3_DIRECT(); } else { closeInjector3_MC33810(); } }
inline void openInjector4(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector4_DIRECT(); } else { openInjector4_MC33810(); } }
inline void closeInjector4(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector4_DIRECT(); } else { closeInjector4_MC33810(); } }
inline void openInjector5(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector5_DIRECT(); } else { openInjector5_MC33810(); } }
inline void closeInjector5(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector5_DIRECT(); } else { closeInjector5_MC33810(); } }
inline void openInjector6(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector6_DIRECT(); } else { openInjector6_MC33810(); } }
inline void closeInjector6(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector6_DIRECT(); } else { closeInjector6_MC33810(); } }
inline void openInjector7(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector7_DIRECT(); } else { openInjector7_MC33810(); } }
inline void closeInjector7(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector7_DIRECT(); } else { closeInjector7_MC33810(); } }
inline void openInjector8(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector8_DIRECT(); } else { openInjector8_MC33810(); } }
inline void closeInjector8(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector8_DIRECT(); } else { closeInjector8_MC33810(); } }
inline void injector1Toggle(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector1Toggle_DIRECT(); } else { injector1Toggle_MC33810(); } }
inline void injector2Toggle(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector2Toggle_DIRECT(); } else { injector2Toggle_MC33810(); } }
inline void injector3Toggle(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector3Toggle_DIRECT(); } else { injector3Toggle_MC33810(); } }
inline void injector4Toggle(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector4Toggle_DIRECT(); } else { injector4Toggle_MC33810(); } }
inline void injector5Toggle(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector5Toggle_DIRECT(); } else { injector5Toggle_MC33810(); } }
inline void injector6Toggle(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector6Toggle_DIRECT(); } else { injector6Toggle_MC33810(); } }
inline void injector7Toggle(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector7Toggle_DIRECT(); } else { injector7Toggle_MC33810(); } }
inline void injector8Toggle(void) { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector8Toggle_DIRECT(); } else { injector8Toggle_MC33810(); } }
inline void coil1Toggle(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil1Toggle_DIRECT(); } else { coil1Toggle_MC33810(); } }
inline void coil2Toggle(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil2Toggle_DIRECT(); } else { coil2Toggle_MC33810(); } }
inline void coil3Toggle(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil3Toggle_DIRECT(); } else { coil3Toggle_MC33810(); } }
inline void coil4Toggle(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil4Toggle_DIRECT(); } else { coil4Toggle_MC33810(); } }
inline void coil5Toggle(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil5Toggle_DIRECT(); } else { coil5Toggle_MC33810(); } }
inline void coil6Toggle(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil6Toggle_DIRECT(); } else { coil6Toggle_MC33810(); } }
inline void coil7Toggle(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil7Toggle_DIRECT(); } else { coil7Toggle_MC33810(); } }
inline void coil8Toggle(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil8Toggle_DIRECT(); } else { coil8Toggle_MC33810(); } }
// These are for Semi-Sequential and 5 Cylinder injection
//Standard 4 cylinder pairings
void openInjector1and3(void) { openInjector1(); openInjector3(); }
void closeInjector1and3(void) { closeInjector1(); closeInjector3(); }
void openInjector2and4(void) { openInjector2(); openInjector4(); }
void closeInjector2and4(void) { closeInjector2(); closeInjector4(); }
//Alternative output pairings
void openInjector1and4(void) { openInjector1(); openInjector4(); }
void closeInjector1and4(void) { closeInjector1(); closeInjector4(); }
void openInjector2and3(void) { openInjector2(); openInjector3(); }
void closeInjector2and3(void) { closeInjector2(); closeInjector3(); }
void openInjector3and5(void) { openInjector3(); openInjector5(); }
void closeInjector3and5(void) { closeInjector3(); closeInjector5(); }
void openInjector2and5(void) { openInjector2(); openInjector5(); }
void closeInjector2and5(void) { closeInjector2(); closeInjector5(); }
void openInjector3and6(void) { openInjector3(); openInjector6(); }
void closeInjector3and6(void) { closeInjector3(); closeInjector6(); }
void openInjector1and5(void) { openInjector1(); openInjector5(); }
void closeInjector1and5(void) { closeInjector1(); closeInjector5(); }
void openInjector2and6(void) { openInjector2(); openInjector6(); }
void closeInjector2and6(void) { closeInjector2(); closeInjector6(); }
void openInjector3and7(void) { openInjector3(); openInjector7(); }
void closeInjector3and7(void) { closeInjector3(); closeInjector7(); }
void openInjector4and8(void) { openInjector4(); openInjector8(); }
void closeInjector4and8(void) { closeInjector4(); closeInjector8(); }
inline void beginCoil1Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil1Charging_DIRECT(); } else { coil1Charging_MC33810(); } tachoOutputOn(); }
inline void endCoil1Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil1StopCharging_DIRECT(); } else { coil1StopCharging_MC33810(); } tachoOutputOff(); }
inline void beginCoil2Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil2Charging_DIRECT(); } else { coil2Charging_MC33810(); } tachoOutputOn(); }
inline void endCoil2Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil2StopCharging_DIRECT(); } else { coil2StopCharging_MC33810(); } tachoOutputOff(); }
inline void beginCoil3Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil3Charging_DIRECT(); } else { coil3Charging_MC33810(); } tachoOutputOn(); }
inline void endCoil3Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil3StopCharging_DIRECT(); } else { coil3StopCharging_MC33810(); } tachoOutputOff(); }
inline void beginCoil4Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil4Charging_DIRECT(); } else { coil4Charging_MC33810(); } tachoOutputOn(); }
inline void endCoil4Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil4StopCharging_DIRECT(); } else { coil4StopCharging_MC33810(); } tachoOutputOff(); }
inline void beginCoil5Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil5Charging_DIRECT(); } else { coil5Charging_MC33810(); } tachoOutputOn(); }
inline void endCoil5Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil5StopCharging_DIRECT(); } else { coil5StopCharging_MC33810(); } tachoOutputOff(); }
inline void beginCoil6Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil6Charging_DIRECT(); } else { coil6Charging_MC33810(); } tachoOutputOn(); }
inline void endCoil6Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil6StopCharging_DIRECT(); } else { coil6StopCharging_MC33810(); } tachoOutputOff(); }
inline void beginCoil7Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil7Charging_DIRECT(); } else { coil7Charging_MC33810(); } tachoOutputOn(); }
inline void endCoil7Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil7StopCharging_DIRECT(); } else { coil7StopCharging_MC33810(); } tachoOutputOff(); }
inline void beginCoil8Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil8Charging_DIRECT(); } else { coil8Charging_MC33810(); } tachoOutputOn(); }
inline void endCoil8Charge(void) { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil8StopCharging_DIRECT(); } else { coil8StopCharging_MC33810(); } tachoOutputOff(); }
//The below 3 calls are all part of the rotary ignition mode
inline void beginTrailingCoilCharge(void) { beginCoil2Charge(); }
inline void endTrailingCoilCharge1(void) { endCoil2Charge(); beginCoil3Charge(); } //Sets ign3 (Trailing select) high
inline void endTrailingCoilCharge2(void) { endCoil2Charge(); endCoil3Charge(); } //sets ign3 (Trailing select) low
//As above but for ignition (Wasted COP mode)
void beginCoil1and3Charge(void) { beginCoil1Charge(); beginCoil3Charge(); }
void endCoil1and3Charge(void) { endCoil1Charge(); endCoil3Charge(); }
void beginCoil2and4Charge(void) { beginCoil2Charge(); beginCoil4Charge(); }
void endCoil2and4Charge(void) { endCoil2Charge(); endCoil4Charge(); }
//For 6cyl wasted COP mode)
void beginCoil1and4Charge(void) { beginCoil1Charge(); beginCoil4Charge(); }
void endCoil1and4Charge(void) { endCoil1Charge(); endCoil4Charge(); }
void beginCoil2and5Charge(void) { beginCoil2Charge(); beginCoil5Charge(); }
void endCoil2and5Charge(void) { endCoil2Charge(); endCoil5Charge(); }
void beginCoil3and6Charge(void) { beginCoil3Charge(); beginCoil6Charge(); }
void endCoil3and6Charge(void) { endCoil3Charge(); endCoil6Charge(); }
//For 8cyl wasted COP mode)
void beginCoil1and5Charge(void) { beginCoil1Charge(); beginCoil5Charge(); }
void endCoil1and5Charge(void) { endCoil1Charge(); endCoil5Charge(); }
void beginCoil2and6Charge(void) { beginCoil2Charge(); beginCoil6Charge(); }
void endCoil2and6Charge(void) { endCoil2Charge(); endCoil6Charge(); }
void beginCoil3and7Charge(void) { beginCoil3Charge(); beginCoil7Charge(); }
void endCoil3and7Charge(void) { endCoil3Charge(); endCoil7Charge(); }
void beginCoil4and8Charge(void) { beginCoil4Charge(); beginCoil8Charge(); }
void endCoil4and8Charge(void) { endCoil4Charge(); endCoil8Charge(); }
void tachoOutputOn(void) { if(configPage6.tachoMode) { TACHO_PULSE_LOW(); } else { tachoOutputFlag = READY; } }
void tachoOutputOff(void) { if(configPage6.tachoMode) { TACHO_PULSE_HIGH(); } }
void nullCallback(void) { return; }

View File

@ -639,7 +639,7 @@ void setIgnitionSchedule1(void (*startCallback)(), unsigned long timeout, unsign
}
}
inline void refreshIgnitionSchedule1(unsigned long timeToEnd)
void refreshIgnitionSchedule1(unsigned long timeToEnd)
{
if( (ignitionSchedule1.Status == RUNNING) && (timeToEnd < ignitionSchedule1.duration) )
//Must have the threshold check here otherwise it can cause a condition where the compare fires twice, once after the other, both for the end
@ -944,7 +944,7 @@ extern void beginInjectorPriming(void)
//fuelSchedules 1 and 5
ISR(TIMER3_COMPA_vect) //cppcheck-suppress misra-c2012-8.2
#else
inline void fuelSchedule1Interrupt(void)
void fuelSchedule1Interrupt(void)
#endif
{
if (fuelSchedule1.Status == PENDING) //Check to see if this schedule is turn on
@ -981,7 +981,7 @@ inline void fuelSchedule1Interrupt(void)
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega2561__) //AVR chips use the ISR for this
ISR(TIMER3_COMPB_vect) //cppcheck-suppress misra-c2012-8.2
#else
inline void fuelSchedule2Interrupt(void)
void fuelSchedule2Interrupt(void)
#endif
{
if (fuelSchedule2.Status == PENDING) //Check to see if this schedule is turn on
@ -1016,7 +1016,7 @@ inline void fuelSchedule2Interrupt(void)
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega2561__) //AVR chips use the ISR for this
ISR(TIMER3_COMPC_vect) //cppcheck-suppress misra-c2012-8.2
#else
inline void fuelSchedule3Interrupt(void)
void fuelSchedule3Interrupt(void)
#endif
{
if (fuelSchedule3.Status == PENDING) //Check to see if this schedule is turn on
@ -1051,7 +1051,7 @@ inline void fuelSchedule3Interrupt(void)
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega2561__) //AVR chips use the ISR for this
ISR(TIMER4_COMPB_vect) //cppcheck-suppress misra-c2012-8.2
#else
inline void fuelSchedule4Interrupt(void)
void fuelSchedule4Interrupt(void)
#endif
{
if (fuelSchedule4.Status == PENDING) //Check to see if this schedule is turn on
@ -1086,7 +1086,7 @@ inline void fuelSchedule4Interrupt(void)
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER4_COMPC_vect) //cppcheck-suppress misra-c2012-8.2
#else
inline void fuelSchedule5Interrupt(void)
void fuelSchedule5Interrupt(void)
#endif
{
if (fuelSchedule5.Status == PENDING) //Check to see if this schedule is turn on
@ -1119,7 +1119,7 @@ inline void fuelSchedule5Interrupt(void)
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER4_COMPA_vect) //cppcheck-suppress misra-c2012-8.2
#else
inline void fuelSchedule6Interrupt(void)
void fuelSchedule6Interrupt(void)
#endif
{
if (fuelSchedule6.Status == PENDING) //Check to see if this schedule is turn on
@ -1154,7 +1154,7 @@ inline void fuelSchedule6Interrupt(void)
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER5_COMPC_vect) //cppcheck-suppress misra-c2012-8.2
#else
inline void fuelSchedule7Interrupt(void)
void fuelSchedule7Interrupt(void)
#endif
{
if (fuelSchedule7.Status == PENDING) //Check to see if this schedule is turn on
@ -1189,7 +1189,7 @@ inline void fuelSchedule7Interrupt(void)
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER5_COMPB_vect) //cppcheck-suppress misra-c2012-8.2
#else
inline void fuelSchedule8Interrupt(void)
void fuelSchedule8Interrupt(void)
#endif
{
if (fuelSchedule8.Status == PENDING) //Check to see if this schedule is turn on
@ -1224,7 +1224,7 @@ inline void fuelSchedule8Interrupt(void)
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER5_COMPA_vect) //cppcheck-suppress misra-c2012-8.2
#else
inline void ignitionSchedule1Interrupt(void)
void ignitionSchedule1Interrupt(void)
#endif
{
if (ignitionSchedule1.Status == PENDING) //Check to see if this schedule is turn on
@ -1266,7 +1266,7 @@ inline void ignitionSchedule1Interrupt(void)
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER5_COMPB_vect) //cppcheck-suppress misra-c2012-8.2
#else
inline void ignitionSchedule2Interrupt(void)
void ignitionSchedule2Interrupt(void)
#endif
{
if (ignitionSchedule2.Status == PENDING) //Check to see if this schedule is turn on
@ -1308,7 +1308,7 @@ inline void ignitionSchedule2Interrupt(void)
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER5_COMPC_vect) //cppcheck-suppress misra-c2012-8.2
#else
inline void ignitionSchedule3Interrupt(void)
void ignitionSchedule3Interrupt(void)
#endif
{
if (ignitionSchedule3.Status == PENDING) //Check to see if this schedule is turn on
@ -1350,7 +1350,7 @@ inline void ignitionSchedule3Interrupt(void)
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER4_COMPA_vect) //cppcheck-suppress misra-c2012-8.2
#else
inline void ignitionSchedule4Interrupt(void)
void ignitionSchedule4Interrupt(void)
#endif
{
if (ignitionSchedule4.Status == PENDING) //Check to see if this schedule is turn on
@ -1392,7 +1392,7 @@ inline void ignitionSchedule4Interrupt(void)
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER4_COMPC_vect) //cppcheck-suppress misra-c2012-8.2
#else
inline void ignitionSchedule5Interrupt(void)
void ignitionSchedule5Interrupt(void)
#endif
{
if (ignitionSchedule5.Status == PENDING) //Check to see if this schedule is turn on
@ -1434,7 +1434,7 @@ inline void ignitionSchedule5Interrupt(void)
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER4_COMPB_vect) //cppcheck-suppress misra-c2012-8.2
#else
inline void ignitionSchedule6Interrupt(void)
void ignitionSchedule6Interrupt(void)
#endif
{
if (ignitionSchedule6.Status == PENDING) //Check to see if this schedule is turn on
@ -1476,7 +1476,7 @@ inline void ignitionSchedule6Interrupt(void)
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER3_COMPC_vect) //cppcheck-suppress misra-c2012-8.2
#else
inline void ignitionSchedule7Interrupt(void)
void ignitionSchedule7Interrupt(void)
#endif
{
if (ignitionSchedule7.Status == PENDING) //Check to see if this schedule is turn on
@ -1518,7 +1518,7 @@ inline void ignitionSchedule7Interrupt(void)
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER3_COMPB_vect) //cppcheck-suppress misra-c2012-8.2
#else
inline void ignitionSchedule8Interrupt(void)
void ignitionSchedule8Interrupt(void)
#endif
{
if (ignitionSchedule8.Status == PENDING) //Check to see if this schedule is turn on

View File

@ -121,49 +121,49 @@ void setIgnitionSchedule8(void (*startCallback)(), unsigned long timeout, unsign
void disablePendingFuelSchedule(byte channel);
void disablePendingIgnSchedule(byte channel);
inline void refreshIgnitionSchedule1(unsigned long timeToEnd) __attribute__((always_inline));
void refreshIgnitionSchedule1(unsigned long timeToEnd);
//The ARM cores use separate functions for their ISRs
#if defined(ARDUINO_ARCH_STM32) || defined(CORE_TEENSY)
inline void fuelSchedule1Interrupt(void);
inline void fuelSchedule2Interrupt(void);
inline void fuelSchedule3Interrupt(void);
inline void fuelSchedule4Interrupt(void);
void fuelSchedule1Interrupt(void);
void fuelSchedule2Interrupt(void);
void fuelSchedule3Interrupt(void);
void fuelSchedule4Interrupt(void);
#if (INJ_CHANNELS >= 5)
inline void fuelSchedule5Interrupt(void);
void fuelSchedule5Interrupt(void);
#endif
#if (INJ_CHANNELS >= 6)
inline void fuelSchedule6Interrupt(void);
void fuelSchedule6Interrupt(void);
#endif
#if (INJ_CHANNELS >= 7)
inline void fuelSchedule7Interrupt(void);
void fuelSchedule7Interrupt(void);
#endif
#if (INJ_CHANNELS >= 8)
inline void fuelSchedule8Interrupt(void);
void fuelSchedule8Interrupt(void);
#endif
#if (IGN_CHANNELS >= 1)
inline void ignitionSchedule1Interrupt(void);
void ignitionSchedule1Interrupt(void);
#endif
#if (IGN_CHANNELS >= 2)
inline void ignitionSchedule2Interrupt(void);
void ignitionSchedule2Interrupt(void);
#endif
#if (IGN_CHANNELS >= 3)
inline void ignitionSchedule3Interrupt(void);
void ignitionSchedule3Interrupt(void);
#endif
#if (IGN_CHANNELS >= 4)
inline void ignitionSchedule4Interrupt(void);
void ignitionSchedule4Interrupt(void);
#endif
#if (IGN_CHANNELS >= 5)
inline void ignitionSchedule5Interrupt(void);
void ignitionSchedule5Interrupt(void);
#endif
#if (IGN_CHANNELS >= 6)
inline void ignitionSchedule6Interrupt(void);
void ignitionSchedule6Interrupt(void);
#endif
#if (IGN_CHANNELS >= 7)
inline void ignitionSchedule7Interrupt(void);
void ignitionSchedule7Interrupt(void);
#endif
#if (IGN_CHANNELS >= 8)
inline void ignitionSchedule8Interrupt(void);
void ignitionSchedule8Interrupt(void);
#endif
#endif
/** Schedule statuses.

View File

@ -20,6 +20,31 @@ A full copy of the license may be found in the projects root directory
#include "auxiliaries.h"
#include "utilities.h"
uint32_t MAPcurRev; //Tracks which revolution we're sampling on
unsigned int MAPcount; //Number of samples taken in the current MAP cycle
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 long EMAPrunningValue; //As above but for EMAP
bool auxIsEnabled;
uint16_t MAPlast; /**< The previous MAP reading */
unsigned long MAP_time; //The time the MAP sample was taken
unsigned long MAPlast_time; //The time the previous MAP sample was taken
volatile unsigned long vssTimes[VSS_SAMPLES] = {0};
volatile byte vssIndex;
volatile byte flexCounter = 0;
volatile unsigned long flexStartTime;
volatile unsigned long flexPulseWidth;
volatile byte knockCounter = 0;
volatile uint16_t knockAngle;
//These variables are used for tracking the number of running sensors values that appear to be errors. Once a threshold is reached, the sensor reading will go to default value and assume the sensor is faulty
byte mapErrorCount = 0;
//byte iatErrorCount = 0; Not used
//byte cltErrorCount = 0; Not used
static inline void validateMAP(void);
/** Init all ADC conversions by setting resolutions, etc.
*/
void initialiseADC(void)
@ -159,7 +184,7 @@ static inline void validateMAP(void)
}
}
static inline void instanteneousMAPReading(void)
void instanteneousMAPReading(void)
{
//Update the calculation times and last value. These are used by the MAP based Accel enrich
MAPlast = currentStatus.MAP;
@ -203,7 +228,7 @@ static inline void instanteneousMAPReading(void)
}
static inline void readMAP(void)
void readMAP(void)
{
unsigned int tempReading;
//MAP Sampling system

View File

@ -34,9 +34,9 @@
#endif
*/
volatile byte flexCounter = 0;
volatile unsigned long flexStartTime;
volatile unsigned long flexPulseWidth;
extern volatile byte flexCounter;
extern volatile unsigned long flexStartTime;
extern volatile unsigned long flexPulseWidth;
#if defined(CORE_AVR)
#define READ_FLEX() ((*flex_pin_port & flex_pin_mask) ? true : false)
@ -44,25 +44,14 @@ volatile unsigned long flexPulseWidth;
#define READ_FLEX() digitalRead(pinFlex)
#endif
volatile byte knockCounter = 0;
volatile uint16_t knockAngle;
extern volatile byte knockCounter;
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 long EMAPrunningValue; //As above but for EMAP
unsigned int MAPcount; //Number of samples taken in the current MAP cycle
uint32_t MAPcurRev; //Tracks which revolution we're sampling on
bool auxIsEnabled;
uint16_t MAPlast; /**< The previous MAP reading */
unsigned long MAP_time; //The time the MAP sample was taken
unsigned long MAPlast_time; //The time the previous MAP sample was taken
volatile unsigned long vssTimes[VSS_SAMPLES] = {0};
volatile byte vssIndex;
//These variables are used for tracking the number of running sensors values that appear to be errors. Once a threshold is reached, the sensor reading will go to default value and assume the sensor is faulty
byte mapErrorCount = 0;
byte iatErrorCount = 0;
byte cltErrorCount = 0;
extern unsigned int MAPcount; //Number of samples taken in the current MAP cycle
extern uint32_t MAPcurRev; //Tracks which revolution we're sampling on
extern bool auxIsEnabled;
extern uint16_t MAPlast; /**< The previous MAP reading */
extern unsigned long MAP_time; //The time the MAP sample was taken
extern unsigned long MAPlast_time; //The time the previous MAP sample was taken
/**
* @brief Simple low pass IIR filter macro for the analog inputs
@ -71,9 +60,6 @@ byte cltErrorCount = 0;
*/
#define ADC_FILTER(input, alpha, prior) (((long)input * (256 - alpha) + ((long)prior * alpha))) >> 8
static inline void instanteneousMAPReading(void) __attribute__((always_inline));
static inline void readMAP(void) __attribute__((always_inline));
static inline void validateMAP(void);
void initialiseADC(void);
void readTPS(bool useFilter=true); //Allows the option to override the use of the filter
void readO2_2(void);
@ -91,6 +77,8 @@ void readIAT(void);
void readO2(void);
void readBat(void);
void readBaro(void);
void readMAP(void);
void instanteneousMAPReading(void);
#if defined(ANALOG_ISR)
volatile int AnChannel[15];

View File

@ -21,6 +21,7 @@ uint16_t PW(int REQ_FUEL, byte VE, long MAP, uint16_t corrections, int injOpen);
byte getVE1(void);
byte getAdvance1(void);
void calculateStaging(uint32_t);
void calculateIgnitionAngles(int dwellAngle);
void checkLaunchAndFlatShift();
extern uint16_t req_fuel_uS; /**< The required fuel variable (As calculated by TunerStudio) in uS */

View File

@ -4,6 +4,8 @@ This file is used for everything related to maps/tables including their definiti
#ifndef TABLE_H
#define TABLE_H
#include "globals.h"
#define SIZE_SIGNED_BYTE 4
#define SIZE_BYTE 8
#define SIZE_INT 16

View File

@ -25,6 +25,26 @@ Timers are typically low resolution (Compared to Schedulers), with maximum frequ
#include <avr/wdt.h>
#endif
volatile uint16_t lastRPM_100ms; //Need to record this for rpmDOT calculation
volatile byte loop33ms;
volatile byte loop66ms;
volatile byte loop100ms;
volatile byte loop250ms;
volatile int loopSec;
volatile unsigned int dwellLimit_uS;
volatile uint8_t tachoEndTime; //The time (in ms) that the tacho pulse needs to end at
volatile TachoOutputStatus tachoOutputFlag;
volatile bool tachoSweepEnabled;
volatile bool tachoAlt = false;
volatile uint16_t tachoSweepIncr;
volatile uint16_t tachoSweepAccum;
#if defined (CORE_TEENSY)
IntervalTimer lowResTimer;
#endif
void initialiseTimers(void)
{
lastRPM_100ms = 0;
@ -160,14 +180,6 @@ void oneMSInterval(void) //Most ARM chips can simply call a function
digitalWrite(LED_BUILTIN, !digitalRead(LED_BUILTIN));
#endif
#if defined(CORE_AVR)
//Reset watchdog timer (Not active currently)
//wdt_reset();
//DIY watchdog
//This is a sign of a crash:
//if( (initialisationComplete == true) && (last250msLoopCount == mainLoopCount) ) { setup(); }
//else { last250msLoopCount = mainLoopCount; }
#endif
}
//1Hz loop

View File

@ -19,34 +19,25 @@ Hence we will preload the timer with 131 cycles to leave 125 until overflow (1ms
#ifndef TIMERS_H
#define TIMERS_H
#include "globals.h"
#define SET_COMPARE(compare, value) compare = (COMPARE_TYPE)(value) // It is important that we cast this to the actual overflow limit of the timer. The compare variables type can be bigger than the timer overflow.
volatile bool tachoAlt = false;
#define TACHO_PULSE_HIGH() *tach_pin_port |= (tach_pin_mask)
#define TACHO_PULSE_LOW() *tach_pin_port &= ~(tach_pin_mask)
enum TachoOutputStatus {TACHO_INACTIVE, READY, ACTIVE}; //The 3 statuses that the tacho output pulse can have. NOTE: Cannot just use 'INACTIVE' as this is already defined within the Teensy Libs
volatile uint8_t tachoEndTime; //The time (in ms) that the tacho pulse needs to end at
volatile TachoOutputStatus tachoOutputFlag;
volatile bool tachoSweepEnabled;
volatile uint16_t tachoSweepIncr;
volatile uint16_t tachoSweepAccum;
extern volatile TachoOutputStatus tachoOutputFlag;
extern volatile bool tachoSweepEnabled;
extern volatile uint16_t tachoSweepIncr;
#define TACHO_SWEEP_TIME_MS 1500
#define TACHO_SWEEP_RAMP_MS (TACHO_SWEEP_TIME_MS * 2 / 3)
#define MS_PER_SEC 1000
volatile byte loop33ms;
volatile byte loop66ms;
volatile byte loop100ms;
volatile byte loop250ms;
volatile int loopSec;
volatile unsigned int dwellLimit_uS;
volatile uint16_t lastRPM_100ms; //Need to record this for rpmDOT calculation
volatile uint16_t last250msLoopCount = 1000; //Set to effectively random number on startup. Just need this to be different to what mainLoopCount equals initially (Probably 0)
extern volatile unsigned int dwellLimit_uS;
#if defined (CORE_TEENSY)
IntervalTimer lowResTimer;
extern IntervalTimer lowResTimer;
void oneMSInterval(void);
#elif defined (ARDUINO_ARCH_STM32)
void oneMSInterval(void);