I’ve baked in everything for:
presets for 6-cyl (60°) and 8-cyl (45°),
coil-per-cylinder ignition (one ignition output per cyl),
EEPROM save/load/defaults for maps + firing order,
still portable across PIC18F47K42 and PIC18F57Q84/43, XC8 2.x, no MCC.
Below is a single drop-in XC8 source you can build in two configurations (6-cyl or 8-cyl). It keeps your event-queue + Timer1 + CCP1 compare scheduler, adds per-cylinder ignition pins, and a tiny CLI:
preset ... → common firing orders (6-cyl: 1-5-3-6-2-4 / 1-4-2-5-3-6; 8-cyl: SBC/LS/Ford HO)
save / load / defaults
order <idx> <cyl> (manual map)
set ia/sa/pw <cyl> <val> (injection angle, spark angle, pulse width)
PIC firmware (XC8, K42/Q84, 6-cyl or 8-cyl, coil-per-cyl + EEPROM)
Wiring (defaults)
Layer-A sensors (edges @ cam speed): PORTB RB0..RB(N-1), active-LOW
Layer-B (optional, dual-stack): PORTA RA0..RA(N-1), active-LOW
Injectors: PORTC RC0..RC(N-1), active-HIGH
Ignition (coil-per-cyl): PORTD RD0..RD(N-1), active-HIGH
Status LED: RE0
Single-coil fallback: RE1 (compile-time switch)
/* ==============================================================
 *  Meyer-Style Optical Distributor (6/8 cyl) + Coil-per-Cyl + EEPROM
 *  Targets: PIC18F47K42 (Curiosity Nano)  or  PIC18F57Q84/43
 *  Toolchain: MPLAB X + XC8 v2.x
 *  Features:
 *    - 6 or 8 cylinders (compile-time)
 *    - Coil-per-cylinder ignition (RDx) or single-coil (RE1)
 *    - Layer-A sensors on RBx, optional Layer-B on RAx (dual-stack)
 *    - Timer1 + CCP1 compare event scheduler (µs-accurate)
 *    - CLI: get/set/preset/order/save/load/defaults
 *    - EEPROM config with CRC16-CCITT
 * ============================================================== */
#include <xc.h>
#include <stdint.h>
#include <stdbool.h>
#include <stdio.h>
#include <stdarg.h>
#include <string.h>
/*================= SELECT BUILD OPTIONS =================*/
// Target (pick one)
#define TARGET_K42   1      // 1=PIC18F47K42, 0=57Q84/43
#define TARGET_Q84   0
// Cylinder count (build one of these two projects)
#define CYL_COUNT    6      // <-- set 6  OR  8
// Timing tick: 64MHz (0.5us) or 32MHz (1.0us)
#define FOSC_HZ      64000000UL  // set 32000000UL for exact 1.000us tick
#define T1_PRESCALE  8           // 1,2,4,8  (hardware max)
// Dual stack edge source (second optical layer on PORTA)
#define MODE_DUAL    0           // 0=single layer A only, 1=dual (spark off layer B)
// Ignition style
#define COIL_PER_CYL 1           // 1=RDx per cylinder, 0=single-coil RE1
/*================= CONFIG BITS (minimal) =================*/
#if TARGET_K42
#pragma config FEXTOSC=OFF, RSTOSC=HFINTOSC_64MHZ /* 32MHZ for 1us tick */
#pragma config CLKOUTEN=OFF, PR1WAY=ON, CSWEN=ON, MCLRE=EXTMCLR
#pragma config WDTE=OFF, LVP=ON, IVT1WAY=ON, MVECEN=ON
#else
#pragma config FEXTOSC=OFF, RSTOSC=HFINTOSC_64MHZ /* 32MHZ for 1us tick */
#pragma config CLKOUTEN=OFF, MCLRE=EXTMCLR, WDTE=OFF, LVP=ON, PBADEN=OFF
#endif
/*================= Derived timing =================*/
#define T1_TICK_US   ((double)(T1_PRESCALE*4.0e6)/(double)FOSC_HZ) // e.g., 0.5us at 64M/1:8
/*================= Pins (default map) =================*/
// Status LED
#define LED_LAT   LATEbits.LATE0
#define LED_TRIS  TRISEbits.TRISE0
// Single-coil output (if COIL_PER_CYL==0)
#define IGN_LAT   LATEbits.LATE1
#define IGN_TRIS  TRISEbits.TRISE1
// Injectors: RC0..RC(N-1)
static inline void inj_init_pins(void){
#if CYL_COUNT>=1
  TRISCbits.TRISC0=0; LATCbits.LATC0=0;
#endif
#if CYL_COUNT>=2
  TRISCbits.TRISC1=0; LATCbits.LATC1=0;
#endif
#if CYL_COUNT>=3
  TRISCbits.TRISC2=0; LATCbits.LATC2=0;
#endif
#if CYL_COUNT>=4
  TRISCbits.TRISC3=0; LATCbits.LATC3=0;
#endif
#if CYL_COUNT>=5
  TRISCbits.TRISC4=0; LATCbits.LATC4=0;
#endif
#if CYL_COUNT>=6
  TRISCbits.TRISC5=0; LATCbits.LATC5=0;
#endif
#if CYL_COUNT>=7
  TRISCbits.TRISC6=0; LATCbits.LATC6=0;
#endif
#if CYL_COUNT>=8
  TRISCbits.TRISC7=0; LATCbits.LATC7=0;
#endif
}
static inline void INJ_SET(uint8_t c, uint8_t on){
  switch(c){
    case 0: LATCbits.LATC0=on; break; case 1: LATCbits.LATC1=on; break;
    case 2: LATCbits.LATC2=on; break; case 3: LATCbits.LATC3=on; break;
#if CYL_COUNT>=5
    case 4: LATCbits.LATC4=on; break; case 5: LATCbits.LATC5=on; break;
#endif
#if CYL_COUNT>=7
    case 6: LATCbits.LATC6=on; break; case 7: LATCbits.LATC7=on; break;
#endif
  }
}
// Coil-per-cylinder: RD0..RD(N-1)
#if COIL_PER_CYL
static inline void ign_init_pins(void){
#if CYL_COUNT>=1
  TRISDbits.TRISD0=0; LATDbits.LATD0=0;
#endif
#if CYL_COUNT>=2
  TRISDbits.TRISD1=0; LATDbits.LATD1=0;
#endif
#if CYL_COUNT>=3
  TRISDbits.TRISD2=0; LATDbits.LATD2=0;
#endif
#if CYL_COUNT>=4
  TRISDbits.TRISD3=0; LATDbits.LATD3=0;
#endif
#if CYL_COUNT>=5
  TRISDbits.TRISD4=0; LATDbits.LATD4=0;
#endif
#if CYL_COUNT>=6
  TRISDbits.TRISD5=0; LATDbits.LATD5=0;
#endif
#if CYL_COUNT>=7
  TRISDbits.TRISD6=0; LATDbits.LATD6=0;
#endif
#if CYL_COUNT>=8
  TRISDbits.TRISD7=0; LATDbits.LATD7=0;
#endif
}
static inline void IGN_SET(uint8_t c, uint8_t on){
  switch(c){
    case 0: LATDbits.LATD0=on; break; case 1: LATDbits.LATD1=on; break;
    case 2: LATDbits.LATD2=on; break; case 3: LATDbits.LATD3=on; break;
#if CYL_COUNT>=5
    case 4: LATDbits.LATD4=on; break; case 5: LATDbits.LATD5=on; break;
#endif
#if CYL_COUNT>=7
    case 6: LATDbits.LATD6=on; break; case 7: LATDbits.LATD7=on; break;
#endif
  }
}
#else
static inline void ign_init_pins(void){ IGN_TRIS=0; IGN_LAT=0; }
static inline void IGN_SET(uint8_t c, uint8_t on){ (void)c; IGN_LAT=on; }
#endif
/*================= Distributor math =================*/
#define SECTOR_DEG  (360.0f/(float)CYL_COUNT)
static volatile float   us_per_cam_deg = 100.0f;
static volatile uint16_t rpm_cam = 0;
/*================= Per-cylinder maps =================*/
static volatile float inj_deg[CYL_COUNT] = {10};
static volatile float spk_deg[CYL_COUNT] = {20};
static volatile float inj_ms [CYL_COUNT] = {3.0};
static volatile uint8_t firingOrder[CYL_COUNT]; // sensor index -> cylinder index (0-based)
/*================= Event queue & timebase =============*/
typedef enum {EV_NONE=0, EV_INJ_ON, EV_INJ_OFF, EV_SPK_ON, EV_SPK_OFF} ev_t;
typedef struct { uint32_t due; ev_t type; uint8_t cyl; } event_t;
#define QSIZE  48
static volatile event_t q[QSIZE];
static volatile uint8_t qh=0, qt=0;
static volatile uint32_t t32=0;
static inline double TICK_US(void){ return T1_TICK_US; }
static inline uint32_t now_us(void){
  uint16_t lo=TMR1; uint32_t hi=t32 & 0xFFFF0000UL;
  if(PIR4bits.TMR1IF && lo<0x8000) hi+=0x00010000UL;
  return hi|lo;
}
static inline void q_push(event_t e){ uint8_t n=(qt+1u)%QSIZE; if(n!=qh){ q[qt]=e; qt=n; } }
static inline bool q_peek(event_t*e){ if(qh==qt) return false; *e=q[qh]; return true; }
static inline bool q_pop(event_t*e){ if(qh==qt) return false; *e=q[qh]; qh=(qh+1u)%QSIZE; return true; }
static void arm_next_compare(void){
  if(qh==qt){ CCPR1 = TMR1 + 1000; return; }
  uint8_t i=qh, idx=qh; uint32_t now=now_us(); uint32_t best=q[qh].due;
  while(i!=qt){
    if((int32_t)(q.due - now) < (int32_t)(best - now)){ best=q.due; idx=i; }
    i=(i+1u)%QSIZE;
  }
  event_t t=q[qh]; q[qh]=q[idx]; q[idx]=t;
  CCPR1 = (uint16_t)(q[qh].due & 0xFFFF);
}
/*================= EEPROM config (CRC16) ==============*/
typedef struct {
  uint16_t magic;   // 0xBEE6
  uint8_t  ver;     // 1
  uint8_t  cyl;     // CYL_COUNT
  uint8_t  modeDual;
  uint8_t  reserved;
  uint8_t  firing[8];
  float    ia[8];
  float    sa[8];
  float    pw[8];
  uint16_t crc;
} cfg_t;
#define CFG_MAGIC 0xBEE6
#define CFG_VER   1
#define EE_BASE   0x0000
static uint16_t crc16(const uint8_t* p, uint16_t n){
  uint16_t c=0xFFFF;
  while(n--){
    c ^= (uint16_t)(*p++)<<8;
    for(uint8_t i=0;i<8;i++)
      c = (c&0x8000)? (c<<1)^0x1021 : (c<<1);
  }
  return c;
}
// Low-level EEPROM R/W for K42/Q84
static void ee_write_byte(uint16_t a, uint8_t v){
  NVMADRL = a & 0xFF; NVMADRH = a>>8;
  NVMDATL = v;  NVMCON1 = 0x04; // WREN=1, CFGS=0, FREE=0,  EE write
  INTCON0bits.GIE=0;
  NVMCON2=0x55; NVMCON2=0xAA; NVMCON1bits.WR=1;
  while(NVMCON1bits.WR);
  NVMCON1bits.WREN=0; INTCON0bits.GIE=1;
}
static uint8_t ee_read_byte(uint16_t a){
  NVMADRL = a & 0xFF; NVMADRH = a>>8;
  NVMCON1 = 0x00; // CFGS=0, FREE=0
  NVMCON1bits.RD=1;
  return NVMDATL;
}
static void ee_write_block(uint16_t a, const uint8_t* b, uint16_t n){ while(n--) ee_write_byte(a++,*b++); }
static void ee_read_block (uint16_t a,       uint8_t* b, uint16_t n){ while(n--) *b++=ee_read_byte(a++); }
static void cfg_save(void){
  cfg_t c={0};
  c.magic=CFG_MAGIC; c.ver=CFG_VER; c.cyl=CYL_COUNT; c.modeDual=MODE_DUAL;
  for(uint8_t i=0;i<CYL_COUNT;i++){ c.firing=firingOrder; c.ia=inj_deg; c.sa=spk_deg; c.pw=inj_ms; }
  c.crc=0;
  c.crc = crc16((const uint8_t*)&c, sizeof(cfg_t)-2);
  ee_write_block(EE_BASE,(const uint8_t*)&c,sizeof c);
}
static bool cfg_load(void){
  cfg_t c; ee_read_block(EE_BASE,(uint8_t*)&c,sizeof c);
  if(c.magic!=CFG_MAGIC || c.ver!=CFG_VER || c.cyl!=CYL_COUNT) return false;
  uint16_t chk=crc16((const uint8_t*)&c,sizeof(cfg_t)-2);
  if(chk!=c.crc) return false;
  for(uint8_t i=0;i<CYL_COUNT;i++){
    firingOrder=c.firing; inj_deg=c.ia; spk_deg=c.sa; inj_ms=c.pw;
  }
  return true;
}
/*================= Presets (firing orders) ============*/
// Map is "sensor index 0..N-1" -> "cylinder index 0..N-1"
// Presets assume sensor #0 aligns with cylinder #1 TDC compression reference.
// 6-cyl common:
//   I6_A: 1-5-3-6-2-4    (e.g., Toyota/BMW inline-6 classics)
//   I6_B: 1-4-2-5-3-6
static const uint8_t FO_6_I6_A[6]={0,4,2,5,1,3};
static const uint8_t FO_6_I6_B[6]={0,3,1,4,2,5};
// 8-cyl common:
//   SBC (Chevy): 1-8-4-3-6-5-7-2
//   LS (Chevy):  1-8-7-2-6-5-4-3
//   Ford HO/351: 1-3-7-2-6-5-4-8
static const uint8_t FO_8_SBC[8]={0,7,3,2,5,4,6,1};
static const uint8_t FO_8_LS [8]={0,7,6,1,5,4,3,2};
static const uint8_t FO_8_FHO[8]={0,2,6,1,5,4,3,7};
static void apply_preset(const char* name){
#if CYL_COUNT==6
  if(!strcmp(name,"i6_153624")) memcpy((void*)firingOrder,FO_6_I6_A,6);
  else if(!strcmp(name,"i6_142536")) memcpy((void*)firingOrder,FO_6_I6_B,6);
  else memcpy((void*)firingOrder,FO_6_I6_A,6);
#elif CYL_COUNT==8
  if(!strcmp(name,"v8_sbc")) memcpy((void*)firingOrder,FO_8_SBC,8);
  else if(!strcmp(name,"v8_ls")) memcpy((void*)firingOrder,FO_8_LS,8);
  else if(!strcmp(name,"v8_ford_ho")) memcpy((void*)firingOrder,FO_8_FHO,8);
  else memcpy((void*)firingOrder,FO_8_SBC,8);
#endif
}
/*================= UART (K42: EUSART2 RD0/RD1 ; Q84: EUSART1 RC6/RC7) =====*/
static void uart_puts(const char*s){
#if TARGET_K42
  while(*s){ while(!U2TXIF); U2TXB=*s++; }
#else
  while(*s){ while(!U1TXIF); U1TXB=*s++; }
#endif
}
static void uart_putf(const char*fmt,...){
  char b[160]; va_list ap; va_start(ap,fmt); vsnprintf(b,sizeof b,fmt,ap); va_end(ap); uart_puts(b);
}
static bool uart_getline(char*out,int n){
  static int i=0;
#if TARGET_K42
  while(U2RXIF){
    char c=U2RXB;
#else
  while(U1RXIF){
    char c=U1RXB;
#endif
    if(c=='\r'||c=='\n'){ if(i){ out=0; i=0; return true; } }
    else if(i<n-1){ out[i++]=c; }
  }
  return false;
}
/*================= Hardware init ======================*/
static void clock_init(void){
  T1CLK=0x01; T1CON=0;
  uint8_t ps=(T1_PRESCALE==1)?0:(T1_PRESCALE==2)?1:(T1_PRESCALE==4)?2:3;
  T1CONbits.CKPS=ps; TMR1=0; PIR4bits.TMR1IF=0; PIE4bits.TMR1IE=1; T1CONbits.ON=1;
  // CCP1 compare -> Timer1
  CCPTMRS0bits.C1TSEL=0; CCP1CON=0b1000; PIR4bits.CCP1IF=0; PIE4bits.CCP1IE=1;
}
static void pins_init(void){
  // Digital on used ports
  ANSELA=0; ANSELB=0; ANSELC=0; ANSELD=0; ANSELE=0;
  // Outputs
  inj_init_pins(); ign_init_pins(); LED_TRIS=0; LED_LAT=0;
  // Inputs: sensors (RBx layer A, RAx layer B)
  TRISB=0xFF; WPUB=0xFF;
  TRISA=0xFF; WPUA=0xFF;
  // IOC for PORTB (A-layer)
  IOCBF=0; IOCBN=0; IOCBP=0;
  for(uint8_t i=0;i<CYL_COUNT;i++){ IOCBN|=(1u<<i); IOCBP|=(1u<<i); }
#if MODE_DUAL
  // IOC for PORTA (B-layer)
  IOCAF=0; IOCAN=0; IOCAP=0;
  for(uint8_t i=0;i<CYL_COUNT;i++){ IOCAN|=(1u<<i); IOCAP|=(1u<<i); }
#endif
  PIR0bits.IOCIF=0; PIE0bits.IOCIE=1;
  // UART PPS
  INTCON0bits.GIE=0;
#if TARGET_K42
  PPSLOCK=0x55; PPSLOCK=0xAA; PPSLOCKbits.PPSLOCKED=0;
  RD0PPS = 0x12;      // EUSART2 TX -> RD0
  U2RXPPS= 0x19;      // RD1 -> EUSART2 RX
  PPSLOCK=0x55; PPSLOCK=0xAA; PPSLOCKbits.PPSLOCKED=1;
  U2BRG=(uint16_t)((FOSC_HZ/64/115200UL)-1);
  U2CON0=0b10010000; U2CON1=0b10000000; U2CON2=0;
#else
  PPSLOCK=0x55; PPSLOCK=0xAA; PPSLOCKbits.PPSLOCKED=0;
  RC6PPS=0x09;        // EUSART1 TX -> RC6
  U1RXPPS=0x17;       // RC7 -> EUSART1 RX
  PPSLOCK=0x55; PPSLOCK=0xAA; PPSLOCKbits.PPSLOCKED=1;
  U1BRG=(uint16_t)((FOSC_HZ/64/115200UL)-1);
  U1CON0=0b10010000; U1CON1=0b10000000; U1CON2=0;
#endif
  INTCON0bits.GIE=1;
}
/*================= CLI ===============================*/
static void print_help(void){
  uart_puts(
    "get | set ia <c> <deg> | set sa <c> <deg> | set pw <c> <ms>\r\n"
    "order <idx> <cyl> | preset <name>\r\n"
#if CYL_COUNT==6
    "  presets: i6_153624 | i6_142536\r\n"
#else
    "  presets: v8_sbc | v8_ls | v8_ford_ho\r\n"
#endif
    "save | load | defaults\r\n");
}
/*================= Edge handling =====================*/
static inline uint8_t first_set(uint8_t v){ for(uint8_t i=0;i<8;i++) if(v&(1u<<i)) return i; return 0xFF; }
static void on_edge(uint8_t sensorIdx, bool layerB){
  LED_LAT=!LED_LAT;
  // sector timing (adjacent edges)
  static uint16_t t_last=0;
  uint16_t tnow=TMR1, dt=tnow - t_last; t_last=tnow;
  if(dt==0) dt=1;
  double us_sector = dt * T1_TICK_US;
  us_per_cam_deg = (float)(us_sector / SECTOR_DEG);
  double cam_rev_us = us_sector * (360.0/SECTOR_DEG);
  if(cam_rev_us>1.0) rpm_cam = (uint16_t)(60000000.0 / cam_rev_us);
  // map sensor -> cylinder
  uint8_t cyl = firingOrder[sensorIdx];
  uint32_t t0 = now_us();
  // schedule injector
  uint32_t t_inj_on  = t0 + (uint32_t)(inj_deg[cyl] * us_per_cam_deg);
  uint32_t t_inj_off = t_inj_on + (uint32_t)(inj_ms[cyl] * 1000.0);
  q_push((event_t){t_inj_on,  EV_INJ_ON,  cyl});
  q_push((event_t){t_inj_off, EV_INJ_OFF, cyl});
  // schedule spark: layer A (single) or layer B (dual)
#if MODE_DUAL
  if(layerB)
#endif
  {
    uint32_t t_spk = t0 - (uint32_t)(spk_deg[cyl] * us_per_cam_deg); // BEFORE edge
    q_push((event_t){t_spk,      EV_SPK_ON,  cyl});
    q_push((event_t){t_spk+200,  EV_SPK_OFF, cyl}); // ~200us
  }
}
/*================= ISRs ==============================*/
void __interrupt(irq(TMR1), low_priority) TMR1_ISR(void){
  if(PIR4bits.TMR1IF){ PIR4bits.TMR1IF=0; t32+=0x00010000UL; }
}
void __interrupt(irq(IOC), low_priority) IOC_ISR(void){
  if(PIR0bits.IOCIF){
    uint8_t rb=PORTB; uint8_t mA=(~rb) & ((CYL_COUNT>=8)?0xFF:(uint8_t)((1u<<CYL_COUNT)-1u));
    if(mA){ uint8_t s=first_set(mA); if(s<CYL_COUNT) on_edge(s,false); }
#if MODE_DUAL
    uint8_t ra=PORTA; uint8_t mB=(~ra) & ((CYL_COUNT>=8)?0xFF:(uint8_t)((1u<<CYL_COUNT)-1u));
    if(mB){ uint8_t s=first_set(mB); if(s<CYL_COUNT) on_edge(s,true); }
    IOCAF=0;
#endif
    IOCBF=0; PIR0bits.IOCIF=0;
  }
}
void __interrupt(irq(CCP1), low_priority) CCP1_ISR(void){
  if(PIR4bits.CCP1IF){
    PIR4bits.CCP1IF=0;
    uint32_t t=now_us(); event_t e;
    while(q_peek(&e)){
      if((int32_t)(t - e.due) < 0) break;
      q_pop(&e);
      switch(e.type){
        case EV_INJ_ON:  INJ_SET(e.cyl,1); break;
        case EV_INJ_OFF: INJ_SET(e.cyl,0); break;
        case EV_SPK_ON:  IGN_SET(e.cyl,1); break;
        case EV_SPK_OFF: IGN_SET(e.cyl,0); break;
        default: break;
      }
    }
    arm_next_compare();
  }
}
/*================= Defaults & CLI loop ================*/
static void apply_defaults(void){
  // uniform starting maps
  for(uint8_t i=0;i<CYL_COUNT;i++){ inj_deg=10.0f; spk_deg=20.0f; inj_ms=3.0f; }
#if CYL_COUNT==6
  apply_preset("i6_153624");
#else
  apply_preset("v8_sbc");
#endif
}
static void banner(void){
  uart_puts("\r\n[Optical Distributor | ");
#if CYL_COUNT==6
  uart_puts("6-cyl]\r\n");
#else
  uart_puts("8-cyl]\r\n");
#endif
  uart_putf("tick=%.3fus  dual=%d  coil-per-cyl=%d\r\n", T1_TICK_US, (int)MODE_DUAL, (int)COIL_PER_CYL);
  print_help();
}
static void cli_tick(void){
  char line[96];
  if(!uart_getline(line,sizeof line)) return;
  if(!strncmp(line,"get",3)){
    uart_putf("rpm_cam=%u  us/deg=%.3f\r\n", rpm_cam, us_per_cam_deg);
    for(uint8_t c=0;c<CYL_COUNT;c++)
      uart_putf("cyl%u: ia=%.2f sa=%.2f pw=%.3f map=%u\r\n", c+1, (double)inj_deg[c], (double)spk_deg[c], (double)inj_ms[c], (unsigned)firingOrder[c]);
  } else if(!strncmp(line,"set ia ",7)){
    int c; float v; if(sscanf(line+7,"%d %f",&c,&v)==2 && c>=1 && c<=CYL_COUNT){ inj_deg[c-1]=v; uart_puts("OK\r\n"); }
  } else if(!strncmp(line,"set sa ",7)){
    int c; float v; if(sscanf(line+7,"%d %f",&c,&v)==2 && c>=1 && c<=CYL_COUNT){ spk_deg[c-1]=v; uart_puts("OK\r\n"); }
  } else if(!strncmp(line,"set pw ",7)){
    int c; float v; if(sscanf(line+7,"%d %f",&c,&v)==2 && c>=1 && c<=CYL_COUNT){ inj_ms[c-1]=v; uart_puts("OK\r\n"); }
  } else if(!strncmp(line,"order ",6)){
    int idx, cyl; if(sscanf(line+6,"%d %d",&idx,&cyl)==2 && idx>=1 && idx<=CYL_COUNT && cyl>=1 && cyl<=CYL_COUNT){
      firingOrder[idx-1]=(uint8_t)(cyl-1); uart_puts("OK\r\n");
    } else print_help();
  } else if(!strncmp(line,"preset ",7)){
    apply_preset(line+7); uart_puts("OK preset\r\n");
  } else if(!strcmp(line,"save")){
    cfg_save(); uart_puts("saved\r\n");
  } else if(!strcmp(line,"load")){
    uart_puts(cfg_load()?"loaded\r\n":"load failed\r\n");
  } else if(!strcmp(line,"defaults")){
    apply_defaults(); uart_puts("defaults applied\r\n");
  } else {
    print_help();
  }
}
/*================= Main ==============================*/
static void init_uart_banner(void){
  // make sure UART is already up from pins_init()
  banner();
}
void main(void){
  clock_init(); pins_init();
  apply_defaults(); (void)cfg_load(); // load if valid
  // interrupts on
  INTCON0bits.GIEH=1; INTCON0bits.GIEL=1;
  init_uart_banner();
  for(;;){ cli_tick(); arm_next_compare(); }
}
How to build & wire (quick)
In the file, set CYL_COUNT to 6 (or 8), decide tick (FOSC_HZ=32MHz for 1.000 µs or 64MHz for 0.5 µs), and choose MODE_DUAL (usually 0 for single-layer).
Flash to PIC18F47K42 (Curiosity Nano) or 57Q84/43.
Sensors: RB0..RB(N-1), active-LOW. (If dual: RA0..RA(N-1) for layer-B).
Injectors: RC0..RC(N-1) → your MOSFET drivers.
Ignition: RD0..RD(N-1) to your coil drivers (or set COIL_PER_CYL=0 to use RE1 single coil).
Open serial @ 115200. Type:
get
preset i6_153624      // or: v8_sbc | v8_ls | v8_ford_ho | i6_142536
set ia 1 8.0
set sa 1 18.0
set pw 1 2.5
save
============
Spin the shaft; watch per-cyl injector and ignition pulses align with your degrees across RPM.
Step-by-step: what changed & why (so you can replicate)
Generalized N-cyl math: sector = 360/N cam degrees. One edge-to-edge interval ⇒ us_per_cam_deg = dt_us / (360/N).
Per-cyl scheduling: on each edge we map sensorIdx → cylinder via firingOrder[], and enqueue INJ_ON/OFF and SPK_ON/OFF at absolute times computed from angles and PW.
Coil-per-cyl: ignition outputs are a simple IGN_SET(cyl,on) to RDx, so each cylinder can have its own CDI/IGBT (cleaner dwell/energy control later).
EEPROM profile: we snapshot firingOrder, inj_deg, spk_deg, inj_ms with a CRC16 so you can power-cycle and keep maps.
Presets: common firing orders are encoded and applied to firingOrder[] so you don’t have to type them in.
Dual-stack option: if you set MODE_DUAL=1, the spark edges are sourced from PORTA (layer-B). For 6/8-cyl you’ll typically run single-layer (layer-A).
7) Bench validation (repeatable workflow)
Static sensor check
Block each slot with a card; verify the corresponding RBx reads active-LOW.
Spin test (drill on the shaft coupler, ~500–3000 rpm cam):
Confirm rpm_cam monotonic; us/deg ≈ dt_us / 60° (6-cyl) or /45° (8-cyl).
Scope/LA
Trigger on RB0 edge. Measure D(RB0→RC0); it should equal ia[1] in degrees × us_per_deg.
Measure ignition pulse start vs. edge; confirm equals sa[cyl].
Noise testing
Tap a small ignition coil nearby; confirm no false triggering (add LM393 or RC where needed).
Save profile (save) and power cycle; load if needed.
8) Automotive signal integrity
Comparators: Square the phototransistor with LM393 near the ECU; route open-collector outputs into RBx with 10–22 k pull-ups.
Filters: 100 nF to ground at each input pin; short return to sensor ground.
Harness: shielded twisted-pair for each sensor; separate logic ground from coil/CDI grounds; single star return.
Protection: TVS on 12 V supply; flybacks on injectors; opto isolation for CDI trigger.
9) Dual-stack vs. single-stack (what the angles mean)
Single-stack (MODE_DUAL=0): one layer does both maps. Treat ia as ATDC after that cylinder’s reference edge; treat sa as BTDC before the next TDC (see Patch B).
Dual-stack (MODE_DUAL=1): you can dedicate Layer-B to spark phase (e.g., an earlier reference). With a properly phased B-disc, sa can be scheduled strictly after the B-edge (positive “before-TDC” with B leading).