Source file: /~heha/ewa/Reluktanzmotor/maweig-Motor-190927.zip/main.cpp

/*	High-Speed-Motorsteuerung für 2 Motoren im Maschinensatz.
	Davon 1 Reluktanzmotor.
Kodierung: UTF-8 _mit_ BOM, Tabweite: 8, Einrückung: 2
Nur _mit_ BOM transkodiert der Compiler L-Strings korrekt in UTF-16.
Controller:	TMS320F28379D (1 CPU pro Motor)
Board:		LaunchPad + externe Mess- und Leistungselektronik
Autor:		Henrik Haftmann, für Maximilian Weigelt (Login: maweig)

PROBLEME:
* SDFM ungetestet
* Wacklige Programmstruktur, ungeklärt warum es bei manchen Kompilationen
  (gestern) hängt; kein Interrupt von EPWM11.

==== Controller-Peripherie und zugeordnete CPU (1 oder 2) ====
  Interrupts
	1		1,2	(war mal: Resolver)
	3		1,2	MotorControl
	4		1	COM-Port über FT2232H
	5		1,2	(COM-Port über Pfostenleiste und Optokoppler)
	6		1,2	(war mal: Endat und BissC)
  PWM (Pulsweitenmodulator)
	ePWM1-3		1	PWMs für 3 Phasen
	ePWM4-6		2	PWMs für 3 Phasen
	ePWM7			frei (keine Ausgänge verfügbar)
	ePWM8+9		1	Taktgenerator (20 MHz) für ΣΔ-Stromsensoren AMC1204
	ePWM10			frei (beide Ausgänge verfügbar)
	ePWM11		1	Motorsteuer-ISR (10 kHz) + ΣΔ-Synchronisation
	ePWM12			frei (nur Ausgang A verfügbar)
  CAP (Capture/Compare)		(ohne Interesse)

  QEP (Quadratur-Encoder)
	eQEP1		1	Encoder für Motor 1
	eQEP2		2	Encoder für Motor 2 (falls Kupplung des Maschinensatzes versagt)
	eQEP3			(nicht verfügbar)

  SDFM (ΣΔ-Filter-Modul)
	ΣΔ1_CD1		1	Strom 1 U AMC1204
	ΣΔ1_CD2			Strom 1 V
	ΣΔ1_CD3			(nicht verfügbar)
	ΣΔ1_CD4			(nicht verfügbar)
	ΣΔ2_CD1		2	Strom 2 U
	ΣΔ2_CD2			Strom 2 V
	ΣΔ2_CD3			Zwischenkreisspannung oder Strom 2 W
	ΣΔ2_CD4			(nicht verfügbar)

  SPI (Serial Peripheral Interface, Symbol ⇔)
	SPI_A			(beißt sich mit ΣΔ2_CD3)
	SPI_B		1	externer ΣΔ-Dezimierer AMC1210
	SPI_C			(nur auf J9 verfügbar)
  SCI (Asynchron-serielle Schnittstelle)
	SCI_A		1	via FT2232H
	SCI_B		1	(ungenutzt / Debug CPU1)
	SCI_C		2	(ungenutzt / Debug CPU2)
	SCI_D			(ohne Interesse)
  I²C (Inter-IC-Bus)		(ohne Interesse)
  BSP (Buffered Serial Port)	(ohne Interesse)
  CAN (Controller Area Network)	(ohne Interesse)
  USB (Useless Serial Bus)	(nicht verfügbar, nur 12 Mbit/s)
  uPP (Parallelport)		(nicht verfügbar)
  EMIF (External Memory)	(nicht verfügbar + ohne Interesse)

  ADC (Analog-Digital-Wandler) und CMPSS (Komparatoren)
	ADC_A	A13	1	Temperatursensor
		A1		cos 2 (ohne SINCOS 2: D/A-Wandler)
		A2/C1+		LemU 1
		A3		UfbU 1
		A4/C2+		LemU 2
		A5		UfbU 2
	ADC_B	14/C4+	1	sin 1 (ADCIN14) (ohne SINCOS 1: Zwischenkreisspannung?)
		15		sin 2 (ADCIN15) (ohne SINCOS 2: Drehzahl/-Momentvorgabe)
		B2/C3+		LemV 1
		B3		UfbV 1
		B4		LemV 2 (kein Komparator!)
		B5		UfbV 2
	ADC_C	??		frei
		A0/12	1	cos 1 (ohne SINCOS 1: D/A-Wandler)
		C2/C6+		LemW 1
		C3		UfbW 1
		C4/C5+		LemW 2
		C5		UfbW 2
	ADC_D	D4-D5		frei (SMA-Buchsen + Instrumentationsverstärker)
		D0/C7+ - D1	frei (J21-1) - (J21-3)
		D2/C8+ - D3	frei (J21-5) - (J21-7)
	Alle Hi-Referenzen = 2,5 V, alle Lo-Referenzen = 00
	  Das heißt alle negativ werdenden Analogspannungen müssen
	  auf halbe Referenzspannung angehoben werden (Offset).
	  16 Bit geht nur differenziell.
	  Umschaltung nicht innerhalb eines Bursts möglich.
	  Daher läuft ADC_D asynchron zu den drei anderen A/D-Wandlern.
	Ströme werden zuletzt gemessen, um möglichst aktuell zu sein.

  DAC (Digital-Analog-Wandler)
	DacA			(beißt sich mit AdcA0)
	DacB			(beißt sich mit AdcA1)
	DacC			(nicht verfügbar)

  sonstiges
	rote LED	1	GPIO34
	blaue LED	1	GPIO31
	grüne LED	leuchtet immer (3P3)
	COMx (FT2232H)	1	GPIO42 (TxD), GPIO43 (RxD)
	CAN an J12	1	GPIO12 (Tx), GPIO17 (Rx)
  Die LEDs auf der FT232-Seite können nicht vom Controller aus gesteuert werden.

==== Launchpad-Pins ====
(oberes Stiftleistenpaar):
╔═══════╤═══════╦═══════╤═══════╗	╔═══════╤═══════╦═══════╤═══════╗
║	│    3P3║5P	│	║	║PWM1A	│     P0║00	│	║
║	│    P32║00	│	║	║PWM1B	│     P1║P61	│ΣΔ2_C3	║
║(RxD)b	│    P19║Adc14	│sin	║	║PWM2A	│     P2║P123	│ΣΔ1_C1	║
║(TxD)b	│    P18║AdcC3	│UfbW	║	║PWM2B	│     P3║P122	│ΣΔ1_D1	║
║	│    P67║AdcB3	│UfbV	║	║PWM3A	│     P4║RST	│	║
║	│   P111║AdcA3	│UfbU	║	║PWM3B	│     P5║P58	│	║
║ΣΔ2_D3	│    P60║AdcC2	│LemW	║	║tripI	│    P24║P59	│	║
║	│    P22║AdcB2	│LemV	║	║ΣΔCout	│    P16║P124	│ΣΔ1_C2	║
║	│   P105║AdcA2	│LemU	║	║PwmDAC1│ (P159)║P125	│ΣΔ1_D2	║
║	│   P104║AdcA0	│cos	║	║PwmDAC2│ (P160)║P29	│	║
╚═══════╧═══════╩═══════╧═══════╝	╚═══════╧═══════╩═══════╧═══════╝

(unteres Stiftleistenpaar):
╔═══════╤═══════╦═══════╤═══════╗	╔═══════╤═══════╦═══════╤═══════╗
║	│    3P3║5P	│	║	║PWM4A	│     P6║00	│	║
║	│    P95║00	│	║	║PWM4B	│     P7║P66	│⇔CS	║
║(RxD)c	│   P139║Adc15	│sin	║	║PWM5A	│     P8║P131	│ΣΔ2_C1	║
║(TxD)c	│    P56║AdcC5	│UfbW	║	║PWM5B	│     P9║P130	│ΣΔ2_D1	║
║	│    P97║AdcB5	│UfbV	║	║PWM6A	│    P10║RST	│	║
║	│    P94║AdcA5	│UfbU	║	║PWM6B	│    P11║P63	│⇔MOSI	║
║⇔SCK	│    P65║AdcC4	│LemW	║	║tripI	│    P14║P64	│⇔MISO	║
║	│    P52║AdcB4	│LemV	║	║ΣΔCout	│    P15║P26	│ΣΔ2_C2	║
║	│    P41║AdcA4	│LemU	║	║PwmDAC3│ (P161)║P27	│ΣΔ2_D2	║
║	│    P40║AdcA1	│cos	║	║PwmDAC4│ (P162)║P25	│	║
╚═══════╧═══════╩═══════╧═══════╝	╚═══════╧═══════╩═══════╧═══════╝

(Encoder 5V:)	QEP_B			QEP_A
		╔═══════╤═══════╗	╔═══════╤═══════╗
		║A	│P54	║	║A	│P20	║
		║B	│P55	║	║B	│P21	║
		║I	│P57	║	║I	│P99	║
		║5P	│	║	║5P	│	║
		║00	│	║	║00	│	║
		╚═══════╧═══════╝	╚═══════╧═══════╝

Verschaltung:
P0 = PWM1A -> Phase A High-Side-Treiber, Low = aktiv (treibt Zwischenkreisspannung)
P1 = PWM1B -> Phase A  Low-Side-Treiber, Low = aktiv (treibt 0 V)
P2 = PWM2A -> Phase B High-Side-Treiber, Low = aktiv (treibt Zwischenkreisspannung)
P3 = PWM2B -> Phase B  Low-Side-Treiber, Low = aktiv (treibt 0 V)
P4 = PWM3A -> Phase C High-Side-Treiber, Low = aktiv (treibt Zwischenkreisspannung)
P5 = PWM3B -> Phase C  Low-Side-Treiber, Low = aktiv (treibt 0 V)
…TODO
*/

#include "Settings.h"
//#include <cstdio>	// sprintf (serielle Schnittstelle testen)
#include <cstring>	// strchr, memset
//#include <cstdlib>	// div_t
#include "regdef2.h"	// ADC_RESULT_REGSA

// Define the base quantites
namespace nsBASE{
  //const float VOLTAGE = 236.14;	// Base peak phase voltage (volt), Vdc/sqrt(3)
  const float SHUNT_CURRENT	=9.95;	// Base peak phase current (amp), Max. measurable peak curr.
  const float LEM_CURRENT	=12.0;	//  ----- do -----
  //const float TORQUE =		// Base torque (N.m)
  //const float FLUX =			// Base flux linkage (volt.sec/rad)
}

Comport com0(SciaRegs);

// ****************************************************************************
// Variables for current measurement
// ****************************************************************************

static const float curLimit = 8.0;

// LEM    1.0pu current ==> 12.0A -> 2048 counts ==> 8A -> 1365
// SHUNT  1.0pu current ==> 9.95A -> 2048 counts ==> 8A -> 1647
inline int LEM(float A)     {return 2048*A/nsBASE::LEM_CURRENT;}
inline int SHUNT(float A)   {return 2048*A/nsBASE::SHUNT_CURRENT;}

// CMPSS parameters for Overcurrent Protection
static const Uint16 
	clkPrescale = 20,
	sampwin     = 30,
	thresh      = 18;
static const Uint16
	LEM_curHi   = 2048 + LEM(curLimit),
	LEM_curLo   = 2048 - LEM(curLimit),
	SHUNT_curHi = 2048 + SHUNT(curLimit),
	SHUNT_curLo = 2048 - SHUNT(curLimit);

// ****************************************************************************
// Flag variables
// ****************************************************************************
MONITOR bool TripFlag;		// PWM trip status
MONITOR bool TripFlagClear;	// PWM trip clear (from debugger)

//=============================================================================
//	A - TASK (executed every 50 µs ≙ 20 kHz = F_CPU/10000)
//=============================================================================

// Setup OCP limits and digital filter parameters of CMPSS
static void CMPSS_DIG_FILTER(volatile CMPSS_REGS&regs, Uint16 curHi, Uint16 curLo) {
	// comparator references
  regs.DACHVALS.bit.DACVAL = curHi;	// positive max current limit
  regs.DACLVALS.bit.DACVAL = curLo;	// negative max current limit

	// digital filter settings - HIGH side
  regs.CTRIPHFILCLKCTL.bit.CLKPRESCALE = clkPrescale;	// set time between samples, max : 1023
  regs.CTRIPHFILCTL.bit.SAMPWIN        = sampwin;	// # of samples in window, max : 31
  regs.CTRIPHFILCTL.bit.THRESH         = thresh;	// recommended : thresh > sampwin/2

	// digital filter settings - LOW side
  regs.CTRIPLFILCLKCTL.bit.CLKPRESCALE = clkPrescale;	// Max count of 1023 */
  regs.CTRIPLFILCTL.bit.SAMPWIN        = sampwin;	// # of samples in window, max : 31
  regs.CTRIPLFILCTL.bit.THRESH         = thresh;	// recommended : thresh > sampwin/2
}

static void A() {
	// *******************************************************
	// Current limit setting / tuning in Debug environment
	// *******************************************************
  if (BUILDLEVEL!=LEVEL1) {
    EALLOW;
//    LEM_curHi = 2048 + LEM(curLimit);
//    LEM_curLo = 2048 - LEM(curLimit);
//    SHUNT_curHi = 2048 + SHUNT(curLimit);
//    SHUNT_curLo = 2048 - SHUNT(curLimit);

    if (SENSES & bit(LEM_CURRENT_SENSE)) {
      CMPSS_DIG_FILTER(Cmpss1Regs, LEM_curHi, LEM_curLo);      // LEM - V
      CMPSS_DIG_FILTER(Cmpss3Regs, LEM_curHi, LEM_curLo);      // LEM - W
    }
    if (SENSES & bit(SHUNT_CURRENT_SENSE)) {
      CMPSS_DIG_FILTER(Cmpss2Regs, SHUNT_curHi, SHUNT_curLo);  // SHUNT - V
      CMPSS_DIG_FILTER(Cmpss6Regs, SHUNT_curHi, SHUNT_curLo);  // SHUNT - U
    }
    EDIS;
	// Check for PWM trip due to over current or over speed
    if (!TripFlag) TripFlag = EPwm1Regs.TZFLG.all
     || EPwm2Regs.TZFLG.all
     || EPwm3Regs.TZFLG.all;	// Trip on DMC (halt and IPM fault trip )
  }

  if (TripFlag) {
	// if any EPwm's OST is set, force OST on all three to DISABLE inverter
    EALLOW;
    EPwm1Regs.TZFRC.all = 1<<2;
    EPwm2Regs.TZFRC.all = 1<<2;
    EPwm3Regs.TZFRC.all = 1<<2;
    EDIS;
    RunMotor = false;
  }
	// If clear cmd received, reset PWM trip
  if (TripFlagClear) {
    TripFlag = false;
    TripFlagClear = false;
    EALLOW;
		// clear OST and DCAEVT1 flags
    EPwm1Regs.TZCLR.all = EPwm1Regs.TZFLG.all;
    EPwm2Regs.TZCLR.all = EPwm2Regs.TZFLG.all;
    EPwm3Regs.TZCLR.all = EPwm3Regs.TZFLG.all;
		// clear LLATCH and HLATCH - (not in TRIP gen path)
    Cmpss1Regs.COMPSTSCLR.all = 1<<1 | 1<<9;
    Cmpss3Regs.COMPSTSCLR.all = 1<<1 | 1<<9;
    Cmpss2Regs.COMPSTSCLR.all = 1<<1 | 1<<9;
    Cmpss6Regs.COMPSTSCLR.all = 1<<1 | 1<<9;
    EDIS;
  }
}

//=============================================================================
//	B - TASK (executed every 200 µs ≙ 5 kHz = F_CPU/40000)
//=============================================================================
static void outAdcValues(ADC_RESULT_REGSA&regs) {
  for (int i=0; i<6; i++) {
    com0.printf(L"%6d",regs.RESULT[i]);
  }
  com0.send("\r\n");
}
static void outAdcValues() {
  for (int i=0; i<3; i++) outAdcValues(AdcResultRegsA[i]);	// Adca bis Adcc
}
static unsigned bitmapdata[(160>>4)*50];	// erst mal nicht mit new/delete, 1 kilobyte
static struct Bitmap{
  unsigned*image;
  int w,h;
  void setpixel(int,int);
  bool getpixel(int,int);
  void clear() {memset(image,0,(w>>4)*h);}
  void line(int,int,int,int);
  void outbraille(int zero_y);
}bmp={bitmapdata,160,50};

void Bitmap::setpixel(int x, int y) {
 if ((unsigned)x>=(unsigned)w) return;
 if ((unsigned)y>=(unsigned)h) return;
 image[(w>>4)*y+(x>>4)] |= 1U<<(x&0xF);	// MSB ist hier rechts!
}
bool Bitmap::getpixel(int x, int y) {
 if ((unsigned)x>=(unsigned)w) return false;
 if ((unsigned)y>=(unsigned)h) return false;
 return !!(image[(w>>4)*y+(x>>4)] & (1U<<(x&0xF)));
}
void Bitmap::line(int x0,int y0,int x1,int y1) {	// aus Wikipedia
  int dx =  abs(x1-x0), sx = x0<x1 ? 1 : -1;
  int dy = -abs(y1-y0), sy = y0<y1 ? 1 : -1;
  int err = dx+dy; /* error value e_xy */
  while(x0!=x1 || y0!=y1) {	// zeichnet letztes Pixel nicht mit
    setpixel(x0,y0);
    int e2 = 2*err;
    if (e2 > dy) { err += dy; x0 += sx; }
    if (e2 < dx) { err += dx; y0 += sy; }
  }
}
void Bitmap::outbraille(int yz) {	// Kursor steht links oben; Ausgabe der Bitmap
  for (int y=0; y<h; y+=4) {
    for (int x=0; x<w; x+=2) {	// Braille-Zeichen = U+2800,	Bits:	0 3
      wchar_t c=0x2800, mask=1;					//	1 4
      for (int xx=0; xx<2; xx++) {				//	2 5
	for (int yy=0; yy<3; yy++) {				//	6 7
	  if (getpixel(x+xx,y+yy)) c|=mask;
	  mask<<=1;
	}
      }
      for (int xx=0; xx<2; xx++) {
	if (getpixel(x+xx,y+3)) c|=mask;
	mask<<=1;
      }
      if (c==0x2800) {
	c=' ';			// Leerzeichen fressen weniger serielle Bandbreite
        if (y==yz) c=0x2500/*L'─'*/;	// Leerzeichen durch horizontale Linie ersetzen
      }
      com0.send(c);
    }
    com0.send("\r\n");
  }
}

static void outDiagram() {
  bmp.clear();
  static int wackel=40;
  bmp.line(10,5,30,wackel);
  bmp.line(30,wackel,50,30);
  bmp.line(50,30,70,-5);
  bmp.line(70,-5,160,25);
  bmp.line(82,30,99,30);	// 2 waagerechte Linien zum Test
  bmp.line(82,33,99,33);
  bmp.line(100,0,100,50);	// 1 senkrechte Linie
  bmp.outbraille(24);
  if (++wackel==bmp.h) wackel=0;
}

static void B() { 	// Toggle GPIO-34
#ifdef CPU1
  static int LedCnt1;
  if (++LedCnt1==200) {	// 200 µs × 200 = 40 ms ≙ 25 Hz
    LedCnt1 = 0;
    GpioDataRegs.GPBTOGGLE.bit.GPIO34 = 1;  // LED blinking (12.5 Hz)
  }
  static int terminaltick;
  if (++terminaltick==1000) {	// 200 ms
    terminaltick = 0;
    float T = myGetTemperatureC(AdcaResultRegs.ADCRESULT0);
    com0.printf(L"\rT = \e[1m%,1f\e[m °C ",T);
    com0.send("\e[s" "\e[?25l" "\r\n");	// Cursor merken und 1 Zeile runter
    outAdcValues();
    outDiagram();
    com0.send("\e[?25h" "\e[u");	// Cursor zurück
  }
#endif
}

// THE BACKGROUND TASK: On overflow of each of the three CPU timer, do something.
// Otherwise, sleeping CPU would be nice to save power.
static void loop() {
  if (CpuTimer0Regs.TCR.bit.TIF==1) {
    CpuTimer0Regs.TCR.bit.TIF = 1;	// clear flag
    A();
  }
  if (CpuTimer1Regs.TCR.bit.TIF==1) {
    CpuTimer1Regs.TCR.bit.TIF = 1;	// clear flag
    B();
  }
}

//  DMC Protection Against Over Current Protection
static void cmpssConfig(volatile CMPSS_REGS&regs, int16 Hi, int16 Lo) {
	// Set up COMPCTL register
  regs.COMPCTL.bit.COMPDACE    = 1;	// Enable CMPSS
  regs.COMPCTL.bit.COMPLSOURCE = 0;	// NEG signal from DAC for COMP-L
  regs.COMPCTL.bit.COMPHSOURCE = 0;	// NEG signal from DAC for COMP-H
  regs.COMPCTL.bit.COMPHINV    = 0;	// COMP-H output is NOT inverted
  regs.COMPCTL.bit.COMPLINV    = 1;	// COMP-L output is inverted
  regs.COMPCTL.bit.ASYNCHEN    = 0;	// Disable aynch COMP-H ouput
  regs.COMPCTL.bit.ASYNCLEN    = 0;	// Disable aynch COMP-L ouput
  regs.COMPCTL.bit.CTRIPHSEL    = 2;	// Dig filter output ==> CTRIPH
  regs.COMPCTL.bit.CTRIPOUTHSEL = 2;	// Dig filter output ==> CTRIPOUTH
  regs.COMPCTL.bit.CTRIPLSEL    = 2;	// Dig filter output ==> CTRIPL
  regs.COMPCTL.bit.CTRIPOUTLSEL = 2;	// Dig filter output ==> CTRIPOUTL
	// Set up COMPHYSCTL register
  regs.COMPHYSCTL.bit.COMPHYS   = 2;	// COMP hysteresis set to 2x typical value
	// set up COMPDACCTL register
  regs.COMPDACCTL.bit.SELREF    = 0;	// VDDA is REF for CMPSS DACs
  regs.COMPDACCTL.bit.SWLOADSEL = 0;	// DAC updated on sysclock
  regs.COMPDACCTL.bit.DACSOURCE = 0;	// Ramp bypassed
	// Load DACs - High and Low
  regs.DACHVALS.bit.DACVAL = Hi;	// Set DAC-H to allowed MAX +ve current
  regs.DACLVALS.bit.DACVAL = Lo;	// Set DAC-L to allowed MAX -ve current
	// digital filter settings - HIGH side
  regs.CTRIPHFILCLKCTL.bit.CLKPRESCALE = clkPrescale;	// set time between samples, max : 1023
  regs.CTRIPHFILCTL.bit.SAMPWIN        = sampwin;	// # of samples in window, max : 31
  regs.CTRIPHFILCTL.bit.THRESH         = thresh;	// recommended : thresh > sampwin/2
  regs.CTRIPHFILCTL.bit.FILINIT        = 1;		// Init samples to filter input value
	// digital filter settings - LOW side
  regs.CTRIPLFILCLKCTL.bit.CLKPRESCALE = clkPrescale;	// set time between samples, max : 1023
  regs.CTRIPLFILCTL.bit.SAMPWIN        = sampwin;	// # of samples in window, max : 31
  regs.CTRIPLFILCTL.bit.THRESH         = thresh;	// recommended : thresh > sampwin/2
  regs.CTRIPLFILCTL.bit.FILINIT        = 1;		// Init samples to filter input value
	// Clear the status register for latched comparator events
  regs.COMPSTSCLR.bit.HLATCHCLR = 1;
  regs.COMPSTSCLR.bit.LLATCHCLR = 1;
}

static void InitPwmTrip(volatile EPWM_REGS&regs,Uint16 tzsel) {
  regs.DCTRIPSEL.all = 3<<0;		// Digital Comparator A High Input kommt von TripIn 4
  regs.TZDCSEL.all = TZ_DCAH_HI<<0;	// Digital Comparator A Event 1 Select: DCAH==H && DCAL=x
  regs.DCACTL.all = DC_EVT_ASYNC<<1;	// asynchron
  regs.TZSEL.all = tzsel;
  regs.TZCTL.all= TZ_FORCE_HI<<0 | TZ_FORCE_HI<<2;	// Ausgang A und B auf HIGH wenn One-Shot-Trip kommt
  regs.TZCLR.all = 1<<2 | 1<<3;		// Clear any spurious OV trip
}

static void HVDMC_Protection() {
// Digitale Eingänge für das Abschalten der PWM bereitstellen
  GpioCtrlRegs.GPAINV.all |=  bit(14)|bit(24);	// High = PWM Stop
  GpioCtrlRegs.GPAPUD.all &=~(bit(14)|bit(24));	// offener Eingang = PWM Stop
  InputXbarRegs.INPUT1SELECT = 24;	// Select GPIO24 as INPUTXBAR1 = !TZ1 for tripping PWM1..3
  InputXbarRegs.INPUT2SELECT = 14;	// Select GPIO14 as INPUTXBAR2 = !TZ2 for tripping PWM4..6
  if (BUILDLEVEL!=LEVEL1) {
	//Clearing the Fault(active low), GPIO41,
	// Configure as Output
//  GpioCtrlRegs.GPBPUD.bit.GPIO41  = 1; // disable pull ups
//  GpioCtrlRegs.GPBMUX1.bit.GPIO41 = 0; // choose GPIO for mux option
    GpioCtrlRegs.GPBDIR.bit.GPIO41  = 1; // set as output
    GpioDataRegs.GPBSET.bit.GPIO41  = 1;

	// LEM Current phase V(ADC A2, COMP1) and W(ADC B2, COMP3), High Low Compare event trips
    if (SENSES & bit(LEM_CURRENT_SENSE)) {
//  LEM_curHi = 2048 + LEM(curLimit);
//  LEM_curLo = 2048 - LEM(curLimit);
      cmpssConfig(Cmpss1Regs, LEM_curHi, LEM_curLo);  //Enable CMPSS1 - LEM V
      cmpssConfig(Cmpss3Regs, LEM_curHi, LEM_curLo);  //Enable CMPSS3 - LEM W
    }

    if (SENSES & bit(SHUNT_CURRENT_SENSE)) {
	// Shunt Current phase V(ADC A4, COMP2) and W(ADC C2, COMP6), High Low Compare event trips
//    SHUNT_curHi = 2048 + SHUNT(curLimit);
//    SHUNT_curLo = 2048 - SHUNT(curLimit);
      cmpssConfig(Cmpss2Regs, SHUNT_curHi, SHUNT_curLo);  //Enable CMPSS2 - Shunt V
      cmpssConfig(Cmpss6Regs, SHUNT_curHi, SHUNT_curLo);  //Enable CMPSS6 - Shunt U
    }

	// Configure TRIP 4 to OR the High and Low trips from both comparator 1 & 3
    EPwmXbarRegs.TRIP4MUX0TO15CFG.all  = bit(0) | bit(4) | bit(2) | bit(10) | bit(3);
    EPwmXbarRegs.TRIP4MUX16TO31CFG.all = 0;
	// Enable Muxes for ored input of CMPSS1H and 1L, i.e. .1 mux for Mux0
//  MUX0  = 1;  //cmpss1 - tripH or tripL
//  MUX4  = 1;  //cmpss3 - tripH or tripL
//  MUX2  = 1;  //cmpss2 - tripH or tripL
//  MUX10 = 1;  //cmpss6 - tripH or tripL
//  MUX3  = 1;  //inputxbar2 trip

	// Enable Mux 0 OR Mux 4 to generate TRIP4
    EPwmXbarRegs.TRIP4MUXENABLE.all = bit(0) | bit(4) | bit(2) | bit(10) | bit(1);
  }
  InitPwmTrip(EPwm1Regs,1<<14 | 1<<0 | 1<<5);	// Bit 14: DCAEVT1 = Quelle für Dauer-Aus
  InitPwmTrip(EPwm2Regs,1<<14 | 1<<0 | 1<<5);	// Bit 8: TZ1 (GPIO24) = Quelle für Dauer-Aus
  InitPwmTrip(EPwm3Regs,1<<14 | 1<<0 | 1<<5);	// Bit 5: TZ6 = Quelle für Zyklus-Aus
  InitPwmTrip(EPwm4Regs,1<<14 | 1<<1 | 1<<5);	// Bit 14: DCAEVT1 = Quelle für Dauer-Aus
  InitPwmTrip(EPwm5Regs,1<<14 | 1<<1 | 1<<5);	// Bit 9: TZ2 (GPIO14) = Quelle für Dauer-Aus
  InitPwmTrip(EPwm6Regs,1<<14 | 1<<1 | 1<<5);	// Bit 5: TZ6 = Quelle für Zyklus-Aus
	// What do we want the OST/CBC events to do?
	// TZA events can force EPWMxA
	// TZB events can force EPWMxB
}

void configPwm(volatile EPWM_REGS&regs, Uint16 period, Uint16 slave_phase) {
	// Time Base SubModule Registers
  TBCTL_REG tbctl = {0};
  tbctl.bit.CTRMODE = TB_COUNT_UP;	// 00: Aufwärts
  if (slave_phase) tbctl.bit.PHSEN = TB_ENABLE;	// 1: Phasensynchronisierung erlauben
  else tbctl.bit.SYNCOSEL = TB_CTR_ZERO;	// 01: sync "down-stream" when counter == 0
  tbctl.bit.FREE_SOFT = 0b10;			// 1x: Continue running at emulation events
  regs.TBCTL.all = tbctl.all;
  regs.TBPRD = period-1;	// PWM frequency = 1 / period
	// Action Qualifier SubModule Registers
  AQCTLA_REG aqctla = {0};
  aqctla.bit.ZRO = AQ_SET;	// setzen bei Null
  aqctla.bit.CAU = AQ_CLEAR;	// löschen bei Erreichen des Compare-Wertes -> Normale PWM
  regs.AQCTLA.all = aqctla.all;
  regs.TBPHS.bit.TBPHS = slave_phase;
}

static void configDac(volatile DAC_REGS&regs) {
  regs.DACCTL.bit.DACREFSEL  = 1;	// Referenzspannung
  regs.DACOUTEN.bit.DACOUTEN = 1;	//Enable DAC output
  regs.DACVALS.bit.DACVALS   = 1024;
}

static void configDac() {	// SETUP DACS
  configDac(DacaRegs);
  DacaRegs.DACCTL.bit.LOADMODE = 1;	// enable value change only on sync signal
  DacaRegs.DACCTL.bit.SYNCSEL  = 0;	// sync from pwm 1
  configDac(DacbRegs);
  configDac(DaccRegs);
}

static void calOffsets() {
  Currentsense::resetADCoffset();
  Currentsense::resetSDFMoffset();
  for (int Counter=0; Counter<20000; ) {
    if (EPwm11Regs.ETFLG.bit.INT==1) {
      EPwm11Regs.ETCLR.bit.INT=1;
      if (++Counter>1000) {
        const float K2 = 0.001999;	// Offset filter coefficient: T/(T+0.05);
        Currentsense::integrateSDFMoffset(K2);
        Currentsense::integrateADCoffset(K2);
      }
    }
  }
  Currentsense::setADCoffsetregs();
}

//*****************************************************************************
void main() {
#ifdef _FLASH
// Copy time critical code and Flash setup code to RAM
// The  RamfuncsLoadStart, RamfuncsLoadEnd, and RamfuncsRunStart
// symbols are created by the linker. Refer to the linker files.
  memcpy(&RamfuncsRunStart, &RamfuncsLoadStart, (Uint32)&RamfuncsLoadSize);
#endif
#ifdef CPU1	// muss vorher geschehen!
  EALLOW;
  CPUSEL0_REG cpusel0 = {0};
  cpusel0.bit.EPWM6 = cpusel0.bit.EPWM5 = cpusel0.bit.EPWM4 = 1;
  DevCfgRegs.CPUSEL0.all = cpusel0.all;
  DevCfgRegs.CPUSEL2.bit.EQEP2 = 1;
  DevCfgRegs.CPUSEL4.bit.SD2 = 1;
  DevCfgRegs.CPUSEL5.bit.SCI_C = 1;
  EDIS;
#endif
	// PLL, WatchDog, all(!) Peripheral Clocks
	// This example function is found in the F28M3Xx_SysCtrl.c file.
  InitSysCtrl();
	// 1. Idiotischerweise im RAM und macht obiges memcpy() nochmal
	// 2. ruft InitFlash()

//IPCBootCPU2(C1C2_BROM_BOOTMODE_BOOT_FROM_FLASH);
  EALLOW;
  ClkCfgRegs.LOSPCP.all = 0;		// LSPCLK = 200 MHz (für SPI)
  ClkCfgRegs.SYSCLKDIVSEL.all = 0;	// Taktteiler entfernen (Fehler in InitSysCtrl())
  GpioCtrlRegs.GPADIR.bit.GPIO31=1;	// GPIO31 für blaue LED auf Ausgang
  EDIS;
  GpioDataRegs.GPASET.all = bit(31);	// GPIO31 auf High — Blaue LED aus
	// Initialize the PIE control registers to their default state.
	// The default state is all PIE interrupts disabled and flags
	// are cleared.
	// This function is found in the F28M3Xx_PieCtrl.c file.
  InitPieCtrl();
	// Initialize the PIE vector table with pointers to the shell Interrupt
	// Service Routines (ISR).
	// This will populate the entire table.
	// The shell ISR routines are found in F28M3Xx_DefaultIsr.c.
	// This function is found in F28M3Xx_PieVect.c.
  InitPieVectTable();
// Timing sync for background loops
// Timer period definitions found in device specific PeripheralHeaderIncludes.h
  CpuTimer0Regs.PRD.all =  10000;	// A tasks
  CpuTimer1Regs.PRD.all =  40000;	// B tasks
  EALLOW;
  CpuSysRegs.PCLKCR0.bit.CPUTIMER2 = 0;	// wird nicht benötigt
  CpuSysRegs.PCLKCR4.bit.EQEP3 = 0;
// Initialize PWM module
  CpuSysRegs.PCLKCR0.bit.TBCLKSYNC = 0;
	//Rote LED
  GpioCtrlRegs.GPBDIR.bit.GPIO34=1;	// GPIO34 für rote LED auf Ausgang
	// *****************************************
	// Inverter PWM configuration
	// ****************************************
  SyncSocRegs.SYNCSELECT.bit.EPWM4SYNCIN = 0;	//EPwm1SyncOut
  EPwm4Regs.TBCTL.bit.SYNCOSEL = TB_SYNC_IN;

  SyncSocRegs.SYNCSELECT.bit.EPWM10SYNCIN = 0;	//EPwm1Sync Out
  EPwm10Regs.TBCTL.bit.SYNCOSEL = TB_SYNC_IN;

  com0.init(BRR(12000000));	// 12 MBaud ergibt BRR = 1
  com0.send("\e[H\e[JStart\r\n");
  com0.TxIsr();		// Interrupts sind noch gesperrt, ISR so starten

  initADC();
  configDac();
  initMotorControl();
  initSigmaDelta();
  initPosEncoderSuite();
  amc1210.init();

// Note that the vectorial sum of d-q PI outputs should be less than 1.0 which
// refers to maximum duty cycle for SVGEN.
// Another duty cycle limiting factor is current sense
// through shunt resistors which depends on hardware/software implementation.
// Depending on the application requirements 3,2 or a single
// shunt resistor can be used for current waveform reconstruction.
// The higher number of shunt resistors allow the higher duty cycle operation
// and better dc bus utilization.
// The users should adjust the PI saturation levels carefully during
// open loop tests (i.e pi_id.Umax, pi_iq.Umax and Umins) as in project manuals.
// Violation of this procedure yields distorted current
// waveforms and unstable closed loop operations which may damage the inverter.

  HVDMC_Protection();
// Feedbacks OFFSET Calibration
  CpuSysRegs.PCLKCR0.bit.TBCLKSYNC = 1;
  EDIS;

  calOffsets();
// ISR Mapping
  EALLOW;
  EPwm11Regs.ETCLR.bit.INT=1;
  asm(" push IER");
  asm(" pop DBGIER");	// All interrupts allowed while real-time debugging
  asm(" clrc INTM,DBGM");	// enable interrupts and debug interrupts
  EDIS;
  com0.send("\e[1;32mSchleife\e[m\r\n");
//  - IDLE loop. Just loop forever
  for(;;) loop();	// (Arduino-like)
}
Detected encoding: ASCII (7 bit)8