update:
klappt wunderbar!
Danke an alle Helfer!
Hier das Ergebnis für alle Interessierten - share and enjoy ! 
// PID controller
// to control 2 encoder motors by PWM
// ver 1.022
#include <PID_v1.h>
#define MAXMOTORS 2
// global variables for Interrupt-Service-Routine (ISR)
volatile int8_t ISRab[MAXMOTORS] = {0,0};
volatile long motenc[MAXMOTORS] = {0,0},
oldenc[MAXMOTORS] = {0,0};
// global PID variables
double PIDsetpoint[MAXMOTORS],
PIDinput[MAXMOTORS],
PIDoutput[MAXMOTORS];
int PIDregstate[MAXMOTORS];
float PIDencgap[MAXMOTORS];
// PID tuning parameters
PID PIDs[] =
{
PID (&PIDinput[0], &PIDoutput[0], &PIDsetpoint[0], 2,5,1, DIRECT),
PID (&PIDinput[1], &PIDoutput[1], &PIDsetpoint[1], 2,5,1, DIRECT)
};
#define PID_REGTIME_MS 5
#define PID_REG_PREC 1
#define PID_REGSTATE_IDLE 0
#define PID_REGSTATE_ACTIVE 1
#define PID_REGMAX 255
#define PID_REGMIN -255
//*************************************************************
#define sensortouch(pinHIGH) !digitalRead(pinHIGH)
#define startpin 12
// set motor pins
// motor 0
#define pinmenc0A 2 // encA yellow
#define pinmenc0B 3 // encB blue
#define pinmot0d1 4 // dir1
#define pinmot0d2 5 // dir2
#define pinmot0pwm 6 // enable
// motor 1
#define pinmenc1A 7 // encA yellow
#define pinmenc1B 8 // encB blue
#define pinmot1d1 9 // dir1
#define pinmot1d2 10 // dir2
#define pinmot1pwm 11 // enable
// Encoder functions courtesy of / entnommen aus: http: //www.meinDUINO.de //
// Die beiden Schritt-Tabellen für 1/1, 1/2 oder 1/4-Auflösung/resolution
// 1/1 Auflösung/resolution
//int8_t schrittTab[16] = {0,-1,1,0,1,0,0,-1,-1,0,0,1,0,1,-1,0};
// 1/2 Auflösung/resolution
int8_t schrittTab[16] = {0, 0,0,0,1,0,0,-1, 0,0,0,1,0,0,-1,0};
// 1/4 Auflösung/resolution
//int8_t schrittTab[16] = {0,0,0,0,0,0,0,-1,0,0,0,0,0,1,0,0};
// Interrupt Service Routine: wenn Interrupt ausgelöst wird
ISR(TIMER1_COMPA_vect) {
ISRab[0] <<= 2;
ISRab[0] &= B00001100;
ISRab[0] |= (digitalRead(pinmenc0A) << 1) | digitalRead(pinmenc0B);
motenc[0] += schrittTab[ISRab[0]]; //
ISRab[1] <<= 2;
ISRab[1] &= B00001100;
ISRab[1] |= (digitalRead(pinmenc1A) << 1) | digitalRead(pinmenc1B);
motenc[1] += schrittTab[ISRab[1]]; //
}
byte pinmotdir[MAXMOTORS][2]={ {pinmot0d1, pinmot0d2},
{pinmot1d1, pinmot1d2} };
int pinmotpwm[MAXMOTORS]={pinmot0pwm, pinmot1pwm};
inline void motoron(byte motnr, int power) {
if(power>0) {
digitalWrite( pinmotdir[motnr][0],HIGH);
digitalWrite( pinmotdir[motnr][1],LOW);
} else if(power<0) {
digitalWrite( pinmotdir[motnr][0],LOW);
digitalWrite( pinmotdir[motnr][1],HIGH);
} else if(power==0) {
digitalWrite( pinmotdir[motnr][0],LOW);
digitalWrite( pinmotdir[motnr][1],LOW);
}
power = abs(power);
if(power>254) power=254;
analogWrite(pinmotpwm[motnr], power);
}
inline void motorbrake(byte motnr) { // to do list !!!
motoron(motnr, 0);
}
inline void motorcoast(int motnr) {
motoron( motnr, 0);
}
#define motoroff motorcoast
//************************************************************************************
void setup()
{
Serial.begin(115200);
pinMode(startpin,INPUT_PULLUP); // btn to start
pinMode(pinmot0d1,OUTPUT); // dir1
pinMode(pinmot0d2,OUTPUT); // dir2
pinMode(pinmenc0A,INPUT_PULLUP); // encA
pinMode(pinmenc0B,INPUT_PULLUP); // encB
pinMode(pinmot0pwm,OUTPUT); // enable
pinMode(pinmot1d1,OUTPUT); // dir1
pinMode(pinmot1d2,OUTPUT); // dir2
pinMode(pinmenc1A,INPUT_PULLUP); // encA
pinMode(pinmenc1B,INPUT_PULLUP); // encB
pinMode(pinmot1pwm,OUTPUT); // enable
// time interrupt for encoder readings
noInterrupts(); // Jetzt keine Interrupts / disable
TIMSK1 |= (1<<OCIE1A); // Timer 1 PIDOutput Compare A Match Interrupt Enable
TCCR1A = 0; // "Normaler" Modus
// WGM12: CTC-Modus einschalten (Clear Timer on Compare match)
// Stimmen OCR1A und Timer überein, wird der Interrupt ausgelöst
// Bit CS12 und CS10 setzen
// => Prescaler=8:
TCCR1B = (1<<WGM12) | (1<<CS11);
// Frequenz = 16,000,000 / 8 / 512 = rd. 4 kHz
OCR1A =511;
interrupts(); // Interrupts wieder erlauben / enable
// set PID parameters
PIDs[ 0].SetMode(AUTOMATIC);
PIDs[ 0].SetOutputLimits(PID_REGMIN, PID_REGMAX);
PIDs[ 0].SetSampleTime(PID_REGTIME_MS);
PIDsetpoint[0] = 360; // set target,
PIDregstate[0]=PID_REGSTATE_ACTIVE; // switch the PID on to motor[0]
PIDs[ 1].SetMode(AUTOMATIC);
PIDs[ 1].SetOutputLimits(PID_REGMIN, PID_REGMAX);
PIDs[ 1].SetSampleTime(PID_REGTIME_MS);
PIDsetpoint[ 1] = 540; // set target,
PIDregstate[ 1]=PID_REGSTATE_ACTIVE; // switch the PID on to motor[0]
}
//************************************************************************************
char started =0;
int mainloopcnt=0;
void PIDupdate( byte nr) {
PIDinput[nr] = motenc[nr];
PIDencgap[nr] = abs(PIDsetpoint[nr]-PIDinput[nr]); //distance away from setpoint
if (PIDregstate[nr]==PID_REGSTATE_ACTIVE) {
PIDs[nr].Compute();
PIDs[nr].SetTunings(30, 80, 1.2);
}
else PIDoutput[nr]=0;
if ((PIDencgap[nr]>PID_REG_PREC)&&(PIDregstate[nr]==PID_REGSTATE_ACTIVE))
{ motoron(nr, PIDoutput[nr]); }
}
void PIDcheckok (byte nr) {
if(mainloopcnt>=9) { // stopped after 9 loops delay ?
if( (PIDencgap[nr]<=PID_REG_PREC)&& abs(oldenc[nr]-motenc[nr])<1
&& abs(PIDoutput[nr]<PID_REGMAX/2 ) ) {
PIDs[nr].SetMode(MANUAL);
PIDs[nr].SetTunings( 0, 0, 0);
PIDregstate[nr]=PID_REGSTATE_IDLE;
motoroff(nr);
}
}
}
void loop()
{
mainloopcnt++;
if (!started) {
Serial.println();
Serial.println("nr | enc - output | nr | enc - output");
Serial.print( "0: "); Serial.print(motenc[0]); Serial.print(" | "); Serial.print(PIDoutput[0]);
Serial.print(" | 1: "); Serial.print(motenc[1]); Serial.print(" | "); Serial.print(PIDoutput[1]);
Serial.println();
delay(500); // wait before starting
started=1;
}
for(int i=0; i< MAXMOTORS ; ++i) PIDupdate( i);
for(int i=0; i< MAXMOTORS ; ++i) PIDcheckok( i);
if (mainloopcnt >=9) {
Serial.print( "0: "); Serial.print(motenc[0]); Serial.print(" | "); Serial.print(PIDoutput[0]);
Serial.print(" | 1: "); Serial.print(motenc[1]); Serial.print(" | "); Serial.print(PIDoutput[1]);
Serial.println();
mainloopcnt=0;
}
for(int i=0; i< MAXMOTORS ; ++i) oldenc[ i]=motenc[ i];
delay( 5);
}
Ziel(0)=360, Ziel(1)=540, Genauigkeit +/-1
nr | enc - output | nr | enc - output
0: 0 | 0.00 | 1: 0 | 0.00
0: 6 | 255.00 | 1: 8 | 255.00
0: 27 | 255.00 | 1: 32 | 255.00
0: 54 | 255.00 | 1: 63 | 255.00
0: 85 | 255.00 | 1: 98 | 255.00
0: 118 | 255.00 | 1: 136 | 255.00
0: 151 | 255.00 | 1: 174 | 255.00
0: 185 | 255.00 | 1: 213 | 255.00
0: 219 | 255.00 | 1: 252 | 255.00
0: 254 | 255.00 | 1: 291 | 255.00
0: 288 | 255.00 | 1: 331 | 255.00
0: 323 | 255.00 | 1: 371 | 255.00
0: 352 | -225.00 | 1: 412 | 255.00
0: 361 | -15.40 | 1: 454 | 255.00
0: 363 | 153.40 | 1: 497 | 255.00
0: 363 | 142.60 | 1: 530 | 75.00
0: 363 | 131.80 | 1: 542 | -46.20
0: 363 | 121.00 | 1: 545 | -151.40
0: 363 | 110.20 | 1: 545 | -167.80
0: 363 | 99.40 | 1: 545 | -184.20
0: 362 | 255.00 | 1: 545 | -200.20
0: 362 | 111.80 | 1: 545 | -216.60
0: 362 | 104.60 | 1: 545 | 37.80
0: 362 | 97.40 | 1: 544 | 21.80
0: 361 | 123.80 | 1: 544 | -24.20
0: 361 | 0.00 | 1: 544 | -7.80
0: 361 | 0.00 | 1: 544 | -22.20
0: 361 | 0.00 | 1: 544 | -36.60
0: 361 | 0.00 | 1: 544 | -51.00
0: 361 | 0.00 | 1: 543 | -33.80
0: 361 | 0.00 | 1: 541 | 20.60
0: 361 | 0.00 | 1: 541 | 0.00
0: 361 | 0.00 | 1: 541 | 0.00
0: 361 | 0.00 | 1: 541 | 0.00
0: 361 | 0.00 | 1: 541 | 0.00
0: 361 | 0.00 | 1: 541 | 0.00
PID sicher noch nicht 100% fein getunt 