Falls auch andere Probleme mit dem I2C Zugriff auf den MD22 haben:
Das Problem lag darin, dass in der Beschreibung immer von der Basisadresse 0xB0 die Rede ist.
Ansprechen läßt sich der MD22 aber unter der Adresse 0x58.
Hab leider mehrere Tage damit rumgekaspert.

Hier noch der funktionierende Code:

Code:
 /******************************************************************************
 *  Arduino analog input 5 - I2C SCL
 *  Arduino analog input 4 - I2C SDA
 * ******************************************************************************/

#include <Wire.h>

#define md22Address 0x58  // !! NOT 0xB0 !!

void setup() {
  Serial.begin(9600);
  Wire.begin(0x53);
  readMD22();
}


void loop() {
  write_MD22();
  readMD22();
  delay(1000);
}

void write_MD22(){ 
   Wire.beginTransmission(md22Address);       // MD22 Address (All Switches ON = 0x58)
   Wire.send(0x00);                           // Set Register 0 (Mode)
   delay(1);
   Wire.send(0x00);                           // Send Data Mode to 1 (0 to 255)
   delay(1);                                  // automatic shift right (next Register 1)
   Wire.send(160);                            // Send Data for left Motor(1) Speed (0 = Full Reverse | 128 = Stop | 255 = Full Forward)
   delay(1);
   Wire.send(100);                            // Send Data for right Motor(2) Speed
   delay(1);
   Wire.send(128);                            // Send Data for Acceleration
   Wire.endTransmission();
}

void readMD22(){                              // Reads Data from MD22
  Wire.beginTransmission(md22Address);        // Calles software register
  Wire.send(0x07);                            // Register of SoftwareRevision
  Wire.endTransmission();
  Wire.requestFrom(md22Address, 1);           // Requests one byte
  while(Wire.available() < 1);                // Wait for it to arrive
  int revision = Wire.receive();              // Get byte
  
  Wire.beginTransmission(md22Address);        // Calles software register
  Wire.send(0x01);                            // Register of Motor 1
  Wire.endTransmission();
  Wire.requestFrom(md22Address, 1);           // Requests one byte
  while(Wire.available() < 1);                // Wait for it to arrive
  int mot1 = Wire.receive();                  // Get byte
  
  Wire.beginTransmission(md22Address);
  Wire.send(0x02);                            // Register of Motor 2
  Wire.endTransmission();
  Wire.requestFrom(md22Address, 1);           // Requests one byte
  while(Wire.available() < 1);                // Wait for it to arrive
  int mot2 = Wire.receive();                  // Get byte
  
  Wire.beginTransmission(md22Address);
  Wire.send(0x03);                            // Register of Acceleration
  Wire.endTransmission();
  Wire.requestFrom(md22Address, 1);           // Requests one byte
  while(Wire.available() < 1);                // Wait for it to arrive
  int accel = Wire.receive();                 // Get byte
  
  Serial.print("MD22-Ver: ");                 // Print to Serial
  Serial.print(revision);
  
  Serial.print(" | Current Mot 1 Speed: ");
  Serial.print(mot1);
  
  Serial.print(" | Current Mot 2 Speed: ");
  Serial.print(mot2);
  
  Serial.print(" | Current Accel: ");
  Serial.println(accel);                      // Print to serial and CR
}
Bis die Tage.