MISRA cleanup rule: misra-c2012-8.2

This commit is contained in:
Josh Stewart 2022-11-06 09:43:29 +11:00
parent a1d3c59af7
commit 2fc29ceef5
54 changed files with 1030 additions and 877 deletions

157
misra/all_rules.txt Normal file
View File

@ -0,0 +1,157 @@
misra-c2012-1.1
misra-c2012-1.2
misra-c2012-1.3
misra-c2012-2.1
misra-c2012-2.2
misra-c2012-2.3
misra-c2012-2.4
misra-c2012-2.5
misra-c2012-2.6
misra-c2012-2.7
misra-c2012-3.1
misra-c2012-3.2
misra-c2012-3.3
misra-c2012-4.1
misra-c2012-4.2
misra-c2012-5.1
misra-c2012-5.2
misra-c2012-5.3
misra-c2012-5.4
misra-c2012-5.5
misra-c2012-5.6
misra-c2012-5.7
misra-c2012-5.8
misra-c2012-5.9
misra-c2012-6.1
misra-c2012-6.2
misra-c2012-7.1
misra-c2012-7.2
misra-c2012-7.3
misra-c2012-7.4
misra-c2012-8.1
misra-c2012-8.2
misra-c2012-8.3
misra-c2012-8.4
misra-c2012-8.5
misra-c2012-8.6
misra-c2012-8.7
misra-c2012-8.8
misra-c2012-8.9
misra-c2012-8.10
misra-c2012-8.11
misra-c2012-8.12
misra-c2012-8.13
misra-c2012-8.14
misra-c2012-9.1
misra-c2012-9.2
misra-c2012-9.3
misra-c2012-9.4
misra-c2012-9.5
misra-c2012-10.1
misra-c2012-10.2
misra-c2012-10.3
misra-c2012-10.4
misra-c2012-10.5
misra-c2012-10.6
misra-c2012-10.7
misra-c2012-10.8
misra-c2012-11.1
misra-c2012-11.2
misra-c2012-11.3
misra-c2012-11.4
misra-c2012-11.5
misra-c2012-11.6
misra-c2012-11.7
misra-c2012-11.8
misra-c2012-11.9
misra-c2012-12.1
misra-c2012-12.2
misra-c2012-12.3
misra-c2012-12.4
misra-c2012-13.1
misra-c2012-13.2
misra-c2012-13.3
misra-c2012-13.4
misra-c2012-13.5
misra-c2012-13.6
misra-c2012-14.1
misra-c2012-14.2
misra-c2012-14.3
misra-c2012-14.4
misra-c2012-15.1
misra-c2012-15.2
misra-c2012-15.3
misra-c2012-15.4
misra-c2012-15.5
misra-c2012-15.6
misra-c2012-15.7
misra-c2012-16.1
misra-c2012-16.2
misra-c2012-16.3
misra-c2012-16.4
misra-c2012-16.5
misra-c2012-16.6
misra-c2012-16.7
misra-c2012-17.1
misra-c2012-17.2
misra-c2012-17.3
misra-c2012-17.4
misra-c2012-17.5
misra-c2012-17.6
misra-c2012-17.7
misra-c2012-17.8
misra-c2012-18.1
misra-c2012-18.2
misra-c2012-18.3
misra-c2012-18.4
misra-c2012-18.5
misra-c2012-18.6
misra-c2012-18.7
misra-c2012-18.8
misra-c2012-19.1
misra-c2012-19.2
misra-c2012-20.1
misra-c2012-20.2
misra-c2012-20.3
misra-c2012-20.4
misra-c2012-20.5
misra-c2012-20.6
misra-c2012-20.7
misra-c2012-20.8
misra-c2012-20.9
misra-c2012-20.10
misra-c2012-20.11
misra-c2012-20.12
misra-c2012-20.13
misra-c2012-20.14
misra-c2012-21.1
misra-c2012-21.2
misra-c2012-21.3
misra-c2012-21.4
misra-c2012-21.5
misra-c2012-21.6
misra-c2012-21.7
misra-c2012-21.8
misra-c2012-21.9
misra-c2012-21.10
misra-c2012-21.11
misra-c2012-21.12
misra-c2012-21.13
misra-c2012-21.14
misra-c2012-21.15
misra-c2012-21.16
misra-c2012-21.17
misra-c2012-21.18
misra-c2012-21.19
misra-c2012-21.20
misra-c2012-21.21
misra-c2012-22.1
misra-c2012-22.2
misra-c2012-22.3
misra-c2012-22.4
misra-c2012-22.5
misra-c2012-22.6
misra-c2012-22.7
misra-c2012-22.8
misra-c2012-22.9
misra-c2012-22.10

View File

@ -71,4 +71,4 @@
#define TS_CMD_VSS_RATIO6 39174
/* the maximum id number is 65,535 */
void TS_CommandButtonsHandler(uint16_t);
void TS_CommandButtonsHandler(uint16_t buttonCommand);

View File

@ -15,7 +15,7 @@ volatile uint8_t mc33810_2_requestedState; //Current binary state of the 2nd ICs
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
void initMC33810();
void initMC33810(void);
#define MC33810_1_ACTIVE() (*mc33810_1_pin_port &= ~(mc33810_1_pin_mask))
#define MC33810_1_INACTIVE() (*mc33810_1_pin_port |= (mc33810_1_pin_mask))

View File

@ -2,7 +2,7 @@
#include "globals.h"
#include <SPI.h>
void initMC33810()
void initMC33810(void)
{
//Set the output states of both ICs to be off to fuel and ignition
mc33810_1_requestedState = 0;

View File

@ -3,23 +3,22 @@
#include BOARD_H //Note that this is not a real file, it is defined in globals.h.
void initialiseAuxPWM();
void boostControl();
void boostDisable();
void boostByGear();
void idleControl();
void vvtControl();
void initialiseFan();
void initialiseAirCon();
void nitrousControl();
void fanControl();
void airConControl();
bool READ_AIRCON_REQUEST();
void wmiControl();
void initialiseAuxPWM(void);
void boostControl(void);
void boostDisable(void);
void boostByGear(void);
void vvtControl(void);
void initialiseFan(void);
void initialiseAirCon(void);
void nitrousControl(void);
void fanControl(void);
void airConControl(void);
bool READ_AIRCON_REQUEST(void);
void wmiControl(void);
static inline void checkAirConCoolantLockout();
static inline void checkAirConTPSLockout();
static inline void checkAirConRPMLockout();
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
@ -113,7 +112,7 @@ 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;
void fanInterrupt();
void fanInterrupt(void);
#endif
uint32_t vvtWarmTime;
bool vvtIsHot;
@ -134,8 +133,8 @@ long vvt2_pid_target_angle;
long vvt_pid_current_angle;
long vvt2_pid_current_angle;
void boostInterrupt();
void vvtInterrupt();
void boostInterrupt(void);
void vvtInterrupt(void);
bool acIsEnabled;
bool acStandAloneFanIsEnabled;

View File

@ -20,7 +20,7 @@ integerPID vvt2PID(&vvt2_pid_current_angle, &currentStatus.vvt2Duty, &vvt2_pid_t
/*
Air Conditioning Control
*/
void initialiseAirCon()
void initialiseAirCon(void)
{
if( (configPage15.airConEnable&1) == 1 &&
pinAirConRequest != 0 &&
@ -69,7 +69,7 @@ void initialiseAirCon()
}
}
void airConControl()
void airConControl(void)
{
if(acIsEnabled == true)
{
@ -145,7 +145,7 @@ void airConControl()
}
}
bool READ_AIRCON_REQUEST()
bool READ_AIRCON_REQUEST(void)
{
if(acIsEnabled == false)
{
@ -159,7 +159,7 @@ bool READ_AIRCON_REQUEST()
return acReqPinStatus;
}
static inline void checkAirConCoolantLockout()
static inline void checkAirConCoolantLockout(void)
{
// ---------------------------
// Coolant Temperature Lockout
@ -182,7 +182,7 @@ static inline void checkAirConCoolantLockout()
}
}
static inline void checkAirConTPSLockout()
static inline void checkAirConTPSLockout(void)
{
// ------------------------------
// High Throttle Position Lockout
@ -212,7 +212,7 @@ static inline void checkAirConTPSLockout()
}
}
static inline void checkAirConRPMLockout()
static inline void checkAirConRPMLockout(void)
{
// --------------------
// High/Low RPM Lockout
@ -247,7 +247,7 @@ static inline void checkAirConRPMLockout()
/*
Fan control
*/
void initialiseFan()
void initialiseFan(void)
{
fan_pin_port = portOutputRegister(digitalPinToPort(pinFan));
fan_pin_mask = digitalPinToBitMask(pinFan);
@ -267,7 +267,7 @@ void initialiseFan()
#endif
}
void fanControl()
void fanControl(void)
{
if( configPage2.fanEnable == 1 ) // regular on/off fan control
{
@ -380,7 +380,7 @@ void fanControl()
}
}
void initialiseAuxPWM()
void initialiseAuxPWM(void)
{
boost_pin_port = portOutputRegister(digitalPinToPort(pinBoost));
boost_pin_mask = digitalPinToBitMask(pinBoost);
@ -473,7 +473,7 @@ void initialiseAuxPWM()
}
void boostByGear()
void boostByGear(void)
{
if(configPage4.boostType == OPEN_LOOP_BOOST)
{
@ -613,7 +613,7 @@ void boostByGear()
}
}
void boostControl()
void boostControl(void)
{
if( configPage6.boostEnabled==1 )
{
@ -707,7 +707,7 @@ void boostControl()
boostCounter++;
}
void vvtControl()
void vvtControl(void)
{
if( (configPage6.vvtEnabled == 1) && (currentStatus.coolant >= (int)(configPage4.vvtMinClt - CALIBRATION_TEMPERATURE_OFFSET)) && (BIT_CHECK(currentStatus.engine, BIT_ENGINE_RUN)))
{
@ -875,7 +875,7 @@ void vvtControl()
}
}
void nitrousControl()
void nitrousControl(void)
{
bool nitrousOn = false; //This tracks whether the control gets turned on at any point.
if(configPage10.n2o_enable > 0)
@ -932,7 +932,7 @@ void nitrousControl()
}
// Water methanol injection control
void wmiControl()
void wmiControl(void)
{
int wmiPW = 0;
@ -999,7 +999,7 @@ void wmiControl()
}
}
void boostDisable()
void boostDisable(void)
{
boostPID.Initialize(); //This resets the ITerm value to prevent rubber banding
currentStatus.boostDuty = 0;
@ -1009,9 +1009,9 @@ void boostDisable()
//The interrupt to control the Boost PWM
#if defined(CORE_AVR)
ISR(TIMER1_COMPA_vect)
ISR(TIMER1_COMPA_vect) //cppcheck-suppress misra-c2012-8.2
#else
void boostInterrupt() //Most ARM chips can simply call a function
void boostInterrupt(void) //Most ARM chips can simply call a function
#endif
{
if (boost_pwm_state == true)
@ -1039,9 +1039,9 @@ void boostDisable()
//The interrupt to control the VVT PWM
#if defined(CORE_AVR)
ISR(TIMER1_COMPB_vect)
ISR(TIMER1_COMPB_vect) //cppcheck-suppress misra-c2012-8.2
#else
void vvtInterrupt() //Most ARM chips can simply call a function
void vvtInterrupt(void) //Most ARM chips can simply call a function
#endif
{
if ( ((vvt1_pwm_state == false) || (vvt1_max_pwm == true)) && ((vvt2_pwm_state == false) || (vvt2_max_pwm == true)) )
@ -1158,7 +1158,7 @@ void boostDisable()
#if defined(PWM_FAN_AVAILABLE)
//The interrupt to control the FAN PWM. Mega2560 doesn't have enough timers, so this is only for the ARM chip ones
void fanInterrupt()
void fanInterrupt(void)
{
if (fan_pwm_state == true)
{

View File

@ -27,10 +27,10 @@
#else
#define RTC_LIB_H <Time.h>
#endif
void initBoard();
uint16_t freeRam();
void doSystemReset();
void jumpToBootloader();
void initBoard(void);
uint16_t freeRam(void);
void doSystemReset(void);
void jumpToBootloader(void);
#if defined(TIMER5_MICROS)
/*#define micros() (((timer5_overflow_count << 16) + TCNT5) * 4) */ //Fast version of micros() that uses the 4uS tick of timer5. See timers.ino for the overflow ISR of timer5

View File

@ -16,7 +16,7 @@
#define TIMER_MODE_CTC ((1<<WGM01)|(0<<WGM00))
#define TIMER_MODE_FASTPWM ((1<<WGM01)|(1<<WGM00))
void initBoard()
void initBoard(void)
{
/*
***********************************************************************************************************
@ -93,7 +93,7 @@ void initBoard()
Returns how much free dynamic memory exists (between heap and stack)
This function is one big MISRA violation. MISRA advisories forbid directly poking at memory addresses, however there is no other way of determining heap size on embedded systems.
*/
uint16_t freeRam()
uint16_t freeRam(void)
{
extern int __heap_start, *__brkval;
int currentVal;
@ -108,8 +108,8 @@ uint16_t freeRam()
return (uint16_t) &v - currentVal; //cppcheck-suppress misra-c2012-11.4
}
void doSystemReset() { return; }
void jumpToBootloader() { return; }
void doSystemReset(void) { return; }
void jumpToBootloader(void) { return; }
#if defined(TIMER5_MICROS)
//This is used by the fast version of micros(). We just need to increment the timer overflow counter
ISR(TIMER5_OVF_vect)
@ -117,7 +117,7 @@ ISR(TIMER5_OVF_vect)
++timer5_overflow_count;
}
static inline unsigned long micros_safe()
static inline unsigned long micros_safe(void)
{
unsigned long newMicros;
noInterrupts();

View File

@ -22,9 +22,9 @@
extern HardwareSerial &CANSerial;
#endif
void secondserial_Command();//This is the heart of the Command Line Interpreter. All that needed to be done was to make it human readable.
void secondserial_Command(void);//This is the heart of the Command Line Interpreter. All that needed to be done was to make it human readable.
void sendcanValues(uint16_t offset, uint16_t packetLength, byte cmd, byte portNum);
void can_Command();
void can_Command(void);
void sendCancommand(uint8_t cmdtype , uint16_t canadddress, uint8_t candata1, uint8_t candata2, uint16_t sourcecanAddress);
void obd_response(uint8_t therequestedPID , uint8_t therequestedPIDlow, uint8_t therequestedPIDhigh);

View File

@ -46,7 +46,7 @@ bool canCmdPending = false;
HardwareSerial &CANSerial = Serial2;
#endif
void secondserial_Command()
void secondserial_Command(void)
{
#if defined(CANSerial_AVAILABLE)
if (! canCmdPending) { currentsecondserialCommand = CANSerial.read(); }
@ -362,7 +362,7 @@ void sendcanValues(uint16_t offset, uint16_t packetLength, byte cmd, byte portTy
}
void can_Command()
void can_Command(void)
{
//int currentcanCommand = inMsg.id;
#if defined (NATIVE_CAN_AVAILABLE)

View File

@ -49,7 +49,7 @@ FastCRC32 CRC32_serial; //This instance of CRC32 is exclusively used on the comm
/**
* @brief Flush all remaining bytes from the rx serial buffer
*/
void flushRXbuffer()
void flushRXbuffer(void)
{
while (Serial.available() > 0) { Serial.read(); }
}
@ -61,7 +61,7 @@ Can be either data for a new command or a continuation of data for command that
Comands are single byte (letter symbol) commands.
*/
void parseSerial()
void parseSerial(void)
{
//Check for an existing legacy command in progress
@ -200,7 +200,7 @@ void sendSerialPayload(void *payload, uint16_t payloadLength)
}
}
void continueSerialTransmission()
void continueSerialTransmission(void)
{
if(serialWriteInProgress == true)
{
@ -231,7 +231,7 @@ void continueSerialTransmission()
}
}
void processSerialCommand()
void processSerialCommand(void)
{
currentCommand = serialPayload[0];
@ -943,7 +943,7 @@ namespace
/**
*
*/
void sendToothLog(byte startOffset)
void sendToothLog(uint8_t startOffset)
{
//We need TOOTH_LOG_SIZE number of records to send to TunerStudio. If there aren't that many in the buffer then we just return and wait for the next call
if (BIT_CHECK(currentStatus.status1, BIT_STATUS1_TOOTHLOG1READY)) //Sanity check. Flagging system means this should always be true
@ -1015,7 +1015,7 @@ void sendToothLog(byte startOffset)
}
}
void sendCompositeLog(byte startOffset)
void sendCompositeLog(uint8_t startOffset)
{
if ( (BIT_CHECK(currentStatus.status1, BIT_STATUS1_TOOTHLOG1READY)) || (compositeLogSendInProgress == true) ) //Sanity check. Flagging system means this should always be true
{

View File

@ -73,17 +73,15 @@ extern bool serialWriteInProgress;
extern bool serialReceivePending; /**< Whether or not a serial request has only been partially received. This occurs when a the length has been received in the serial buffer, but not all of the payload or CRC has yet been received. */
void parseSerial();//This is the heart of the Command Line Interpreter. All that needed to be done was to make it human readable.
void processSerialCommand();
void parseSerial(void);//This is the heart of the Command Line Interpreter. All that needed to be done was to make it human readable.
void processSerialCommand(void);
void sendSerialReturnCode(byte returnCode);
void sendSerialPayload(void*, uint16_t payloadLength);
void sendSerialPayload(void* payload, uint16_t payloadLength);
void generateLiveValues(uint16_t, uint16_t);
void saveConfig();
void flushRXbuffer();
void sendToothLog(uint8_t);
void commandButtons(int16_t);
void sendCompositeLog(uint8_t);
void continueSerialTransmission();
void generateLiveValues(uint16_t offset, uint16_t packetLength);
void flushRXbuffer(void);
void sendToothLog(uint8_t startOffset);
void sendCompositeLog(uint8_t startOffset);
void continueSerialTransmission(void);
#endif // COMMS_H

View File

@ -48,7 +48,7 @@ Can be either data for a new command or a continuation of data for command that
Commands are single byte (letter symbol) commands.
*/
void legacySerialCommand()
void legacySerialCommand(void)
{
if ( (cmdPending == false) && (legacySerial == false) ) { currentCommand = Serial.read(); }
@ -652,7 +652,7 @@ void sendValues(uint16_t offset, uint16_t packetLength, byte cmd, byte portNum)
}
void sendValuesLegacy()
void sendValuesLegacy(void)
{
uint16_t temp;
int bytestosend = 114;
@ -841,7 +841,7 @@ namespace {
* Note that some translation of the data is required to lay it out in the way Megasquirt / TunerStudio expect it.
* Data is sent in binary format, as defined by in each page in the speeduino.ini.
*/
void sendPage()
void sendPage(void)
{
page_iterator_t entity = page_begin(currentPage);
@ -951,7 +951,7 @@ namespace {
*
* This is used for testing only (Not used by TunerStudio) in order to see current map and config data without the need for TunerStudio.
*/
void sendPageASCII()
void sendPageASCII(void)
{
switch (currentPage)
{

View File

@ -29,16 +29,14 @@ extern bool serialInProgress;
extern bool toothLogSendInProgress;
extern bool compositeLogSendInProgress;
void legacySerialCommand();//This is the heart of the Command Line Interpreter. All that needed to be done was to make it human readable.
void sendValues(uint16_t, uint16_t,byte, byte);
void sendValuesLegacy();
void saveConfig();
void sendPage();
void sendPageASCII();
void receiveCalibration(byte);
void sendToothLog_legacy(uint8_t);
void testComm();
void commandButtons(int16_t);
void sendCompositeLog_legacy(uint8_t);
void legacySerialCommand(void);//This is the heart of the Command Line Interpreter. All that needed to be done was to make it human readable.
void sendValues(uint16_t offset, uint16_t packetLength, byte cmd, byte portNum);
void sendValuesLegacy(void);
void sendPage(void);
void sendPageASCII(void);
void receiveCalibration(byte tableID);
void testComm(void);
void sendToothLog_legacy(byte startOffset);
void sendCompositeLog_legacy(byte startOffset);
#endif // COMMS_H

View File

@ -7,37 +7,36 @@ All functions in the gamma file return
#define IGN_IDLE_THRESHOLD 200 //RPM threshold (below CL idle target) for when ign based idle control will engage
void initialiseCorrections();
uint16_t correctionsFuel();
byte correctionWUE(); //Warmup enrichment
uint16_t correctionCranking(); //Cranking enrichment
byte correctionASE(); //After Start Enrichment
uint16_t correctionAccel(); //Acceleration Enrichment
byte correctionFloodClear(); //Check for flood clear on cranking
byte correctionAFRClosedLoop(); //Closed loop AFR adjustment
byte correctionFlex(); //Flex fuel adjustment
byte correctionFuelTemp(); //Fuel temp correction
byte correctionBatVoltage(); //Battery voltage correction
byte correctionIATDensity(); //Inlet temp density correction
byte correctionBaro(); //Barometric pressure correction
byte correctionLaunch(); //Launch control correction
bool correctionDFCO(); //Decelleration fuel cutoff
void initialiseCorrections(void);
uint16_t correctionsFuel(void);
byte correctionWUE(void); //Warmup enrichment
uint16_t correctionCranking(void); //Cranking enrichment
byte correctionASE(void); //After Start Enrichment
uint16_t correctionAccel(void); //Acceleration Enrichment
byte correctionFloodClear(void); //Check for flood clear on cranking
byte correctionAFRClosedLoop(void); //Closed loop AFR adjustment
byte correctionFlex(void); //Flex fuel adjustment
byte correctionFuelTemp(void); //Fuel temp correction
byte correctionBatVoltage(void); //Battery voltage correction
byte correctionIATDensity(void); //Inlet temp density correction
byte correctionBaro(void); //Barometric pressure correction
byte correctionLaunch(void); //Launch control correction
bool correctionDFCO(void); //Decelleration fuel cutoff
int8_t correctionsIgn(int8_t advance);
int8_t correctionFixedTiming(int8_t);
int8_t correctionCrankingFixedTiming(int8_t);
int8_t correctionFlexTiming(int8_t);
int8_t correctionWMITiming(int8_t);
int8_t correctionIATretard(int8_t);
int8_t correctionCLTadvance(int8_t);
int8_t correctionIdleAdvance(int8_t);
int8_t correctionSoftRevLimit(int8_t);
int8_t correctionNitrous(int8_t);
int8_t correctionSoftLaunch(int8_t);
int8_t correctionSoftFlatShift(int8_t);
int8_t correctionKnock(int8_t);
int8_t correctionFixedTiming(int8_t advance);
int8_t correctionCrankingFixedTiming(int8_t advance);
int8_t correctionFlexTiming(int8_t advance);
int8_t correctionWMITiming(int8_t advance);
int8_t correctionIATretard(int8_t advance);
int8_t correctionCLTadvance(int8_t advance);
int8_t correctionIdleAdvance(int8_t advance);
int8_t correctionSoftRevLimit(int8_t advance);
int8_t correctionNitrous(int8_t advance);
int8_t correctionSoftLaunch(int8_t advance);
int8_t correctionSoftFlatShift(int8_t advance);
int8_t correctionKnock(int8_t advance);
uint16_t correctionsDwell(uint16_t dwell);

View File

@ -56,7 +56,7 @@ uint8_t crankingEnrichTaper;
/** Initialise instances and vars related to corrections (at ECU boot-up).
*/
void initialiseCorrections()
void initialiseCorrections(void)
{
egoPID.SetMode(AUTOMATIC); //Turn O2 PID on
currentStatus.flexIgnCorrection = 0;
@ -70,7 +70,7 @@ void initialiseCorrections()
Calls all the other corrections functions and combines their results.
This is the only function that should be called from anywhere outside the file
*/
uint16_t correctionsFuel()
uint16_t correctionsFuel(void)
{
uint32_t sumCorrections = 100;
uint16_t result; //temporary variable to store the result of each corrections function
@ -134,7 +134,7 @@ uint16_t correctionsFuel()
correctionsTotal() calls all the other corrections functions and combines their results.
This is the only function that should be called from anywhere outside the file
*/
static inline byte correctionsFuel_new()
static inline byte correctionsFuel_new(void)
{
uint32_t sumCorrections = 100;
byte numCorrections = 0;
@ -173,7 +173,7 @@ static inline byte correctionsFuel_new()
/** Warm Up Enrichment (WUE) corrections.
Uses a 2D enrichment table (WUETable) where the X axis is engine temp and the Y axis is the amount of extra fuel to add
*/
byte correctionWUE()
byte correctionWUE(void)
{
byte WUEValue;
//Possibly reduce the frequency this runs at (Costs about 50 loops per second)
@ -196,7 +196,7 @@ byte correctionWUE()
/** Cranking Enrichment corrections.
Additional fuel % to be added when the engine is cranking
*/
uint16_t correctionCranking()
uint16_t correctionCranking(void)
{
uint16_t crankingValue = 100;
//Check if we are actually cranking
@ -227,7 +227,7 @@ uint16_t correctionCranking()
*
* @return uint8_t The After Start Enrichment modifier as a %. 100% = No modification.
*/
byte correctionASE()
byte correctionASE(void)
{
int16_t ASEValue = currentStatus.ASEValue;
//Two checks are required:
@ -284,7 +284,7 @@ byte correctionASE()
* As the maximum enrichment amount is +255% and maximum cold adjustment for this is 255%, the overall return value
* from this function can be 100+(255*255/100)=750. Hence this function returns a uint16_t rather than byte.
*/
uint16_t correctionAccel()
uint16_t correctionAccel(void)
{
int16_t accelValue = 100;
int16_t MAP_change = 0;
@ -464,7 +464,7 @@ uint16_t correctionAccel()
/** Simple check to see whether we are cranking with the TPS above the flood clear threshold.
@return 100 (not cranking and thus no need for flood-clear) or 0 (Engine cranking and TPS above @ref config4.floodClear limit).
*/
byte correctionFloodClear()
byte correctionFloodClear(void)
{
byte floodValue = 100;
if( BIT_CHECK(currentStatus.engine, BIT_ENGINE_CRANK) )
@ -482,7 +482,7 @@ byte correctionFloodClear()
/** Battery Voltage correction.
Uses a 2D enrichment table (WUETable) where the X axis is engine temp and the Y axis is the amount of extra fuel to add.
*/
byte correctionBatVoltage()
byte correctionBatVoltage(void)
{
byte batValue = 100;
batValue = table2D_getValue(&injectorVCorrectionTable, currentStatus.battery10);
@ -492,7 +492,7 @@ byte correctionBatVoltage()
/** Simple temperature based corrections lookup based on the inlet air temperature (IAT).
This corrects for changes in air density from movement of the temperature.
*/
byte correctionIATDensity()
byte correctionIATDensity(void)
{
byte IATValue = 100;
IATValue = table2D_getValue(&IATDensityCorrectionTable, currentStatus.IAT + CALIBRATION_TEMPERATURE_OFFSET); //currentStatus.IAT is the actual temperature, values in IATDensityCorrectionTable.axisX are temp+offset
@ -503,7 +503,7 @@ byte correctionIATDensity()
/** Correction for current barometric / ambient pressure.
* @returns A percentage value indicating the amount the fuelling should be changed based on the barometric reading. 100 = No change. 110 = 10% increase. 90 = 10% decrease
*/
byte correctionBaro()
byte correctionBaro(void)
{
byte baroValue = 100;
baroValue = table2D_getValue(&baroFuelTable, currentStatus.baro);
@ -514,7 +514,7 @@ byte correctionBaro()
/** Launch control has a setting to increase the fuel load to assist in bringing up boost.
This simple check applies the extra fuel if we're currently launching
*/
byte correctionLaunch()
byte correctionLaunch(void)
{
byte launchValue = 100;
if(currentStatus.launchingHard || currentStatus.launchingSoft) { launchValue = (100 + configPage6.lnchFuelAdd); }
@ -525,7 +525,7 @@ byte correctionLaunch()
/*
* Returns true if deceleration fuel cutoff should be on, false if its off
*/
bool correctionDFCO()
bool correctionDFCO(void)
{
bool DFCOValue = false;
if ( configPage2.dfcoEnabled == 1 )
@ -554,7 +554,7 @@ bool correctionDFCO()
/** Flex fuel adjustment to vary fuel based on ethanol content.
* The amount of extra fuel required is a linear relationship based on the % of ethanol.
*/
byte correctionFlex()
byte correctionFlex(void)
{
byte flexValue = 100;
@ -568,7 +568,7 @@ byte correctionFlex()
/*
* Fuel temperature adjustment to vary fuel based on fuel temperature reading
*/
byte correctionFuelTemp()
byte correctionFuelTemp(void)
{
byte fuelTempValue = 100;
@ -592,7 +592,7 @@ This continues until either:
PID (Best suited to wideband sensors):
*/
byte correctionAFRClosedLoop()
byte correctionAFRClosedLoop(void)
{
byte AFRValue = 100;

View File

@ -15,9 +15,9 @@
#define ignitionLimits(angle) ( (((int16_t)(angle)) >= CRANK_ANGLE_MAX_IGN) ? ((angle) - CRANK_ANGLE_MAX_IGN) : ( ((int16_t)(angle) < 0) ? ((angle) + CRANK_ANGLE_MAX_IGN) : (angle)) )
unsigned long angleToTime(int16_t, byte);
uint16_t timeToAngle(unsigned long, byte);
void doCrankSpeedCalcs();
unsigned long angleToTime(int16_t angle, byte method);
uint16_t timeToAngle(unsigned long time, byte method);
void doCrankSpeedCalcs(void);
extern volatile uint16_t timePerDegree;
extern volatile uint16_t timePerDegreex16;

View File

@ -99,7 +99,7 @@ uint16_t timeToAngle(unsigned long time, byte method)
}
void doCrankSpeedCalcs()
void doCrankSpeedCalcs(void)
{
//********************************************************
//How fast are we going? Need to know how long (uS) it will take to get from one tooth to the next. We then use that to estimate how far we are between the last tooth and the next one

View File

@ -39,171 +39,171 @@
//This isn't to to filter out wrong pulses on triggers, but just to smooth out the cam angle reading for better closed loop VVT control.
#define ANGLE_FILTER(input, alpha, prior) (((long)input * (256 - alpha) + ((long)prior * alpha))) >> 8
void loggerPrimaryISR();
void loggerSecondaryISR();
void loggerPrimaryISR(void);
void loggerSecondaryISR(void);
//All of the below are the 6 required functions for each decoder / pattern
void triggerSetup_missingTooth();
void triggerPri_missingTooth();
void triggerSec_missingTooth();
void triggerThird_missingTooth();
uint16_t getRPM_missingTooth();
int getCrankAngle_missingTooth();
extern void triggerSetEndTeeth_missingTooth();
void triggerSetup_missingTooth(void);
void triggerPri_missingTooth(void);
void triggerSec_missingTooth(void);
void triggerThird_missingTooth(void);
uint16_t getRPM_missingTooth(void);
int getCrankAngle_missingTooth(void);
extern void triggerSetEndTeeth_missingTooth(void);
void triggerSetup_DualWheel();
void triggerPri_DualWheel();
void triggerSec_DualWheel();
uint16_t getRPM_DualWheel();
int getCrankAngle_DualWheel();
void triggerSetEndTeeth_DualWheel();
void triggerSetup_DualWheel(void);
void triggerPri_DualWheel(void);
void triggerSec_DualWheel(void);
uint16_t getRPM_DualWheel(void);
int getCrankAngle_DualWheel(void);
void triggerSetEndTeeth_DualWheel(void);
void triggerSetup_BasicDistributor();
void triggerPri_BasicDistributor();
void triggerSec_BasicDistributor();
uint16_t getRPM_BasicDistributor();
int getCrankAngle_BasicDistributor();
void triggerSetEndTeeth_BasicDistributor();
void triggerSetup_BasicDistributor(void);
void triggerPri_BasicDistributor(void);
void triggerSec_BasicDistributor(void);
uint16_t getRPM_BasicDistributor(void);
int getCrankAngle_BasicDistributor(void);
void triggerSetEndTeeth_BasicDistributor(void);
void triggerSetup_GM7X();
void triggerPri_GM7X();
void triggerSec_GM7X();
uint16_t getRPM_GM7X();
int getCrankAngle_GM7X();
void triggerSetEndTeeth_GM7X();
void triggerSetup_GM7X(void);
void triggerPri_GM7X(void);
void triggerSec_GM7X(void);
uint16_t getRPM_GM7X(void);
int getCrankAngle_GM7X(void);
void triggerSetEndTeeth_GM7X(void);
void triggerSetup_4G63();
void triggerPri_4G63();
void triggerSec_4G63();
uint16_t getRPM_4G63();
int getCrankAngle_4G63();
void triggerSetEndTeeth_4G63();
void triggerSetup_4G63(void);
void triggerPri_4G63(void);
void triggerSec_4G63(void);
uint16_t getRPM_4G63(void);
int getCrankAngle_4G63(void);
void triggerSetEndTeeth_4G63(void);
void triggerSetup_24X();
void triggerPri_24X();
void triggerSec_24X();
uint16_t getRPM_24X();
int getCrankAngle_24X();
void triggerSetEndTeeth_24X();
void triggerSetup_24X(void);
void triggerPri_24X(void);
void triggerSec_24X(void);
uint16_t getRPM_24X(void);
int getCrankAngle_24X(void);
void triggerSetEndTeeth_24X(void);
void triggerSetup_Jeep2000();
void triggerPri_Jeep2000();
void triggerSec_Jeep2000();
uint16_t getRPM_Jeep2000();
int getCrankAngle_Jeep2000();
void triggerSetEndTeeth_Jeep2000();
void triggerSetup_Jeep2000(void);
void triggerPri_Jeep2000(void);
void triggerSec_Jeep2000(void);
uint16_t getRPM_Jeep2000(void);
int getCrankAngle_Jeep2000(void);
void triggerSetEndTeeth_Jeep2000(void);
void triggerSetup_Audi135();
void triggerPri_Audi135();
void triggerSec_Audi135();
uint16_t getRPM_Audi135();
int getCrankAngle_Audi135();
void triggerSetEndTeeth_Audi135();
void triggerSetup_Audi135(void);
void triggerPri_Audi135(void);
void triggerSec_Audi135(void);
uint16_t getRPM_Audi135(void);
int getCrankAngle_Audi135(void);
void triggerSetEndTeeth_Audi135(void);
void triggerSetup_HondaD17();
void triggerPri_HondaD17();
void triggerSec_HondaD17();
uint16_t getRPM_HondaD17();
int getCrankAngle_HondaD17();
void triggerSetEndTeeth_HondaD17();
void triggerSetup_HondaD17(void);
void triggerPri_HondaD17(void);
void triggerSec_HondaD17(void);
uint16_t getRPM_HondaD17(void);
int getCrankAngle_HondaD17(void);
void triggerSetEndTeeth_HondaD17(void);
void triggerSetup_Miata9905();
void triggerPri_Miata9905();
void triggerSec_Miata9905();
uint16_t getRPM_Miata9905();
int getCrankAngle_Miata9905();
void triggerSetEndTeeth_Miata9905();
int getCamAngle_Miata9905();
void triggerSetup_Miata9905(void);
void triggerPri_Miata9905(void);
void triggerSec_Miata9905(void);
uint16_t getRPM_Miata9905(void);
int getCrankAngle_Miata9905(void);
void triggerSetEndTeeth_Miata9905(void);
int getCamAngle_Miata9905(void);
void triggerSetup_MazdaAU();
void triggerPri_MazdaAU();
void triggerSec_MazdaAU();
uint16_t getRPM_MazdaAU();
int getCrankAngle_MazdaAU();
void triggerSetEndTeeth_MazdaAU();
void triggerSetup_MazdaAU(void);
void triggerPri_MazdaAU(void);
void triggerSec_MazdaAU(void);
uint16_t getRPM_MazdaAU(void);
int getCrankAngle_MazdaAU(void);
void triggerSetEndTeeth_MazdaAU(void);
void triggerSetup_non360();
void triggerPri_non360();
void triggerSec_non360();
uint16_t getRPM_non360();
int getCrankAngle_non360();
void triggerSetEndTeeth_non360();
void triggerSetup_non360(void);
void triggerPri_non360(void);
void triggerSec_non360(void);
uint16_t getRPM_non360(void);
int getCrankAngle_non360(void);
void triggerSetEndTeeth_non360(void);
void triggerSetup_Nissan360();
void triggerPri_Nissan360();
void triggerSec_Nissan360();
uint16_t getRPM_Nissan360();
int getCrankAngle_Nissan360();
void triggerSetEndTeeth_Nissan360();
void triggerSetup_Nissan360(void);
void triggerPri_Nissan360(void);
void triggerSec_Nissan360(void);
uint16_t getRPM_Nissan360(void);
int getCrankAngle_Nissan360(void);
void triggerSetEndTeeth_Nissan360(void);
void triggerSetup_Subaru67();
void triggerPri_Subaru67();
void triggerSec_Subaru67();
uint16_t getRPM_Subaru67();
int getCrankAngle_Subaru67();
void triggerSetEndTeeth_Subaru67();
void triggerSetup_Subaru67(void);
void triggerPri_Subaru67(void);
void triggerSec_Subaru67(void);
uint16_t getRPM_Subaru67(void);
int getCrankAngle_Subaru67(void);
void triggerSetEndTeeth_Subaru67(void);
void triggerSetup_Daihatsu();
void triggerPri_Daihatsu();
void triggerSec_Daihatsu();
uint16_t getRPM_Daihatsu();
int getCrankAngle_Daihatsu();
void triggerSetEndTeeth_Daihatsu();
void triggerSetup_Daihatsu(void);
void triggerPri_Daihatsu(void);
void triggerSec_Daihatsu(void);
uint16_t getRPM_Daihatsu(void);
int getCrankAngle_Daihatsu(void);
void triggerSetEndTeeth_Daihatsu(void);
void triggerSetup_Harley();
void triggerPri_Harley();
void triggerSec_Harley();
uint16_t getRPM_Harley();
int getCrankAngle_Harley();
void triggerSetEndTeeth_Harley();
void triggerSetup_Harley(void);
void triggerPri_Harley(void);
void triggerSec_Harley(void);
uint16_t getRPM_Harley(void);
int getCrankAngle_Harley(void);
void triggerSetEndTeeth_Harley(void);
void triggerSetup_ThirtySixMinus222();
void triggerPri_ThirtySixMinus222();
void triggerSec_ThirtySixMinus222();
uint16_t getRPM_ThirtySixMinus222();
int getCrankAngle_ThirtySixMinus222();
void triggerSetEndTeeth_ThirtySixMinus222();
void triggerSetup_ThirtySixMinus222(void);
void triggerPri_ThirtySixMinus222(void);
void triggerSec_ThirtySixMinus222(void);
uint16_t getRPM_ThirtySixMinus222(void);
int getCrankAngle_ThirtySixMinus222(void);
void triggerSetEndTeeth_ThirtySixMinus222(void);
void triggerSetup_ThirtySixMinus21();
void triggerPri_ThirtySixMinus21();
void triggerSec_ThirtySixMinus21();
uint16_t getRPM_ThirtySixMinus21();
int getCrankAngle_ThirtySixMinus21();
void triggerSetEndTeeth_ThirtySixMinus21();
void triggerSetup_ThirtySixMinus21(void);
void triggerPri_ThirtySixMinus21(void);
void triggerSec_ThirtySixMinus21(void);
uint16_t getRPM_ThirtySixMinus21(void);
int getCrankAngle_ThirtySixMinus21(void);
void triggerSetEndTeeth_ThirtySixMinus21(void);
void triggerSetup_420a();
void triggerPri_420a();
void triggerSec_420a();
uint16_t getRPM_420a();
int getCrankAngle_420a();
void triggerSetEndTeeth_420a();
void triggerSetup_420a(void);
void triggerPri_420a(void);
void triggerSec_420a(void);
uint16_t getRPM_420a(void);
int getCrankAngle_420a(void);
void triggerSetEndTeeth_420a(void);
void triggerPri_Webber();
void triggerSec_Webber();
void triggerPri_Webber(void);
void triggerSec_Webber(void);
void triggerSetup_FordST170();
void triggerSec_FordST170();
uint16_t getRPM_FordST170();
int getCrankAngle_FordST170();
void triggerSetEndTeeth_FordST170();
void triggerSetup_FordST170(void);
void triggerSec_FordST170(void);
uint16_t getRPM_FordST170(void);
int getCrankAngle_FordST170(void);
void triggerSetEndTeeth_FordST170(void);
void triggerSetup_DRZ400();
void triggerSec_DRZ400();
void triggerSetup_DRZ400(void);
void triggerSec_DRZ400(void);
void triggerSetup_NGC();
void triggerPri_NGC();
void triggerSec_NGC4();
void triggerSec_NGC68();
uint16_t getRPM_NGC();
void triggerSetEndTeeth_NGC();
void triggerSetup_NGC(void);
void triggerPri_NGC(void);
void triggerSec_NGC4(void);
void triggerSec_NGC68(void);
uint16_t getRPM_NGC(void);
void triggerSetEndTeeth_NGC(void);
extern void (*triggerHandler)(); //Pointer for the trigger function (Gets pointed to the relevant decoder)
extern void (*triggerSecondaryHandler)(); //Pointer for the secondary trigger function (Gets pointed to the relevant decoder)
extern void (*triggerTertiaryHandler)(); //Pointer for the tertiary trigger function (Gets pointed to the relevant decoder)
extern void (*triggerHandler)(void); //Pointer for the trigger function (Gets pointed to the relevant decoder)
extern void (*triggerSecondaryHandler)(void); //Pointer for the secondary trigger function (Gets pointed to the relevant decoder)
extern void (*triggerTertiaryHandler)(void); //Pointer for the tertiary trigger function (Gets pointed to the relevant decoder)
extern uint16_t (*getRPM)(); //Pointer to the getRPM function (Gets pointed to the relevant decoder)
extern int (*getCrankAngle)(); //Pointer to the getCrank Angle function (Gets pointed to the relevant decoder)
extern void (*triggerSetEndTeeth)(); //Pointer to the triggerSetEndTeeth function of each decoder
extern uint16_t (*getRPM)(void); //Pointer to the getRPM function (Gets pointed to the relevant decoder)
extern int (*getCrankAngle)(void); //Pointer to the getCrank Angle function (Gets pointed to the relevant decoder)
extern void (*triggerSetEndTeeth)(void); //Pointer to the triggerSetEndTeeth function of each decoder
extern volatile unsigned long curTime;
extern volatile unsigned long curGap;

File diff suppressed because it is too large Load Diff

View File

@ -2,8 +2,8 @@
#define HARD_REV_FIXED 1
#define HARD_REV_COOLANT 2
byte checkEngineProtect();
byte checkRevLimit();
byte checkBoostLimit();
byte checkOilPressureLimit();
byte checkAFRLimit();
byte checkEngineProtect(void);
byte checkRevLimit(void);
byte checkBoostLimit(void);
byte checkOilPressureLimit(void);
byte checkAFRLimit(void);

View File

@ -2,7 +2,7 @@
#include "globals.h"
#include "engineProtection.h"
byte checkEngineProtect()
byte checkEngineProtect(void)
{
byte protectActive = 0;
if(checkRevLimit() || checkBoostLimit() || checkOilPressureLimit() || checkAFRLimit() )
@ -13,7 +13,7 @@ byte checkEngineProtect()
return protectActive;
}
byte checkRevLimit()
byte checkRevLimit(void)
{
//Hardcut RPM limit
byte revLimiterActive = 0;
@ -49,7 +49,7 @@ byte checkRevLimit()
return revLimiterActive;
}
byte checkBoostLimit()
byte checkBoostLimit(void)
{
byte boostLimitActive = 0;
BIT_CLEAR(currentStatus.engineProtectStatus, ENGINE_PROTECT_BIT_MAP);
@ -90,7 +90,7 @@ byte checkBoostLimit()
return boostLimitActive;
}
byte checkOilPressureLimit()
byte checkOilPressureLimit(void)
{
byte oilProtectActive = 0;
BIT_CLEAR(currentStatus.engineProtectStatus, ENGINE_PROTECT_BIT_OIL); //Will be set true below if required
@ -110,7 +110,7 @@ byte checkOilPressureLimit()
return oilProtectActive;
}
byte checkAFRLimit()
byte checkAFRLimit(void)
{
static bool checkAFRLimitActive = false;
static bool afrProtectCountEnabled = false;

View File

@ -46,9 +46,9 @@ struct packedError
byte errorID : 6;
};
byte getNextError();
byte setError(byte);
void clearError(byte);
byte getNextError(void);
byte setError(byte errorID);
void clearError(byte errorID);
extern byte errorCount;

View File

@ -49,7 +49,7 @@ void clearError(byte errorID)
}
}
byte getNextError()
byte getNextError(void)
{
packedError currentError;
byte currentErrorNum = 0;

View File

@ -70,8 +70,9 @@ byte idleUpOutputHIGH = HIGH; // Used to invert the idle Up Output
byte idleUpOutputLOW = LOW; // Used to invert the idle Up Output
void initialiseIdle(bool forcehoming);
void initialiseIdleUpOutput();
void disableIdle();
void idleInterrupt();
void idleControl(void);
void initialiseIdleUpOutput(void);
void disableIdle(void);
void idleInterrupt(void);
#endif

View File

@ -20,7 +20,7 @@ integerPID idlePID(&currentStatus.longRPM, &idle_pid_target_value, &idle_cl_targ
//Any common functions associated with starting the Idle
//Typically this is enabling the PWM interrupt
static inline void enableIdle()
static inline void enableIdle(void)
{
if( (configPage6.iacAlgorithm == IAC_ALGORITHM_PWM_CL) || (configPage6.iacAlgorithm == IAC_ALGORITHM_PWM_OL) || (configPage6.iacAlgorithm == IAC_ALGORITHM_PWM_OLCL) )
{
@ -268,7 +268,7 @@ void initialiseIdle(bool forcehoming)
currentStatus.idleLoad = 0;
}
void initialiseIdleUpOutput()
void initialiseIdleUpOutput(void)
{
if (configPage2.idleUpOutputInv == 1) { idleUpOutputHIGH = LOW; idleUpOutputLOW = HIGH; }
else { idleUpOutputHIGH = HIGH; idleUpOutputLOW = LOW; }
@ -286,7 +286,7 @@ Returns:
True: If a step is underway or motor is 'cooling'
False: If the motor is ready for another step
*/
static inline byte checkForStepping()
static inline byte checkForStepping(void)
{
bool isStepping = false;
unsigned int timeCheck;
@ -341,7 +341,7 @@ static inline byte checkForStepping()
/*
Performs a step
*/
static inline void doStep()
static inline void doStep(void)
{
if ( (idleStepper.targetIdleStep <= (idleStepper.curIdleStep - configPage6.iacStepHyster)) || (idleStepper.targetIdleStep >= (idleStepper.curIdleStep + configPage6.iacStepHyster)) ) //Hysteresis check
{
@ -374,7 +374,7 @@ Returns:
True: If the system has been homed. No other action is taken
False: If the motor has not yet been homed. Will also perform another homing step.
*/
static inline byte isStepperHomed()
static inline byte isStepperHomed(void)
{
bool isHomed = true; //As it's the most common scenario, default value is true
if( completedHomeSteps < (configPage6.iacStepHome * 3) ) //Home steps are divided by 3 from TS
@ -391,7 +391,7 @@ static inline byte isStepperHomed()
return isHomed;
}
void idleControl()
void idleControl(void)
{
if( idleInitComplete != configPage6.iacAlgorithm) { initialiseIdle(false); }
if( (currentStatus.RPM > 0) || (configPage6.iacPWMrun == true) ) { enableIdle(); }
@ -798,7 +798,7 @@ void idleControl()
//This function simply turns off the idle PWM and sets the pin low
void disableIdle()
void disableIdle(void)
{
if( (configPage6.iacAlgorithm == IAC_ALGORITHM_PWM_CL) || (configPage6.iacAlgorithm == IAC_ALGORITHM_PWM_OL) )
{
@ -841,9 +841,9 @@ void disableIdle()
}
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER1_COMPC_vect)
ISR(TIMER1_COMPC_vect) //cppcheck-suppress misra-c2012-8.2
#else
void idleInterrupt() //Most ARM chips can simply call a function
void idleInterrupt(void) //Most ARM chips can simply call a function
#endif
{
if (idle_pwm_state)

View File

@ -1,9 +1,9 @@
#ifndef INIT_H
#define INIT_H
void initialiseAll();
void initialiseTriggers();
void setPinMapping(byte);
void initialiseAll(void);
void initialiseTriggers(void);
void setPinMapping(byte boardID);
void changeHalfToFullSync(void);
void changeFullToHalfSync(void);

View File

@ -45,7 +45,7 @@
* - Read CLT and TPS sensors to have cranking pulsewidths computed correctly
* - Mark Initialisation completed (this flag-marking is used in code to prevent after-init changes)
*/
void initialiseAll()
void initialiseAll(void)
{
fpPrimed = false;
injPrimed = false;
@ -2888,7 +2888,7 @@ void setPinMapping(byte boardID)
*
* @todo Explain why triggerSetup_*() alone cannot do all the setup, but there's ~10+ lines worth of extra init for each of decoders.
*/
void initialiseTriggers()
void initialiseTriggers(void)
{
byte triggerInterrupt = 0; // By default, use the first interrupt
byte triggerInterrupt2 = 1;

View File

@ -21,12 +21,12 @@
#define SD_LOG_NUM_FIELDS 90 /**< The number of fields that are in the log. This is always smaller than the entry size due to some fields being 2 bytes */
byte getTSLogEntry(uint16_t);
int16_t getReadableLogEntry(uint16_t);
byte getTSLogEntry(uint16_t byteNum);
int16_t getReadableLogEntry(uint16_t logIndex);
#if FPU_MAX_SIZE >= 32
float getReadableFloatLogEntry(uint16_t);
float getReadableFloatLogEntry(uint16_t logIndex);
#endif
bool is2ByteEntry(uint8_t);
bool is2ByteEntry(uint8_t key);
// This array indicates which index values from the log are 2 byte values
// This array MUST remain in ascending order

View File

@ -1,10 +1,9 @@
#ifndef MATH_H
#define MATH_H
int fastMap1023toX(int, int);
unsigned long percentage(uint8_t, unsigned long);
unsigned long halfPercentage(uint8_t, unsigned long);
inline long powint(int, unsigned int);
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);
#ifdef USE_LIBDIVIDE
#include "src/libdivide/libdivide.h"

View File

@ -414,7 +414,7 @@ page_iterator_t map_page_offset_to_entity(uint8_t pageNumber, uint16_t offset)
// ====================================== External functions ====================================
uint8_t getPageCount()
uint8_t getPageCount(void)
{
return _countof(ini_page_sizes);
}

View File

@ -5,7 +5,7 @@
/**
* Page count, as defined in the INI file
*/
uint8_t getPageCount();
uint8_t getPageCount(void);
/**
* Page size in bytes

View File

@ -3,130 +3,130 @@
#include <Arduino.h>
inline void openInjector1();
inline void closeInjector1();
inline void openInjector1(void);
inline void closeInjector1(void);
inline void openInjector2();
inline void closeInjector2();
inline void openInjector2(void);
inline void closeInjector2(void);
inline void openInjector3();
inline void closeInjector3();
inline void openInjector3(void);
inline void closeInjector3(void);
inline void openInjector4();
inline void closeInjector4();
inline void openInjector4(void);
inline void closeInjector4(void);
inline void openInjector5();
inline void closeInjector5();
inline void openInjector5(void);
inline void closeInjector5(void);
inline void openInjector6();
inline void closeInjector6();
inline void openInjector6(void);
inline void closeInjector6(void);
inline void openInjector7();
inline void closeInjector7();
inline void openInjector7(void);
inline void closeInjector7(void);
inline void openInjector8();
inline void closeInjector8();
inline void openInjector8(void);
inline void closeInjector8(void);
// These are for Semi-Sequential and 5 Cylinder injection
void openInjector1and3();
void closeInjector1and3();
void openInjector2and4();
void closeInjector2and4();
void openInjector1and4();
void closeInjector1and4();
void openInjector2and3();
void closeInjector2and3();
void openInjector1and3(void);
void closeInjector1and3(void);
void openInjector2and4(void);
void closeInjector2and4(void);
void openInjector1and4(void);
void closeInjector1and4(void);
void openInjector2and3(void);
void closeInjector2and3(void);
void openInjector3and5();
void closeInjector3and5();
void openInjector3and5(void);
void closeInjector3and5(void);
void openInjector2and5();
void closeInjector2and5();
void openInjector3and6();
void closeInjector3and6();
void openInjector2and5(void);
void closeInjector2and5(void);
void openInjector3and6(void);
void closeInjector3and6(void);
void openInjector1and5();
void closeInjector1and5();
void openInjector2and6();
void closeInjector2and6();
void openInjector3and7();
void closeInjector3and7();
void openInjector4and8();
void closeInjector4and8();
void openInjector1and5(void);
void closeInjector1and5(void);
void openInjector2and6(void);
void closeInjector2and6(void);
void openInjector3and7(void);
void closeInjector3and7(void);
void openInjector4and8(void);
void closeInjector4and8(void);
void injector1Toggle();
void injector2Toggle();
void injector3Toggle();
void injector4Toggle();
void injector5Toggle();
void injector6Toggle();
void injector7Toggle();
void injector8Toggle();
void injector1Toggle(void);
void injector2Toggle(void);
void injector3Toggle(void);
void injector4Toggle(void);
void injector5Toggle(void);
void injector6Toggle(void);
void injector7Toggle(void);
void injector8Toggle(void);
inline void beginCoil1Charge();
inline void endCoil1Charge();
inline void beginCoil1Charge(void);
inline void endCoil1Charge(void);
inline void beginCoil2Charge();
inline void endCoil2Charge();
inline void beginCoil2Charge(void);
inline void endCoil2Charge(void);
inline void beginCoil3Charge();
inline void endCoil3Charge();
inline void beginCoil3Charge(void);
inline void endCoil3Charge(void);
inline void beginCoil4Charge();
inline void endCoil4Charge();
inline void beginCoil4Charge(void);
inline void endCoil4Charge(void);
inline void beginCoil5Charge();
inline void endCoil5Charge();
inline void beginCoil5Charge(void);
inline void endCoil5Charge(void);
inline void beginCoil6Charge();
inline void endCoil6Charge();
inline void beginCoil6Charge(void);
inline void endCoil6Charge(void);
inline void beginCoil7Charge();
inline void endCoil7Charge();
inline void beginCoil7Charge(void);
inline void endCoil7Charge(void);
inline void beginCoil8Charge();
inline void endCoil8Charge();
inline void beginCoil8Charge(void);
inline 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();
inline void endTrailingCoilCharge1();
inline void endTrailingCoilCharge2();
inline void beginTrailingCoilCharge(void);
inline void endTrailingCoilCharge1(void);
inline void endTrailingCoilCharge2(void);
//And the combined versions of the above for simplicity
void beginCoil1and3Charge();
void endCoil1and3Charge();
void beginCoil2and4Charge();
void endCoil2and4Charge();
void beginCoil1and3Charge(void);
void endCoil1and3Charge(void);
void beginCoil2and4Charge(void);
void endCoil2and4Charge(void);
//For 6-cyl cop
void beginCoil1and4Charge();
void endCoil1and4Charge();
void beginCoil2and5Charge();
void endCoil2and5Charge();
void beginCoil3and6Charge();
void endCoil3and6Charge();
void beginCoil1and4Charge(void);
void endCoil1and4Charge(void);
void beginCoil2and5Charge(void);
void endCoil2and5Charge(void);
void beginCoil3and6Charge(void);
void endCoil3and6Charge(void);
//For 8-cyl cop
void beginCoil1and5Charge();
void endCoil1and5Charge();
void beginCoil2and6Charge();
void endCoil2and6Charge();
void beginCoil3and7Charge();
void endCoil3and7Charge();
void beginCoil4and8Charge();
void endCoil4and8Charge();
void beginCoil1and5Charge(void);
void endCoil1and5Charge(void);
void beginCoil2and6Charge(void);
void endCoil2and6Charge(void);
void beginCoil3and7Charge(void);
void endCoil3and7Charge(void);
void beginCoil4and8Charge(void);
void endCoil4and8Charge(void);
void coil1Toggle();
void coil2Toggle();
void coil3Toggle();
void coil4Toggle();
void coil5Toggle();
void coil6Toggle();
void coil7Toggle();
void coil8Toggle();
void coil1Toggle(void);
void coil2Toggle(void);
void coil3Toggle(void);
void coil4Toggle(void);
void coil5Toggle(void);
void coil6Toggle(void);
void coil7Toggle(void);
void coil8Toggle(void);
void tachoOutputOn();
void tachoOutputOff();
void tachoOutputOn(void);
void tachoOutputOff(void);
/*
#ifndef USE_MC33810
@ -267,6 +267,6 @@ void tachoOutputOff();
#define injector7Toggle_DIRECT() (*inj7_pin_port ^= inj7_pin_mask )
#define injector8Toggle_DIRECT() (*inj8_pin_port ^= inj8_pin_mask )
void nullCallback();
void nullCallback(void);
#endif

View File

@ -9,124 +9,124 @@
* 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() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector1_DIRECT(); } else { openInjector1_MC33810(); } }
inline void closeInjector1() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector1_DIRECT(); } else { closeInjector1_MC33810(); } }
inline void openInjector2() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector2_DIRECT(); } else { openInjector2_MC33810(); } }
inline void closeInjector2() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector2_DIRECT(); } else { closeInjector2_MC33810(); } }
inline void openInjector3() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector3_DIRECT(); } else { openInjector3_MC33810(); } }
inline void closeInjector3() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector3_DIRECT(); } else { closeInjector3_MC33810(); } }
inline void openInjector4() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector4_DIRECT(); } else { openInjector4_MC33810(); } }
inline void closeInjector4() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector4_DIRECT(); } else { closeInjector4_MC33810(); } }
inline void openInjector5() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector5_DIRECT(); } else { openInjector5_MC33810(); } }
inline void closeInjector5() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector5_DIRECT(); } else { closeInjector5_MC33810(); } }
inline void openInjector6() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector6_DIRECT(); } else { openInjector6_MC33810(); } }
inline void closeInjector6() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector6_DIRECT(); } else { closeInjector6_MC33810(); } }
inline void openInjector7() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector7_DIRECT(); } else { openInjector7_MC33810(); } }
inline void closeInjector7() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector7_DIRECT(); } else { closeInjector7_MC33810(); } }
inline void openInjector8() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { openInjector8_DIRECT(); } else { openInjector8_MC33810(); } }
inline void closeInjector8() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { closeInjector8_DIRECT(); } else { closeInjector8_MC33810(); } }
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() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector1Toggle_DIRECT(); } else { injector1Toggle_MC33810(); } }
inline void injector2Toggle() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector2Toggle_DIRECT(); } else { injector2Toggle_MC33810(); } }
inline void injector3Toggle() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector3Toggle_DIRECT(); } else { injector3Toggle_MC33810(); } }
inline void injector4Toggle() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector4Toggle_DIRECT(); } else { injector4Toggle_MC33810(); } }
inline void injector5Toggle() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector5Toggle_DIRECT(); } else { injector5Toggle_MC33810(); } }
inline void injector6Toggle() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector6Toggle_DIRECT(); } else { injector6Toggle_MC33810(); } }
inline void injector7Toggle() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector7Toggle_DIRECT(); } else { injector7Toggle_MC33810(); } }
inline void injector8Toggle() { if(injectorOutputControl != OUTPUT_CONTROL_MC33810) { injector8Toggle_DIRECT(); } else { injector8Toggle_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() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil1Toggle_DIRECT(); } else { coil1Toggle_MC33810(); } }
inline void coil2Toggle() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil2Toggle_DIRECT(); } else { coil2Toggle_MC33810(); } }
inline void coil3Toggle() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil3Toggle_DIRECT(); } else { coil3Toggle_MC33810(); } }
inline void coil4Toggle() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil4Toggle_DIRECT(); } else { coil4Toggle_MC33810(); } }
inline void coil5Toggle() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil5Toggle_DIRECT(); } else { coil5Toggle_MC33810(); } }
inline void coil6Toggle() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil6Toggle_DIRECT(); } else { coil6Toggle_MC33810(); } }
inline void coil7Toggle() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil7Toggle_DIRECT(); } else { coil7Toggle_MC33810(); } }
inline void coil8Toggle() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil8Toggle_DIRECT(); } else { coil8Toggle_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() { openInjector1(); openInjector3(); }
void closeInjector1and3() { closeInjector1(); closeInjector3(); }
void openInjector2and4() { openInjector2(); openInjector4(); }
void closeInjector2and4() { closeInjector2(); closeInjector4(); }
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() { openInjector1(); openInjector4(); }
void closeInjector1and4() { closeInjector1(); closeInjector4(); }
void openInjector2and3() { openInjector2(); openInjector3(); }
void closeInjector2and3() { closeInjector2(); closeInjector3(); }
void openInjector1and4(void) { openInjector1(); openInjector4(); }
void closeInjector1and4(void) { closeInjector1(); closeInjector4(); }
void openInjector2and3(void) { openInjector2(); openInjector3(); }
void closeInjector2and3(void) { closeInjector2(); closeInjector3(); }
void openInjector3and5() { openInjector3(); openInjector5(); }
void closeInjector3and5() { closeInjector3(); closeInjector5(); }
void openInjector3and5(void) { openInjector3(); openInjector5(); }
void closeInjector3and5(void) { closeInjector3(); closeInjector5(); }
void openInjector2and5() { openInjector2(); openInjector5(); }
void closeInjector2and5() { closeInjector2(); closeInjector5(); }
void openInjector3and6() { openInjector3(); openInjector6(); }
void closeInjector3and6() { closeInjector3(); closeInjector6(); }
void openInjector2and5(void) { openInjector2(); openInjector5(); }
void closeInjector2and5(void) { closeInjector2(); closeInjector5(); }
void openInjector3and6(void) { openInjector3(); openInjector6(); }
void closeInjector3and6(void) { closeInjector3(); closeInjector6(); }
void openInjector1and5() { openInjector1(); openInjector5(); }
void closeInjector1and5() { closeInjector1(); closeInjector5(); }
void openInjector2and6() { openInjector2(); openInjector6(); }
void closeInjector2and6() { closeInjector2(); closeInjector6(); }
void openInjector3and7() { openInjector3(); openInjector7(); }
void closeInjector3and7() { closeInjector3(); closeInjector7(); }
void openInjector4and8() { openInjector4(); openInjector8(); }
void closeInjector4and8() { closeInjector4(); closeInjector8(); }
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() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil1Charging_DIRECT(); } else { coil1Charging_MC33810(); } tachoOutputOn(); }
inline void endCoil1Charge() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil1StopCharging_DIRECT(); } else { coil1StopCharging_MC33810(); } tachoOutputOff(); }
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() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil2Charging_DIRECT(); } else { coil2Charging_MC33810(); } tachoOutputOn(); }
inline void endCoil2Charge() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil2StopCharging_DIRECT(); } else { coil2StopCharging_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() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil3Charging_DIRECT(); } else { coil3Charging_MC33810(); } tachoOutputOn(); }
inline void endCoil3Charge() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil3StopCharging_DIRECT(); } else { coil3StopCharging_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() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil4Charging_DIRECT(); } else { coil4Charging_MC33810(); } tachoOutputOn(); }
inline void endCoil4Charge() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil4StopCharging_DIRECT(); } else { coil4StopCharging_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() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil5Charging_DIRECT(); } else { coil5Charging_MC33810(); } tachoOutputOn(); }
inline void endCoil5Charge() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil5StopCharging_DIRECT(); } else { coil5StopCharging_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() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil6Charging_DIRECT(); } else { coil6Charging_MC33810(); } tachoOutputOn(); }
inline void endCoil6Charge() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil6StopCharging_DIRECT(); } else { coil6StopCharging_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() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil7Charging_DIRECT(); } else { coil7Charging_MC33810(); } tachoOutputOn(); }
inline void endCoil7Charge() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil7StopCharging_DIRECT(); } else { coil7StopCharging_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() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil8Charging_DIRECT(); } else { coil8Charging_MC33810(); } tachoOutputOn(); }
inline void endCoil8Charge() { if(ignitionOutputControl != OUTPUT_CONTROL_MC33810) { coil8StopCharging_DIRECT(); } else { coil8StopCharging_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() { beginCoil2Charge(); }
inline void endTrailingCoilCharge1() { endCoil2Charge(); beginCoil3Charge(); } //Sets ign3 (Trailing select) high
inline void endTrailingCoilCharge2() { endCoil2Charge(); endCoil3Charge(); } //sets ign3 (Trailing select) low
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() { beginCoil1Charge(); beginCoil3Charge(); }
void endCoil1and3Charge() { endCoil1Charge(); endCoil3Charge(); }
void beginCoil2and4Charge() { beginCoil2Charge(); beginCoil4Charge(); }
void endCoil2and4Charge() { endCoil2Charge(); endCoil4Charge(); }
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() { beginCoil1Charge(); beginCoil4Charge(); }
void endCoil1and4Charge() { endCoil1Charge(); endCoil4Charge(); }
void beginCoil2and5Charge() { beginCoil2Charge(); beginCoil5Charge(); }
void endCoil2and5Charge() { endCoil2Charge(); endCoil5Charge(); }
void beginCoil3and6Charge() { beginCoil3Charge(); beginCoil6Charge(); }
void endCoil3and6Charge() { endCoil3Charge(); endCoil6Charge(); }
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() { beginCoil1Charge(); beginCoil5Charge(); }
void endCoil1and5Charge() { endCoil1Charge(); endCoil5Charge(); }
void beginCoil2and6Charge() { beginCoil2Charge(); beginCoil6Charge(); }
void endCoil2and6Charge() { endCoil2Charge(); endCoil6Charge(); }
void beginCoil3and7Charge() { beginCoil3Charge(); beginCoil7Charge(); }
void endCoil3and7Charge() { endCoil3Charge(); endCoil7Charge(); }
void beginCoil4and8Charge() { beginCoil4Charge(); beginCoil8Charge(); }
void endCoil4and8Charge() { endCoil4Charge(); endCoil8Charge(); }
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() { if(configPage6.tachoMode) { TACHO_PULSE_LOW(); } else { tachoOutputFlag = READY; } }
void tachoOutputOff() { if(configPage6.tachoMode) { TACHO_PULSE_HIGH(); } }
void tachoOutputOn(void) { if(configPage6.tachoMode) { TACHO_PULSE_LOW(); } else { tachoOutputFlag = READY; } }
void tachoOutputOff(void) { if(configPage6.tachoMode) { TACHO_PULSE_HIGH(); } }
void nullCallback() { return; }
void nullCallback(void) { return; }

View File

@ -46,48 +46,48 @@ See page 136 of the processors datasheet: http://www.atmel.com/Images/doc2549.pd
#define USE_IGN_REFRESH
#define IGNITION_REFRESH_THRESHOLD 30 //Time in uS that the refresh functions will check to ensure there is enough time before changing the end compare
extern void (*inj1StartFunction)();
extern void (*inj1EndFunction)();
extern void (*inj2StartFunction)();
extern void (*inj2EndFunction)();
extern void (*inj3StartFunction)();
extern void (*inj3EndFunction)();
extern void (*inj4StartFunction)();
extern void (*inj4EndFunction)();
extern void (*inj5StartFunction)();
extern void (*inj5EndFunction)();
extern void (*inj6StartFunction)();
extern void (*inj6EndFunction)();
extern void (*inj7StartFunction)();
extern void (*inj7EndFunction)();
extern void (*inj8StartFunction)();
extern void (*inj8EndFunction)();
extern void (*inj1StartFunction)(void);
extern void (*inj1EndFunction)(void);
extern void (*inj2StartFunction)(void);
extern void (*inj2EndFunction)(void);
extern void (*inj3StartFunction)(void);
extern void (*inj3EndFunction)(void);
extern void (*inj4StartFunction)(void);
extern void (*inj4EndFunction)(void);
extern void (*inj5StartFunction)(void);
extern void (*inj5EndFunction)(void);
extern void (*inj6StartFunction)(void);
extern void (*inj6EndFunction)(void);
extern void (*inj7StartFunction)(void);
extern void (*inj7EndFunction)(void);
extern void (*inj8StartFunction)(void);
extern void (*inj8EndFunction)(void);
/** @name IgnitionCallbacks
* These are the (global) function pointers that get called to begin and end the ignition coil charging.
* They are required for the various spark output modes.
* @{
*/
extern void (*ign1StartFunction)();
extern void (*ign1EndFunction)();
extern void (*ign2StartFunction)();
extern void (*ign2EndFunction)();
extern void (*ign3StartFunction)();
extern void (*ign3EndFunction)();
extern void (*ign4StartFunction)();
extern void (*ign4EndFunction)();
extern void (*ign5StartFunction)();
extern void (*ign5EndFunction)();
extern void (*ign6StartFunction)();
extern void (*ign6EndFunction)();
extern void (*ign7StartFunction)();
extern void (*ign7EndFunction)();
extern void (*ign8StartFunction)();
extern void (*ign8EndFunction)();
extern void (*ign1StartFunction)(void);
extern void (*ign1EndFunction)(void);
extern void (*ign2StartFunction)(void);
extern void (*ign2EndFunction)(void);
extern void (*ign3StartFunction)(void);
extern void (*ign3EndFunction)(void);
extern void (*ign4StartFunction)(void);
extern void (*ign4EndFunction)(void);
extern void (*ign5StartFunction)(void);
extern void (*ign5EndFunction)(void);
extern void (*ign6StartFunction)(void);
extern void (*ign6EndFunction)(void);
extern void (*ign7StartFunction)(void);
extern void (*ign7EndFunction)(void);
extern void (*ign8StartFunction)(void);
extern void (*ign8EndFunction)(void);
/** @} */
void initialiseSchedulers();
void beginInjectorPriming();
void initialiseSchedulers(void);
void beginInjectorPriming(void);
void setFuelSchedule1(unsigned long timeout, unsigned long duration);
void setFuelSchedule2(unsigned long timeout, unsigned long duration);
void setFuelSchedule3(unsigned long timeout, unsigned long duration);
@ -110,45 +110,45 @@ inline void refreshIgnitionSchedule1(unsigned long timeToEnd) __attribute__((alw
//The ARM cores use separate functions for their ISRs
#if defined(ARDUINO_ARCH_STM32) || defined(CORE_TEENSY)
static inline void fuelSchedule1Interrupt();
static inline void fuelSchedule2Interrupt();
static inline void fuelSchedule3Interrupt();
static inline void fuelSchedule4Interrupt();
static inline void fuelSchedule1Interrupt(void);
static inline void fuelSchedule2Interrupt(void);
static inline void fuelSchedule3Interrupt(void);
static inline void fuelSchedule4Interrupt(void);
#if (INJ_CHANNELS >= 5)
static inline void fuelSchedule5Interrupt();
static inline void fuelSchedule5Interrupt(void);
#endif
#if (INJ_CHANNELS >= 6)
static inline void fuelSchedule6Interrupt();
static inline void fuelSchedule6Interrupt(void);
#endif
#if (INJ_CHANNELS >= 7)
static inline void fuelSchedule7Interrupt();
static inline void fuelSchedule7Interrupt(void);
#endif
#if (INJ_CHANNELS >= 8)
static inline void fuelSchedule8Interrupt();
static inline void fuelSchedule8Interrupt(void);
#endif
#if (IGN_CHANNELS >= 1)
static inline void ignitionSchedule1Interrupt();
static inline void ignitionSchedule1Interrupt(void);
#endif
#if (IGN_CHANNELS >= 2)
static inline void ignitionSchedule2Interrupt();
static inline void ignitionSchedule2Interrupt(void);
#endif
#if (IGN_CHANNELS >= 3)
static inline void ignitionSchedule3Interrupt();
static inline void ignitionSchedule3Interrupt(void);
#endif
#if (IGN_CHANNELS >= 4)
static inline void ignitionSchedule4Interrupt();
static inline void ignitionSchedule4Interrupt(void);
#endif
#if (IGN_CHANNELS >= 5)
static inline void ignitionSchedule5Interrupt();
static inline void ignitionSchedule5Interrupt(void);
#endif
#if (IGN_CHANNELS >= 6)
static inline void ignitionSchedule6Interrupt();
static inline void ignitionSchedule6Interrupt(void);
#endif
#if (IGN_CHANNELS >= 7)
static inline void ignitionSchedule7Interrupt();
static inline void ignitionSchedule7Interrupt(void);
#endif
#if (IGN_CHANNELS >= 8)
static inline void ignitionSchedule8Interrupt();
static inline void ignitionSchedule8Interrupt(void);
#endif
#endif
/** Schedule statuses.

View File

@ -47,41 +47,41 @@ Schedule ignitionSchedule6;
Schedule ignitionSchedule7;
Schedule ignitionSchedule8;
void (*inj1StartFunction)();
void (*inj1EndFunction)();
void (*inj2StartFunction)();
void (*inj2EndFunction)();
void (*inj3StartFunction)();
void (*inj3EndFunction)();
void (*inj4StartFunction)();
void (*inj4EndFunction)();
void (*inj5StartFunction)();
void (*inj5EndFunction)();
void (*inj6StartFunction)();
void (*inj6EndFunction)();
void (*inj7StartFunction)();
void (*inj7EndFunction)();
void (*inj8StartFunction)();
void (*inj8EndFunction)();
void (*inj1StartFunction)(void);
void (*inj1EndFunction)(void);
void (*inj2StartFunction)(void);
void (*inj2EndFunction)(void);
void (*inj3StartFunction)(void);
void (*inj3EndFunction)(void);
void (*inj4StartFunction)(void);
void (*inj4EndFunction)(void);
void (*inj5StartFunction)(void);
void (*inj5EndFunction)(void);
void (*inj6StartFunction)(void);
void (*inj6EndFunction)(void);
void (*inj7StartFunction)(void);
void (*inj7EndFunction)(void);
void (*inj8StartFunction)(void);
void (*inj8EndFunction)(void);
void (*ign1StartFunction)();
void (*ign1EndFunction)();
void (*ign2StartFunction)();
void (*ign2EndFunction)();
void (*ign3StartFunction)();
void (*ign3EndFunction)();
void (*ign4StartFunction)();
void (*ign4EndFunction)();
void (*ign5StartFunction)();
void (*ign5EndFunction)();
void (*ign6StartFunction)();
void (*ign6EndFunction)();
void (*ign7StartFunction)();
void (*ign7EndFunction)();
void (*ign8StartFunction)();
void (*ign8EndFunction)();
void (*ign1StartFunction)(void);
void (*ign1EndFunction)(void);
void (*ign2StartFunction)(void);
void (*ign2EndFunction)(void);
void (*ign3StartFunction)(void);
void (*ign3EndFunction)(void);
void (*ign4StartFunction)(void);
void (*ign4EndFunction)(void);
void (*ign5StartFunction)(void);
void (*ign5EndFunction)(void);
void (*ign6StartFunction)(void);
void (*ign6EndFunction)(void);
void (*ign7StartFunction)(void);
void (*ign7EndFunction)(void);
void (*ign8StartFunction)(void);
void (*ign8EndFunction)(void);
void initialiseSchedulers()
void initialiseSchedulers(void)
{
//nullSchedule.Status = OFF;
@ -795,7 +795,7 @@ void setIgnitionSchedule8(void (*startCallback)(), unsigned long timeout, unsign
* Set these to run at an arbitrary time in the future (100us).
* The prime pulse value is in ms*10, so need to multiple by 100 to get to uS
*/
extern void beginInjectorPriming()
extern void beginInjectorPriming(void)
{
unsigned long primingValue = table2D_getValue(&PrimingPulseTable, currentStatus.coolant + CALIBRATION_TEMPERATURE_OFFSET);
if( (primingValue > 0) && (currentStatus.TPS < configPage4.floodClear) )
@ -836,7 +836,8 @@ extern void beginInjectorPriming()
//Timer3A (fuel schedule 1) Compare Vector
#if (INJ_CHANNELS >= 1)
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega2561__) //AVR chips use the ISR for this
ISR(TIMER3_COMPA_vect) //fuelSchedules 1 and 5
//fuelSchedules 1 and 5
ISR(TIMER3_COMPA_vect) //cppcheck-suppress misra-c2012-8.2
#else
static inline void fuelSchedule1Interrupt() //Most ARM chips can simply call a function
#endif
@ -873,7 +874,7 @@ static inline void fuelSchedule1Interrupt() //Most ARM chips can simply call a f
#if (INJ_CHANNELS >= 2)
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega2561__) //AVR chips use the ISR for this
ISR(TIMER3_COMPB_vect) //fuelSchedule2
ISR(TIMER3_COMPB_vect) //cppcheck-suppress misra-c2012-8.2
#else
static inline void fuelSchedule2Interrupt() //Most ARM chips can simply call a function
#endif
@ -908,7 +909,7 @@ static inline void fuelSchedule2Interrupt() //Most ARM chips can simply call a f
#if (INJ_CHANNELS >= 3)
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega2561__) //AVR chips use the ISR for this
ISR(TIMER3_COMPC_vect) //fuelSchedule3
ISR(TIMER3_COMPC_vect) //cppcheck-suppress misra-c2012-8.2
#else
static inline void fuelSchedule3Interrupt() //Most ARM chips can simply call a function
#endif
@ -943,7 +944,7 @@ static inline void fuelSchedule3Interrupt() //Most ARM chips can simply call a f
#if (INJ_CHANNELS >= 4)
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega2561__) //AVR chips use the ISR for this
ISR(TIMER4_COMPB_vect) //fuelSchedule4
ISR(TIMER4_COMPB_vect) //cppcheck-suppress misra-c2012-8.2
#else
static inline void fuelSchedule4Interrupt() //Most ARM chips can simply call a function
#endif
@ -978,7 +979,7 @@ static inline void fuelSchedule4Interrupt() //Most ARM chips can simply call a f
#if (INJ_CHANNELS >= 5)
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER4_COMPC_vect) //fuelSchedule5
ISR(TIMER4_COMPC_vect) //cppcheck-suppress misra-c2012-8.2
#else
static inline void fuelSchedule5Interrupt() //Most ARM chips can simply call a function
#endif
@ -1011,7 +1012,7 @@ static inline void fuelSchedule5Interrupt() //Most ARM chips can simply call a f
#if (INJ_CHANNELS >= 6)
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER4_COMPA_vect) //fuelSchedule6
ISR(TIMER4_COMPA_vect) //cppcheck-suppress misra-c2012-8.2
#else
static inline void fuelSchedule6Interrupt() //Most ARM chips can simply call a function
#endif
@ -1046,7 +1047,7 @@ static inline void fuelSchedule6Interrupt() //Most ARM chips can simply call a f
#if (INJ_CHANNELS >= 7)
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER5_COMPC_vect) //fuelSchedule7
ISR(TIMER5_COMPC_vect) //cppcheck-suppress misra-c2012-8.2
#else
static inline void fuelSchedule7Interrupt() //Most ARM chips can simply call a function
#endif
@ -1081,7 +1082,7 @@ static inline void fuelSchedule7Interrupt() //Most ARM chips can simply call a f
#if (INJ_CHANNELS >= 8)
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER5_COMPB_vect) //fuelSchedule8
ISR(TIMER5_COMPB_vect) //cppcheck-suppress misra-c2012-8.2
#else
static inline void fuelSchedule8Interrupt() //Most ARM chips can simply call a function
#endif
@ -1116,9 +1117,9 @@ static inline void fuelSchedule8Interrupt() //Most ARM chips can simply call a f
#if IGN_CHANNELS >= 1
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER5_COMPA_vect) //ignitionSchedule1
ISR(TIMER5_COMPA_vect) //cppcheck-suppress misra-c2012-8.2
#else
static inline void ignitionSchedule1Interrupt() //Most ARM chips can simply call a function
static inline void ignitionSchedule1Interrupt(void) //Most ARM chips can simply call a function
#endif
{
if (ignitionSchedule1.Status == PENDING) //Check to see if this schedule is turn on
@ -1157,9 +1158,9 @@ static inline void ignitionSchedule1Interrupt() //Most ARM chips can simply call
#if IGN_CHANNELS >= 2
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER5_COMPB_vect) //ignitionSchedule2
ISR(TIMER5_COMPB_vect) //cppcheck-suppress misra-c2012-8.2
#else
static inline void ignitionSchedule2Interrupt() //Most ARM chips can simply call a function
static inline void ignitionSchedule2Interrupt(void) //Most ARM chips can simply call a function
#endif
{
if (ignitionSchedule2.Status == PENDING) //Check to see if this schedule is turn on
@ -1198,9 +1199,9 @@ static inline void ignitionSchedule2Interrupt() //Most ARM chips can simply call
#if IGN_CHANNELS >= 3
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER5_COMPC_vect) //ignitionSchedule3
ISR(TIMER5_COMPC_vect) //cppcheck-suppress misra-c2012-8.2
#else
static inline void ignitionSchedule3Interrupt() //Most ARM chips can simply call a function
static inline void ignitionSchedule3Interrupt(void) //Most ARM chips can simply call a function
#endif
{
if (ignitionSchedule3.Status == PENDING) //Check to see if this schedule is turn on
@ -1239,9 +1240,9 @@ static inline void ignitionSchedule3Interrupt() //Most ARM chips can simply call
#if IGN_CHANNELS >= 4
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER4_COMPA_vect) //ignitionSchedule4
ISR(TIMER4_COMPA_vect) //cppcheck-suppress misra-c2012-8.2
#else
static inline void ignitionSchedule4Interrupt() //Most ARM chips can simply call a function
static inline void ignitionSchedule4Interrupt(void) //Most ARM chips can simply call a function
#endif
{
if (ignitionSchedule4.Status == PENDING) //Check to see if this schedule is turn on
@ -1280,9 +1281,9 @@ static inline void ignitionSchedule4Interrupt() //Most ARM chips can simply call
#if IGN_CHANNELS >= 5
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER4_COMPC_vect) //ignitionSchedule5
ISR(TIMER4_COMPC_vect) //cppcheck-suppress misra-c2012-8.2
#else
static inline void ignitionSchedule5Interrupt() //Most ARM chips can simply call a function
static inline void ignitionSchedule5Interrupt(void) //Most ARM chips can simply call a function
#endif
{
if (ignitionSchedule5.Status == PENDING) //Check to see if this schedule is turn on
@ -1321,9 +1322,9 @@ static inline void ignitionSchedule5Interrupt() //Most ARM chips can simply call
#if IGN_CHANNELS >= 6
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER4_COMPB_vect) //ignitionSchedule6
ISR(TIMER4_COMPB_vect) //cppcheck-suppress misra-c2012-8.2
#else
static inline void ignitionSchedule6Interrupt() //Most ARM chips can simply call a function
static inline void ignitionSchedule6Interrupt(void) //Most ARM chips can simply call a function
#endif
{
if (ignitionSchedule6.Status == PENDING) //Check to see if this schedule is turn on
@ -1362,9 +1363,9 @@ static inline void ignitionSchedule6Interrupt() //Most ARM chips can simply call
#if IGN_CHANNELS >= 7
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER3_COMPC_vect) //ignitionSchedule6
ISR(TIMER3_COMPC_vect) //cppcheck-suppress misra-c2012-8.2
#else
static inline void ignitionSchedule7Interrupt() //Most ARM chips can simply call a function
static inline void ignitionSchedule7Interrupt(void) //Most ARM chips can simply call a function
#endif
{
if (ignitionSchedule7.Status == PENDING) //Check to see if this schedule is turn on
@ -1403,9 +1404,9 @@ static inline void ignitionSchedule7Interrupt() //Most ARM chips can simply call
#if IGN_CHANNELS >= 8
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER3_COMPB_vect) //ignitionSchedule8
ISR(TIMER3_COMPB_vect) //cppcheck-suppress misra-c2012-8.2
#else
static inline void ignitionSchedule8Interrupt() //Most ARM chips can simply call a function
static inline void ignitionSchedule8Interrupt(void) //Most ARM chips can simply call a function
#endif
{
if (ignitionSchedule8.Status == PENDING) //Check to see if this schedule is turn on

View File

@ -1,4 +1,4 @@
void calculateSecondaryFuel();
void calculateSecondarySpark();
byte getVE2();
byte getAdvance2();
void calculateSecondaryFuel(void);
void calculateSecondarySpark(void);
byte getVE2(void);
byte getAdvance2(void);

View File

@ -2,7 +2,7 @@
#include "secondaryTables.h"
#include "corrections.h"
void calculateSecondaryFuel()
void calculateSecondaryFuel(void)
{
//If the secondary fuel table is in use, also get the VE value from there
BIT_CLEAR(currentStatus.status3, BIT_STATUS3_FUEL2_ACTIVE); //Clear the bit indicating that the 2nd fuel table is in use.
@ -76,7 +76,7 @@ void calculateSecondaryFuel()
}
void calculateSecondarySpark()
void calculateSecondarySpark(void)
{
//Same as above but for the secondary ignition table
BIT_CLEAR(currentStatus.spark2, BIT_SPARK2_SPARK2_ACTIVE); //Clear the bit indicating that the 2nd spark table is in use.
@ -161,7 +161,7 @@ void calculateSecondarySpark()
* This performs largely the same operations as getVE() however the lookup is of the secondary fuel table and uses the secondary load source
* @return byte
*/
byte getVE2()
byte getVE2(void)
{
byte tempVE = 100;
if( configPage10.fuel2Algorithm == LOAD_SOURCE_MAP)
@ -190,7 +190,7 @@ byte getVE2()
*
* @return byte The current target advance value in degrees
*/
byte getAdvance2()
byte getAdvance2(void)
{
byte tempAdvance = 0;
if (configPage10.spark2Algorithm == LOAD_SOURCE_MAP) //Check which fuelling algorithm is being used

View File

@ -71,26 +71,26 @@ byte cltErrorCount = 0;
*/
#define ADC_FILTER(input, alpha, prior) (((long)input * (256 - alpha) + ((long)prior * alpha))) >> 8
static inline void instanteneousMAPReading() __attribute__((always_inline));
static inline void readMAP() __attribute__((always_inline));
static inline void validateMAP();
void initialiseADC();
void readTPS(bool=true); //Allows the option to override the use of the filter
void readO2_2();
void flexPulse();
uint32_t vssGetPulseGap(byte);
void vssPulse();
uint16_t getSpeed();
byte getGear();
byte getFuelPressure();
byte getOilPressure();
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);
void flexPulse(void);
uint32_t vssGetPulseGap(byte toothHistoryIndex);
void vssPulse(void);
uint16_t getSpeed(void);
byte getGear(void);
byte getFuelPressure(void);
byte getOilPressure(void);
uint16_t readAuxanalog(uint8_t analogPin);
uint16_t readAuxdigital(uint8_t digitalPin);
void readCLT(bool=true); //Allows the option to override the use of the filter
void readIAT();
void readO2();
void readBat();
void readBaro();
void readCLT(bool useFilter=true); //Allows the option to override the use of the filter
void readIAT(void);
void readO2(void);
void readBat(void);
void readBaro(void);
#if defined(ANALOG_ISR)
volatile int AnChannel[15];

View File

@ -20,7 +20,7 @@ A full copy of the license may be found in the projects root directory
/** Init all ADC conversions by setting resolutions, etc.
*/
void initialiseADC()
void initialiseADC(void)
{
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega2561__) //AVR chips use the ISR for this
@ -131,7 +131,7 @@ void initialiseADC()
vssIndex = 0;
}
static inline void validateMAP()
static inline void validateMAP(void)
{
//Error checks
if(currentStatus.MAP < VALID_MAP_MIN)
@ -157,7 +157,7 @@ static inline void validateMAP()
}
}
static inline void instanteneousMAPReading()
static inline void instanteneousMAPReading(void)
{
//Update the calculation times and last value. These are used by the MAP based Accel enrich
MAPlast = currentStatus.MAP;
@ -201,7 +201,7 @@ static inline void instanteneousMAPReading()
}
static inline void readMAP()
static inline void readMAP(void)
{
unsigned int tempReading;
//MAP Sampling system
@ -457,7 +457,7 @@ void readCLT(bool useFilter)
currentStatus.coolant = table2D_getValue(&cltCalibrationTable, currentStatus.cltADC) - CALIBRATION_TEMPERATURE_OFFSET; //Temperature calibration values are stored as positive bytes. We subtract 40 from them to allow for negative temperatures
}
void readIAT()
void readIAT(void)
{
unsigned int tempReading;
#if defined(ANALOG_ISR)
@ -471,7 +471,7 @@ void readIAT()
currentStatus.IAT = table2D_getValue(&iatCalibrationTable, currentStatus.iatADC) - CALIBRATION_TEMPERATURE_OFFSET;
}
void readBaro()
void readBaro(void)
{
if ( configPage6.useExtBaro != 0 )
{
@ -522,7 +522,7 @@ void readBaro()
}
}
void readO2()
void readO2(void)
{
//An O2 read is only performed if an O2 sensor type is selected. This is to prevent potentially dangerous use of the O2 readings prior to proper setup/calibration
if(configPage6.egoType > 0)
@ -547,7 +547,7 @@ void readO2()
}
void readO2_2()
void readO2_2(void)
{
//Second O2 currently disabled as its not being used
//Get the current O2 value.
@ -563,7 +563,7 @@ void readO2_2()
currentStatus.O2_2 = table2D_getValue(&o2CalibrationTable, currentStatus.O2_2ADC);
}
void readBat()
void readBat(void)
{
int tempReading;
#if defined(ANALOG_ISR)
@ -622,7 +622,7 @@ uint32_t vssGetPulseGap(byte historyIndex)
return tempGap;
}
uint16_t getSpeed()
uint16_t getSpeed(void)
{
uint16_t tempSpeed = 0;
@ -655,7 +655,7 @@ uint16_t getSpeed()
return tempSpeed;
}
byte getGear()
byte getGear(void)
{
byte tempGear = 0; //Unknown gear
if(currentStatus.vss > 0)
@ -676,7 +676,7 @@ byte getGear()
return tempGear;
}
byte getFuelPressure()
byte getFuelPressure(void)
{
int16_t tempFuelPressure = 0;
uint16_t tempReading;
@ -697,7 +697,7 @@ byte getFuelPressure()
return (byte)tempFuelPressure;
}
byte getOilPressure()
byte getOilPressure(void)
{
int16_t tempOilPressure = 0;
uint16_t tempReading;
@ -724,7 +724,7 @@ byte getOilPressure()
* The interrupt function for reading the flex sensor frequency and pulse width
* flexCounter value is incremented with every pulse and reset back to 0 once per second
*/
void flexPulse()
void flexPulse(void)
{
if(READ_FLEX() == true)
{
@ -742,7 +742,7 @@ void flexPulse()
* The interrupt function for pulses from a knock conditioner / controller
*
*/
void knockPulse()
void knockPulse(void)
{
//Check if this the start of a knock.
if(knockCounter == 0)
@ -759,7 +759,7 @@ void knockPulse()
* @brief The ISR function for VSS pulses
*
*/
void vssPulse()
void vssPulse(void)
{
//TODO: Add basic filtering here
vssIndex++;

View File

@ -13,24 +13,24 @@
#define SPEEDUINO_H
//#include "globals.h"
void setup();
void loop();
void setup(void);
void loop(void);
uint16_t PW(int REQ_FUEL, byte VE, long MAP, uint16_t corrections, int injOpen);
byte getVE1();
byte getAdvance1();
byte getVE1(void);
byte getAdvance1(void);
uint16_t calculateInjectorStartAngle(uint16_t, int16_t);
void calculateIgnitionAngle1(int);
void calculateIgnitionAngle2(int);
void calculateIgnitionAngle3(int);
void calculateIgnitionAngle3(int, int);
void calculateIgnitionAngle4(int);
void calculateIgnitionAngle4(int, int);
void calculateIgnitionAngle5(int);
void calculateIgnitionAngle6(int);
void calculateIgnitionAngle7(int);
void calculateIgnitionAngle8(int);
void calculateIgnitionAngles(int);
uint16_t calculateInjectorStartAngle(uint16_t PWdivTimerPerDegree, int16_t injChannelDegrees);
void calculateIgnitionAngle1(int dwellAngle);
void calculateIgnitionAngle2(int dwellAngle);
void calculateIgnitionAngle3(int dwellAngle);
void calculateIgnitionAngle3(int dwellAngle, int rotarySplitDegrees);
void calculateIgnitionAngle4(int dwellAngle);
void calculateIgnitionAngle4(int dwellAngle, int rotarySplitDegrees);
void calculateIgnitionAngle5(int dwellAngle);
void calculateIgnitionAngle6(int dwellAngle);
void calculateIgnitionAngle7(int dwellAngle);
void calculateIgnitionAngle8(int dwellAngle);
void calculateIgnitionAngles(int dwellAngle);
extern uint16_t req_fuel_uS; /**< The required fuel variable (As calculated by TunerStudio) in uS */
extern uint16_t inj_opentime_uS; /**< The injector opening time. This is set within Tuner Studio, but stored here in uS rather than mS */

View File

@ -85,7 +85,7 @@ uint32_t rollingCutLastRev = 0; /**< Tracks whether we're on the same or a diffe
uint16_t staged_req_fuel_mult_pri = 0;
uint16_t staged_req_fuel_mult_sec = 0;
#ifndef UNIT_TEST // Scope guard for unit testing
void setup()
void setup(void)
{
initialisationComplete = false; //Tracks whether the initialiseAll() function has run completely
initialiseAll();
@ -114,7 +114,7 @@ inline uint16_t applyFuelTrimToPW(trimTable3d *pTrimTable, int16_t fuelLoad, int
* - Can be tested for certain frequency interval being expired by (eg) BIT_CHECK(LOOP_TIMER, BIT_TIMER_15HZ)
*
*/
void loop()
void loop(void)
{
mainLoopCount++;
LOOP_TIMER = TIMER_mask;
@ -1378,7 +1378,7 @@ uint16_t PW(int REQ_FUEL, byte VE, long MAP, uint16_t corrections, int injOpen)
*
* @return byte The current VE value
*/
byte getVE1()
byte getVE1(void)
{
byte tempVE = 100;
if (configPage2.fuelAlgorithm == LOAD_SOURCE_MAP) //Check which fuelling algorithm is being used
@ -1407,7 +1407,7 @@ byte getVE1()
*
* @return byte The current target advance value in degrees
*/
byte getAdvance1()
byte getAdvance1(void)
{
byte tempAdvance = 0;
if (configPage2.ignAlgorithm == LOAD_SOURCE_MAP) //Check which fuelling algorithm is being used

View File

@ -30,14 +30,14 @@ A full copy of the license may be found in the projects root directory
uint32_t deferEEPROMWritesUntil = 0;
bool isEepromWritePending()
bool isEepromWritePending(void)
{
return BIT_CHECK(currentStatus.status4, BIT_STATUS4_BURNPENDING);
}
/** Write all config pages to EEPROM.
*/
void writeAllConfig()
void writeAllConfig(void)
{
uint8_t pageCount = getPageCount();
uint8_t page = 1U;
@ -327,7 +327,7 @@ void writeConfig(uint8_t pageNum)
/** Reset all configPage* structs (2,4,6,9,10,13) and write them full of null-bytes.
*/
void resetConfigPages()
void resetConfigPages(void)
{
for (uint8_t page=1; page<getPageCount(); ++page)
{
@ -406,7 +406,7 @@ static inline eeprom_address_t loadTable(const void *pTable, table_type_t key, e
/** Load all config tables from storage.
*/
void loadConfig()
void loadConfig(void)
{
loadTable(&fuelTable, decltype(fuelTable)::type_key, EEPROM_CONFIG1_MAP);
load_range(EEPROM_CONFIG2_START, (byte *)&configPage2, (byte *)&configPage2+sizeof(configPage2));
@ -479,7 +479,7 @@ void loadConfig()
/** Read the calibration information from EEPROM.
This is separate from the config load as the calibrations do not exist as pages within the ini file for Tuner Studio.
*/
void loadCalibration()
void loadCalibration(void)
{
// If you modify this function be sure to also modify writeCalibration();
// it should be a mirror image of this function.
@ -498,7 +498,7 @@ void loadCalibration()
This takes the values in the 3 calibration tables (Coolant, Inlet temp and O2)
and saves them to the EEPROM.
*/
void writeCalibration()
void writeCalibration(void)
{
// If you modify this function be sure to also modify loadCalibration();
// it should be a mirror image of this function.
@ -609,7 +609,7 @@ uint32_t readCalibrationCRC32(uint8_t calibrationPageNum)
return crc32_val;
}
uint16_t getEEPROMSize()
uint16_t getEEPROMSize(void)
{
return EEPROM.length();
}
@ -617,10 +617,10 @@ uint16_t getEEPROMSize()
// Utility functions.
// By having these in this file, it prevents other files from calling EEPROM functions directly. This is useful due to differences in the EEPROM libraries on different devces
/// Read last stored barometer reading from EEPROM.
byte readLastBaro() { return EEPROM.read(EEPROM_LAST_BARO); }
byte readLastBaro(void) { return EEPROM.read(EEPROM_LAST_BARO); }
/// Write last acquired arometer reading to EEPROM.
void storeLastBaro(byte newValue) { EEPROM.update(EEPROM_LAST_BARO, newValue); }
/// Read EEPROM current data format version (from offset EEPROM_DATA_VERSION).
byte readEEPROMVersion() { return EEPROM.read(EEPROM_DATA_VERSION); }
byte readEEPROMVersion(void) { return EEPROM.read(EEPROM_DATA_VERSION); }
/// Store EEPROM current data format version (to offset EEPROM_DATA_VERSION).
void storeEEPROMVersion(byte newVersion) { EEPROM.update(EEPROM_DATA_VERSION, newVersion); }

View File

@ -120,27 +120,27 @@
*
*/
void writeAllConfig();
void writeAllConfig(void);
void writeConfig(uint8_t pageNum);
void EEPROMWriteRaw(uint16_t address, uint8_t data);
uint8_t EEPROMReadRaw(uint16_t address);
void loadConfig();
void loadCalibration();
void writeCalibration();
void loadConfig(void);
void loadCalibration(void);
void writeCalibration(void);
void writeCalibrationPage(uint8_t pageNum);
void resetConfigPages();
void resetConfigPages(void);
//These are utility functions that prevent other files from having to use EEPROM.h directly
byte readLastBaro();
void storeLastBaro(byte);
uint8_t readEEPROMVersion();
void storeEEPROMVersion(uint8_t);
byte readLastBaro(void);
void storeLastBaro(byte newValue);
uint8_t readEEPROMVersion(void);
void storeEEPROMVersion(byte newVersion);
void storePageCRC32(uint8_t pageNum, uint32_t crcValue);
uint32_t readPageCRC32(uint8_t pageNum);
void storeCalibrationCRC32(uint8_t calibrationPageNum, uint32_t calibrationCRC);
uint32_t readCalibrationCRC32(uint8_t calibrationPageNum);
uint16_t getEEPROMSize();
bool isEepromWritePending();
uint16_t getEEPROMSize(void);
bool isEepromWritePending(void);
extern uint32_t deferEEPROMWritesUntil;

View File

@ -33,10 +33,9 @@ struct table2D {
byte cacheTime; //Tracks when the last cache value was set so it can expire after x seconds. A timeout is required to pickup when a tuning value is changed, otherwise the old cached value will continue to be returned as the X value isn't changing.
};
void table2D_setSize(struct table2D*, byte);
int16_t table2D_getAxisValue(struct table2D*, byte);
int16_t table2D_getRawValue(struct table2D*, byte);
int16_t table2D_getAxisValue(struct table2D *fromTable, byte X_in);
int16_t table2D_getRawValue(struct table2D *fromTable, byte X_index);
int table2D_getValue(struct table2D *fromTable, int);
int table2D_getValue(struct table2D *fromTable, int X_in);
#endif // TABLE_H

View File

@ -14,7 +14,7 @@ Note that this may clear some of the existing values of the table
#endif
static inline uint8_t getCacheTime() {
static inline uint8_t getCacheTime(void) {
#if !defined(UNIT_TEST)
return currentStatus.secl;
#else

View File

@ -46,24 +46,24 @@ public:
}
/** @brief Increment the iterator by one element*/
inline table_axis_iterator& operator++()
inline table_axis_iterator& operator++(void)
{
return advance(1);
}
/** @brief Test for end of iteration */
inline bool at_end() const
inline bool at_end(void) const
{
return _pAxis == _pAxisEnd;
}
/** @brief Dereference the iterator */
inline table3d_axis_t& operator*()
inline table3d_axis_t& operator*(void)
{
return *const_cast<table3d_axis_t *>(_pAxis);
}
/** @copydoc table_axis_iterator::operator*() */
inline const table3d_axis_t& operator*() const
inline const table3d_axis_t& operator*(void) const
{
return *_pAxis;
}
@ -72,7 +72,7 @@ public:
*
* Iterate from the end to the start. <b>This is only meant to be called on a freshly constructed iterator.</b>
*/
inline table_axis_iterator& reverse()
inline table_axis_iterator& reverse(void)
{
const table3d_axis_t *_pOldAxis = _pAxis;
_pAxis = _pAxisEnd - _stride;
@ -104,7 +104,7 @@ private:
table3d_axis_t axis[size]; \
\
/** @brief Iterate over the axis elements */ \
inline table_axis_iterator begin() \
inline table_axis_iterator begin(void) \
{ \
return table_axis_iterator(axis, axis+size, 1, domain); \
} \

View File

@ -31,9 +31,9 @@ public:
}
/** @brief Pointer to the end of the row */
inline const table3d_value_t* end() const { return pEnd; }
inline const table3d_value_t* end(void) const { return pEnd; }
/** @copydoc table_row_iterator::end() const */
inline table3d_value_t* end() { return const_cast<table3d_value_t *>(pEnd); }
inline table3d_value_t* end(void) { return const_cast<table3d_value_t *>(pEnd); }
/** @brief Advance the iterator
* @param steps The number of elements to move the iterator
@ -45,30 +45,30 @@ public:
}
/** @brief Increment the iterator by one element*/
inline table_row_iterator& operator++()
inline table_row_iterator& operator++(void)
{
return advance(1);
}
/** @brief Test for end of iteration */
inline bool at_end() const
inline bool at_end(void) const
{
return pValue == pEnd;
}
/** @brief Dereference the iterator */
inline const table3d_value_t& operator*() const
inline const table3d_value_t& operator*(void) const
{
return *pValue;
}
/** @copydoc table_row_iterator::operator*() const */
inline table3d_value_t& operator*()
inline table3d_value_t& operator*(void)
{
return *const_cast<table3d_value_t *>(pValue);
}
/** @brief Number of elements available */
inline table3d_dim_t size() const { return pEnd-pValue; }
inline table3d_dim_t size(void) const { return pEnd-pValue; }
private:
const table3d_value_t *pValue;
@ -115,24 +115,24 @@ public:
}
/** @brief Increment the iterator by one \b row */
inline table_value_iterator& operator++()
inline table_value_iterator& operator++(void)
{
return advance(1);
}
/** @brief Dereference the iterator to access a row of data */
inline const table_row_iterator operator*() const
inline const table_row_iterator operator*(void) const
{
return table_row_iterator(pRowsStart, rowWidth);
}
/** @copydoc table_value_iterator::operator*() const */
inline table_row_iterator operator*()
inline table_row_iterator operator*(void)
{
return table_row_iterator(pRowsStart, rowWidth);
}
/** @brief Test for end of iteration */
inline bool at_end() const
inline bool at_end(void) const
{
return pRowsStart == pRowsEnd;
}

View File

@ -41,10 +41,10 @@ volatile uint16_t last250msLoopCount = 1000; //Set to effectively random number
#if defined (CORE_TEENSY)
IntervalTimer lowResTimer;
void oneMSInterval();
void oneMSInterval(void);
#elif defined (ARDUINO_ARCH_STM32)
void oneMSInterval();
void oneMSInterval(void);
#endif
void initialiseTimers();
void initialiseTimers(void);
#endif // TIMERS_H

View File

@ -24,7 +24,7 @@ Timers are typically low resolution (Compared to Schedulers), with maximum frequ
#include <avr/wdt.h>
#endif
void initialiseTimers()
void initialiseTimers(void)
{
lastRPM_100ms = 0;
loop33ms = 0;
@ -39,9 +39,10 @@ void initialiseTimers()
//Timer2 Overflow Interrupt Vector, called when the timer overflows.
//Executes every ~1ms.
#if defined(CORE_AVR) //AVR chips use the ISR for this
ISR(TIMER2_OVF_vect, ISR_NOBLOCK) //This MUST be no block. Turning NO_BLOCK off messes with timing accuracy
//This MUST be no block. Turning NO_BLOCK off messes with timing accuracy.
ISR(TIMER2_OVF_vect, ISR_NOBLOCK) //cppcheck-suppress misra-c2012-8.2
#else
void oneMSInterval() //Most ARM chips can simply call a function
void oneMSInterval(void) //Most ARM chips can simply call a function
#endif
{
ms_counter++;

View File

@ -3,8 +3,8 @@
#include "table3d.h"
void doUpdates();
void multiplyTableLoad(const void*, table_type_t, uint8_t); //Added 202201 - to update the table Y axis as TPS now works at 0.5% increments. Multiplies the load axis values by 4 (most tables) or by 2 (VVT table)
void divideTableLoad(const void*, table_type_t, uint8_t); //Added 202201 - to update the table Y axis as TPS now works at 0.5% increments. This should only be needed by the VVT tables when using MAP as load.
void doUpdates(void);
void multiplyTableLoad(const void *pTable, table_type_t key, uint8_t multiplier); //Added 202201 - to update the table Y axis as TPS now works at 0.5% increments. Multiplies the load axis values by 4 (most tables) or by 2 (VVT table)
void divideTableLoad(const void *pTable, table_type_t key, uint8_t divisor); //Added 202201 - to update the table Y axis as TPS now works at 0.5% increments. This should only be needed by the VVT tables when using MAP as load.
#endif

View File

@ -14,7 +14,7 @@
#include "updates.h"
#include EEPROM_LIB_H //This is defined in the board .h files
void doUpdates()
void doUpdates(void)
{
#define CURRENT_DATA_VERSION 21
//Only the latest update for small flash devices must be retained

View File

@ -30,11 +30,11 @@ extern uint8_t pinIsValid;
extern uint8_t currentRuleStatus;
//uint8_t outputPin[sizeof(configPage13.outputPin)];
void setResetControlPinState();
byte pinTranslate(byte);
byte pinTranslateAnalog(byte);
void initialiseProgrammableIO();
void checkProgrammableIO();
void setResetControlPinState(void);
byte pinTranslate(byte rawPin);
byte pinTranslateAnalog(byte rawPin);
void initialiseProgrammableIO(void);
void checkProgrammableIO(void);
int16_t ProgrammableIOGetData(uint16_t index);
#if !defined(UNUSED)

View File

@ -91,7 +91,7 @@ byte pinTranslateAnalog(byte rawPin)
}
void setResetControlPinState()
void setResetControlPinState(void)
{
BIT_CLEAR(currentStatus.status3, BIT_STATUS3_RESET_PREVENT);
@ -118,7 +118,7 @@ void setResetControlPinState()
}
//*********************************************************************************************************************************************************************************
void initialiseProgrammableIO()
void initialiseProgrammableIO(void)
{
uint8_t outputPin;
for (uint8_t y = 0; y < sizeof(configPage13.outputPin); y++)
@ -149,7 +149,7 @@ void initialiseProgrammableIO()
* Use ProgrammableIOGetData() to get 2 vars to compare.
* Skip all programmable I/O:s where output pin is set 0 (meaning: not programmed).
*/
void checkProgrammableIO()
void checkProgrammableIO(void)
{
int16_t data, data2;
uint8_t dataRequested;