Der Ship-to-Shore Kran (STS-Kran) wird im Gegensatz zum Bahn/Straße Containerkran nicht mit RC, sondern über eine Kabelschleppe gesteuert. Keine RC-Fahrtregler, keine Sender, keine Empfänger – zum Einsatz kommt eine komplett selbst entwickelte Elektronik: zur Steuerung des Krans verwenden wir die Potis aus einem dafür umgebauten Playstation 2 Controller.

2013-09-21 17.24.46-2 2013-09-21 16.57.38
Diese Controller erzeugen eigentlich ein proprietäres serielles Protokoll, wir haben allerdings die Steuerungselektronik entfernt und die Ausgänge der Joysticks/Potis an jeweils einen Mikrocontroller angeschlossen, der die Auswertung der Potis und die Ansteuerung der Motoren mittels PWM übernimmt. Hier haben wir zwei verschiedene Wege gewählt: Bei Katze und Spreader wird das PWM-Signal proportional zur Auslenkung des Joysticks erzeugt (je weiter die Auslenkung, desto schneller läuft der Motor; bei Nullstellung bleibt der Motor sofort stehen). Bei den Fahrgestellen des Krans selbst erhöht sich die Geschwindigkeit nur  allmählich, egal wie weit der Joystick bewegt wird. Befindet sich der Joystick in Nullstellung, bremst der Kran allmählich bis zum Stillstand ab. Das Heben und Senken des Auslegers selbst erfolgt mit konstanter Geschwindigkeit, so das hier derzeit keine Elektronik zum Einsatz kommt.

Als Mikrocontroller kommen bei uns ATtiny85 von Atmel zum Einsatz.

Als Motortreiber (H-Brücke) verwenden wir derzeit einen DRV8835 von Texas Instruments für Katze und Spreader, da wir hier mit Spannungen um die 5V bei < 1A arbeiten, und für die 6 Kato-Fahrgeselle für den Kran selbst einen L298, da hier Spannungen von 12V (und Ströme >1A) anliegen. Man könnte auch die Spannung etwas senken (auf ca. 11V) und dann beide Ausgänge eines DRV8835 parallel schalten, dann würde dieser Treiber auch Ströme von 2,5A liefern können.

Viele fertige Motortreiber (z.B. DRV8835) benötigen zwei Eingangssignale (eins für die Laufrichtung, eins für Geschwindigkeit), andere (L298 z.B.) benötigen 3 Signale (eins für Linkslauf, eins für Rechtslauf, eins für Geschwindigkeit). Unsere Software kann beide Arten ansteuern, das nicht benötigte Signal wird dann einfach nicht verwendet.

/*——————————————————————————————–
  PWM Control via Poti/Joystick
  Version für DFRobot Motorshield L298
  Hardware: ATtiny85 
 
              +——+
 (RESET) PB5 -|1°   8|- Vcc
         PB3 -|2    7|- PB2 (SCK)
         PB4 -|3    6|- PB1 (MISO)
         GND -|4    5|- PB0 (MOSI)     
              +——+ 
 
  Motortreiber: DFRobot L298 Shield
 
  Shield im PWM Mode betreiben
  Shield auf externe Stromversorgung jumpern
 
  PIN4 – Motor1 Direction Control (an PB1 vom ATtiny)
  PIN5 – Motor1 PWM Control       (an PB0 vom ATtiny)
  PIN6 – Motor2 PWM Control
  PIN7 – Motor2 Direction Control
 
  Stand: 05.11.2013
——————————————————————————————–*/

const int mitte = 128;       // enthält den Wert der Mittelposition des Potis/Joysticks
                             // dieser Wert sollte in der Theorie 255/2 = 128 sein…
                             // (muss experimentell ermittelt werden)
const int intervall = 15;    // Umgebung um die Mittelposition, in der der Motor stehen soll
                             // (muss experimentell ermittelt werden)
const int arraysize = 70;    // Anzahl der Stützpunkte für die Kennlinie

/*——————————————————————————————–
Dieses Array enthält die Kennlinie für den Controller. Zur Zeit wird dasselbe Array für
Rechts- und Linkslauf verwendet, aber man kann natürlich genauso gut verschiedene Kennlinien
für beide Richtungen anlegen. Die Kennlinie sollte experimentell ermittelt werden.
Wir fangen mal mit 25 an, da kleinere Werte den Motor nur fiepen lassen,
und bei 125 hören wir auf, sonst wird’s zu schnell:
——————————————————————————————–*/
const int pwm_array[arraysize] = {25,25,25,26,26,26,27,27,27,28,28,28,29,29,29,30,30,30,31,31,
                                  31,32,32,32,33,33,33,34,34,35,35,38,38,40,40,45,45,50,50,55,
                                  55,60,60,65,65,70,70,75,75,80,80,85,85,90,90,95,95,100,100,105,
                                  105,110,110,115,115,120,120,125,125,125};
                             
int pwm = 0;                 // beim DFRobot L298 Shield an PIN5
int richtung = 1;            // beim DFRobot L298 Shield an PIN4
int poti = 3;                // Poti an PIN PB3 vom ATtiny (PIN2)
int vp;                      // enthält den Wert des Potis

/*——————————————————————————————–
Mit dieser Funktion kann die PWM Frequenz verändert werden.
base frequency 62500 Hz.
——————————————————————————————–*/
void setPwmFrequency(int divisor) {
  byte mode;
  switch(divisor) {
    case 1: mode = 0x01; break;
    case 8: mode = 0x02; break;
    case 64: mode = 0x03; break;
    case 256: mode = 0x04; break;
    case 1024: mode = 0x05; break;
    default: return;
  }
  TCCR0B = TCCR0B & 0b11111000 | mode;
}

void setup() {                 
  pinMode(richtung, OUTPUT);
  pinMode(pwm,OUTPUT);
  setPwmFrequency(256);
}

void loop() {
  vp = analogRead(poti);
  vp = map(vp,0,1023,0,255);                   // 10bit Wert vom ADC in 8bit umwandeln
 
  if (vp >= mitte-intervall &&                 // Mittelstellung +/- Intervall
      vp <= mitte+intervall) {        digitalWrite(richtung, LOW );              // Motor disabled     analogWrite(pwm, 0);                       // Motor disabled   }   else if (vp < mitte-intervall) {             // Poti nach rechts     vp -= (mitte-intervall);                   // Wert für Nullposition abziehen, da wir ja bei                                                // Geschwindigkeit 0 anfangen wollen...     vp = vp * -1;                              // die -1 deswegen, weil der Potiwert kleiner wird, für                                                // unsere Zwecke aber größer werden muss...     if (vp >= arraysize-1) {                   // nicht über’s Ende des Arrays hinausschiessen (böse Falle!)
      vp = arraysize-1;
    }
    digitalWrite(richtung, HIGH);              // Richtung 1
    analogWrite(pwm, pwm_array[vp]);           // Kennlinie für Rechtslauf
  }   
  else if (vp > mitte+intervall) {             // Poti nach links       
    vp -= (mitte+intervall);                   // Wert für Nullposition abziehen (siehe oben)
                                           
    if (vp >= arraysize-1) {
      vp = arraysize-1;
    }
    digitalWrite(richtung, LOW);               // Richtung 2
    analogWrite(pwm, pwm_array[vp]);           // Kennlinie für Linkslauf
  } 
  delay(1);                                    // 1 ms warten, damit der A/D Wandler sich „beruhigt“
}