so, dieser
Code:
//libraries
#include <IRremoteInt.h>
#include <ir_Lego_PF_BitStreamEncoder.h>
#include <IRremote.h>
#include <Bounce2.h>


uint8_t RECV_PIN = 13;
uint8_t taste = 0;
uint8_t zaehler = 1;

//resett pin definieren
#define PIN2RESET 10


// DIR und STEP pins definieren
#define dirPin_VL 2
#define stepPin_VL 3
#define dirPin_HL 4
#define stepPin_HL 5
#define dirPin_VR 6
#define stepPin_VR 7
#define dirPin_HR 8
#define stepPin_HR 9

//enable pins definieren
#define enbl_VL 40
#define enbl_HL 42
#define enbl_VR 41
#define enbl_HR 43

//definiere steps pro umdrehung:
#define stepsPerRevolution 200

//IR pin definieren
IRrecv irrecv(RECV_PIN);

decode_results results;

// debouncer instanz definieren
Bounce debouncer = Bounce();


void setup()
{

  // deklariere pins als output:
  pinMode(dirPin_VL, OUTPUT);
  pinMode(stepPin_VL, OUTPUT);
  pinMode(dirPin_HL, OUTPUT);
  pinMode(stepPin_HL, OUTPUT);
  pinMode(dirPin_VR, OUTPUT);
  pinMode(stepPin_VR, OUTPUT);
  pinMode(dirPin_HR, OUTPUT);
  pinMode(stepPin_HR, OUTPUT);

  Serial.begin(115200);

  Serial.println("code----/home/georg/Arduino/outdoor_robo/stepper/test_vier_stepper/ohne_lib/remote_vier_stepper_switch_1_enbl_bounce");

  //resett pin zustand definieren
  pinMode(PIN2RESET, INPUT);

  // IR empfänger pin mit bounce verbinden
  debouncer.attach(RECV_PIN);

  // debounce interval in ms
  debouncer.interval(5);

  // starte IR receiver
  irrecv.enableIRIn();

  // deaktiviere enable pins:
  digitalWrite(enbl_VL, HIGH);
  digitalWrite(enbl_HL, HIGH);
  digitalWrite(enbl_VR, HIGH);
  digitalWrite(enbl_HR, HIGH);

  //resett pin aktivieren
  digitalWrite(PIN2RESET, HIGH);
}

void loop()
{

  // aktiviere enable pins:
  digitalWrite(enbl_VL, LOW);
  digitalWrite(enbl_HL, LOW);
  digitalWrite(enbl_VR, LOW);
  digitalWrite(enbl_HR, LOW);


  // Update the Bounce instance :
  debouncer.update();

  // Get the updated value :
  zaehler = debouncer.read();

  if (zaehler == 1)
  {
    zaehler = 0;
    //    taste = 0;
    if (irrecv.decode(&results))
    {
      taste = results.value;
      Serial.println(taste);
      //      delay(1000);
      irrecv.resume(); // Receive the next value
    }

  }
  tasten_abfrage();

}


/***********************************************************/

void tasten_abfrage(void)
{
  switch (taste)
  {

    case 151 ://taste 1 große FB
      {
        if (taste == 151 )
        {
          Serial.println("szenario_1");
          Serial1.println("szenario_1");

          //fahre szenario_1

          delay (1000);

          break;
        }
      }

    case 103://taste 2 große FB
      {
        if (taste == 103)
        {
          Serial.println("szenario_2");
          Serial1.println("szenario_2");

          //fahre szenario_2

          delay (1000);

          break;
        }
      }

    case 79://taste 3 große FB
      {
        if (taste == 79)
        {
          Serial.println("szenario_3");
          Serial1.println("szenario_3");

          //fahre szenario_3

          delay (1000);

          break;
        }
      }


    case 207://taste 4 große FB
      {
        if (taste == 207)
        {
          Serial.println("szenario_4");
          Serial1.println("szenario_4");

          //fahre szenario_4

          delay (1000);

          break;
        }
      }


    case 253://OK taste, motor stop
      {
        if (taste == 253)
        {
          alle_stepper_stop();

          break;
        }
      }


    case 61:// rotate rechts große FB
      {
        if (taste == 61)
        {
          rechts_drehen();

          break;
        }
      }


    case 221:// rotate links große FB
      {
        if (taste == 221)
        {
          links_drehen();

          break;
        }

      }


    case 157:// fahre vor große FB
      {
        if (taste == 157)
        {
          vorwaerts();

          break;
        }
      }


    case 87:// fahre rückwärts große FB
      {
        if (taste == 87)
        {
          rueckwaerts();

          break;
        }
      }
  }


}


/***********************************************************/
void alle_stepper_stop(void)
{
  //enable pins deaktivieren
  digitalWrite(enbl_VL, HIGH);
  digitalWrite(enbl_HL, HIGH);
  digitalWrite(enbl_VR, HIGH);
  digitalWrite(enbl_HR, HIGH);
  reboot();
}

/***********************************************************/
void vorwaerts(void)
{

  // aktiviere enable pins:
  digitalWrite(enbl_VL, LOW);
  digitalWrite(enbl_HL, LOW);
  digitalWrite(enbl_VR, LOW);
  digitalWrite(enbl_HR, LOW);

  //richtung bestimmen
  digitalWrite(dirPin_VL, LOW);
  digitalWrite(dirPin_HL, LOW);
  digitalWrite(dirPin_VR, HIGH);
  digitalWrite(dirPin_HR, HIGH);

  for (int i = 0; i < stepsPerRevolution; i++)
  {
    digitalWrite(stepPin_VL, HIGH);
    digitalWrite(stepPin_HL, HIGH);
    digitalWrite(stepPin_VR, HIGH);
    digitalWrite(stepPin_HR, HIGH);
    delayMicroseconds(2000);
    digitalWrite(stepPin_VL, LOW);
    digitalWrite(stepPin_HL, LOW);
    digitalWrite(stepPin_VR, LOW);
    digitalWrite(stepPin_HR, LOW);
    delayMicroseconds(2000);
  }
}


/**********************************************************/

void rueckwaerts(void)
{

  // aktiviere enable pins:
  digitalWrite(enbl_VL, LOW);
  digitalWrite(enbl_HL, LOW);
  digitalWrite(enbl_VR, LOW);
  digitalWrite(enbl_HR, LOW);

  //richtung bestimmen
  digitalWrite(dirPin_VL, HIGH);
  digitalWrite(dirPin_HL, HIGH);
  digitalWrite(dirPin_VR, LOW);
  digitalWrite(dirPin_HR, LOW);

  for (int i = 0; i < stepsPerRevolution; i++)
  {
    digitalWrite(stepPin_VL, HIGH);
    digitalWrite(stepPin_HL, HIGH);
    digitalWrite(stepPin_VR, HIGH);
    digitalWrite(stepPin_HR, HIGH);
    delayMicroseconds(2000);
    digitalWrite(stepPin_VL, LOW);
    digitalWrite(stepPin_HL, LOW);
    digitalWrite(stepPin_VR, LOW);
    digitalWrite(stepPin_HR, LOW);
    delayMicroseconds(2000);
  }
}

/***********************************************************/
void rechts_drehen(void)
{

  // enable pins aktivieren
  digitalWrite(enbl_VL, LOW);
  digitalWrite(enbl_HL, LOW);
  digitalWrite(enbl_VR, LOW);
  digitalWrite(enbl_HR, LOW);

  //richtung bestimmen
  digitalWrite(dirPin_VL, LOW);
  digitalWrite(dirPin_HL, LOW);
  digitalWrite(dirPin_VR, LOW);
  digitalWrite(dirPin_HR, LOW);

  for (int i = 0; i < stepsPerRevolution; i++)
  {
    digitalWrite(stepPin_VL, HIGH);
    digitalWrite(stepPin_HL, HIGH);
    digitalWrite(stepPin_VR, HIGH);
    digitalWrite(stepPin_HR, HIGH);
    delayMicroseconds(2000);
    digitalWrite(stepPin_VL, LOW);
    digitalWrite(stepPin_HL, LOW);
    digitalWrite(stepPin_VR, LOW);
    digitalWrite(stepPin_HR, LOW);
    delayMicroseconds(2000);
  }

}


/**********************************************************/
void links_drehen(void)
{

  //enable pins aktivieren
  digitalWrite(enbl_VL, LOW);
  digitalWrite(enbl_HL, LOW);
  digitalWrite(enbl_VR, LOW);
  digitalWrite(enbl_HR, LOW);

  //richtung bestimmen
  digitalWrite(dirPin_VL, HIGH);
  digitalWrite(dirPin_HL, HIGH);
  digitalWrite(dirPin_VR, HIGH);
  digitalWrite(dirPin_HR, HIGH);

  for (int i = 0; i < stepsPerRevolution; i++)
  {
    digitalWrite(stepPin_VL, HIGH);
    digitalWrite(stepPin_HL, HIGH);
    digitalWrite(stepPin_VR, HIGH);
    digitalWrite(stepPin_HR, HIGH);
    delayMicroseconds(2000);
    digitalWrite(stepPin_VL, LOW);
    digitalWrite(stepPin_HL, LOW);
    digitalWrite(stepPin_VR, LOW);
    digitalWrite(stepPin_HR, LOW);
    delayMicroseconds(2000);
  }

}

/***********************************************************/
void reboot()
{
  pinMode(PIN2RESET, OUTPUT);
  digitalWrite(PIN2RESET, LOW);
  delay(100);
}
/***********************************************************/

/************************************************************/
kommt ohne eine stepper-lib aus, funktioniert soweit...
die erweiterungen / aufnahmen für die A4988 sowie der stärkere akku sind noch unterwegs, erst dann, mit der notwendigen einstellung der ströme zu den steppern kann ich sagen wie es weitergeht...