Watterott Roboter Starter Kit – Erweiterungen

Vor einiger Zeit habe ich ein paar Modifikationen am Watterott Roboter Starter Kit vorgenommen. Diesmal geht es um Erweiterungen, (Liniensensor, Ultraschallsensor , Bluetooth Modul) mit denen man den Roboter sinnvoll ergänzen kann.

Ultraschallsensor Erweiterung

Der Ultraschall Sensor kann anstelle des Sharp Infrarotsensors eingesetzt werden. Der Sensor hat einen breiteren Erfassungswinkel. Auf das Scannen der Umgebung mit dem Servo kann weitestgehend verzichtet werden.

Was wird benötigt?

  • HC-SR04 Ultraschallsensor
  • 4-polige Buchsenleisten
  • 4-polige Stiftleiste
  • 4 Drähte 15cm lang
  • Plexiglas Halterung (im Roboter Starter Kit enthalten)
  • Lötkolben, Seitenschneider

Durchführung

Der Sensor wird gemäß Verdrahtungs-Schema verdrahtet und mit der Plexiglas Halterung am Servo Horn befestigt

[pe2-image src=“https://lh3.googleusercontent.com/-pGw-rZkCCv0/VyYdaTbgdEI/AAAAAAAAO_Y/MqSCRGIRV7cDHzNpVMbiadWY64JSQrdcQCHM/s144-c-o/IMG_5793.JPG“ href=“https://picasaweb.google.com/100614490999857774768/RoboterStarterKitV2#6279739068144186434″ caption=““ type=“image“ alt=“IMG_5793.JPG“ ]

Verdrahtung

[pe2-image src=“https://lh3.googleusercontent.com/-EqKExS0Eppc/VyYPgJ–jfI/AAAAAAAAO-w/UgOU60mJKfYWfS6EcgHj96WhjvMtRLJRwCHM/s144-c-o/HC-SR04-Erweiterung_Steckplatine.jpg“ href=“https://picasaweb.google.com/100614490999857774768/RoboterStarterKitV2#6279723775525031410″ caption=““ type=“image“ alt=“HC-SR04-Erweiterung_Steckplatine.jpg“ ]

Arduino Sketch

Die Funktionen zum Auslesen des Sensors sind Teil der Watterott Roboter Starter Kit (WRSK) Bibliothek.
Das Beispiel Sketch zum Kollionsvermeider (examples/ObstacleAvoiding)

/*
  ObstacleAvoiding.ino - Watterott Starter Robot Kit (WSRK)
  Author: RobotFreak www.robotfreak.de/blog
  Copyright (c) 2015 RobotFreak All Rights Reserved

  For information about the Watterott Starter Robot Kit (WSRK)
  visit http://www.watterott.com/de/StarterKit-Roboter

  The minimum circuit:
  * Watterott Starter Robot Kit (WSRK) Arduino Uno + Arduino Motor Shield 
  * Sharp GP2D12 or GP2D120 Infrared distance sensor connected to A3
  * or HC-SR04 Ultrasonic distance sensor connected to pin 6, 7
  * USB cable

  Alternative circuit:
  * Watterott Starter Robot Kit (WSRK) Arduino Pro + Arduino Motor Shield 
  * FTDI compatible USB serial module/cable
  * Sharp GP2D12 or GP2D120 Infrared distance sensor connected to A3
  * or HC-SR04 Ultrasonic distance sensor connected to pin 6, 7
  * optional Adafruit Bluefruit EZ-Link Module connected to FTDI connector

 */
#include ;
#include ;
#include "iomapping.h"
#include 
#include 

#define DEBUG_LEVEL 2

#define LOW_SPEED 50
#define MID_SPEED 70
#define TOP_SPEED 100

WRSK_MotorControl motors( m1DirectionControl, m1SpeedControl, m2DirectionControl, m2SpeedControl, DEBUG_LEVEL);
WRSK_UltrasonicSensor us(usEchoPin, usTriggerPin, DEBUG_LEVEL);

int speed_l;
int speed_r;
int dly;
float distance;
int debugLevel = DEBUG_LEVEL;

Servo SensorServo;  // Mit diesem Element wird der Servo gesteuert

void setup() {

  Serial.begin(38400);                 // Sets the baud rate to 38400
  speed_l = 0;
  speed_r = 0;
  // Servo initialiseren und auf 90° stellen
  SensorServo.attach( servoPin );
  SensorServo.write( 90 );
  delay( 500 );

  Serial.println("WMR-SHR obstacle Avoiding Version 1.0");   

  distance = us.read();  // get distance
  while (distance > 10.0)
  {
    distance =  us.read();  // get distance
    delay(100);
  }
  Serial.println("Let's go");
}


void loop()
{
  int i;

  distance =  us.read();  // get distance

  if (distance > 0.0)
  {
    if (distance < 10.0)
    {
      motors.driveWheels(0,0);
      delay(500);
      speed_l = -MID_SPEED;
      speed_r = MID_SPEED;
      dly = 5;
      do {
        distance =  us.read();  // get distance
        delay(40);
        motors.driveWheels(speed_l, speed_r);
        //      motors.driveWheelsRamp(speed_l, speed_r, dly);
      } 
      while(distance < 20.0);  
      speed_l = 0;
      speed_r = 0;
      motors.driveWheels(speed_l,speed_r);
      //    motors.driveWheelsRamp(speed_l, speed_r, dly);
      delay(500);
    }
    else if (distance < 30.0)
    {
      speed_l = MID_SPEED;
      speed_r = MID_SPEED;
    }
    else
    {
      speed_l = TOP_SPEED;
      speed_r = TOP_SPEED;
    }
    dly = 10;
    motors.driveWheels(speed_l, speed_r);
    //  motors.driveWheelsRamp(speed_l, speed_r, dly);
  }

  delay(40);

}

Liniensensor Erweiterung

Mit dieser Erweiterung kann der Roboter einen schwarzen Linie auf weißem Unterrund folgen

Was wird benötigt?

  • Pololu QTR-3A Liniensensor (analog)
  • 5 polige Buchsenleiste
  • 5 polige Stiftleiste
  • 2 polige Stiftleiste
  • 2 Schrauben M2x15, 4 Muttern M2
  • Lötkolben, Seitenschneider, Dremel
  • schwarzes Isolier Klebeband 10mm breit
  • Plexiglas Halterung (im Roboter Kit enthalten)

Durchführung

Es müssen die beiden Lötbrücken SNS1 und SNS2 am Motor Shield entfernt werden.
Die Verbindung Sensor / Arduino Shield erfolgt mit den Drähten, Buchsen- und Stiftleisten
Der Sensor wird mit den M2 Schrauben und Muttern und der Plexiglas Halterung am Roboter Starter Kt befestigt
[pe2-image src="https://lh3.googleusercontent.com/-RxmaW1BTv_I/VyYPhCyvz9I/AAAAAAAAO-w/VgNaIrKdHC4gtob0hSe5dBx2K-bXZa_nQCHM/s144-c-o/Linien-Sensor-Mod.jpg" href="https://picasaweb.google.com/100614490999857774768/RoboterStarterKitV2#6279723790774554578" caption="Arduino Motor Shield mit Elko" type="image" alt="Linien-Sensor-Mod.jpg" ]

[pe2-image src="https://lh3.googleusercontent.com/-It0jV08MWEU/VyYdWnJRHfI/AAAAAAAAO_Y/2PLMMkdpGQwsGUNw7_KnNGs85lIgIN9NACHM/s144-c-o/IMG_5790.JPG" href="https://picasaweb.google.com/100614490999857774768/RoboterStarterKitV2#6279739004716916210" caption="" type="image" alt="IMG_5790.JPG" ]

[pe2-image src="https://lh3.googleusercontent.com/-ZHU1Tx2kOus/VyYdZOt2HoI/AAAAAAAAO_Y/8nz2NsNwzVAVanF_hKZnVIIwDwn2mmOagCHM/s144-c-o/IMG_5792.JPG" href="https://picasaweb.google.com/100614490999857774768/RoboterStarterKitV2#6279739049699057282" caption="" type="image" alt="IMG_5792.JPG" ]

[pe2-image src="https://lh3.googleusercontent.com/-sRQ8zyyJwf4/VyYdXwaXHiI/AAAAAAAAO_Y/6R9c4AeYI-gesrGW4OcF5JV0kHa0-NRrwCHM/s144-c-o/IMG_5791.JPG" href="https://picasaweb.google.com/100614490999857774768/RoboterStarterKitV2#6279739024384400930" caption="" type="image" alt="IMG_5791.JPG" ]

Sensor Verdrahtung

[pe2-image src="https://lh3.googleusercontent.com/-L-esiDimQ00/VyYPffLod0I/AAAAAAAAO-w/O0CImMKfP6wOw8GMrfgSumNvuQPdEgd8gCHM/s144-c-o/Line-Sensor-Erweiterung_Steckplatine.jpg" href="https://picasaweb.google.com/100614490999857774768/RoboterStarterKitV2#6279723764035385154" caption="" type="image" alt="Line-Sensor-Erweiterung_Steckplatine.jpg" ]

Arduino Sketch

Es wird die Pololu QTR Bibliothek benötigt

/*
 LineFollower.ino - Watterott Starter Robot Kit (WSRK) line follower

  Author: RobotFreak www.robotfreak.de/blog
  Copyright (c) 2015 RobotFreak All Rights Reserved

  For information about the Watterott Starter Robot Kit (WSRK)
  visit http://www.watterott.com/de/StarterKit-Roboter

  The minimum circuit:
  * Watterott Starter Robot Kit (WSRK) Arduino Uno + Arduino Motor Shield 
  * Pololu QTR-3RC or QTR-3A Line sensor connected to A0,A1,A2
  * HC-SR04 Ultrasonic distance sensor connected to pin 6, 7
  * USB cable

  Alternative circuit:
  * Watterott Starter Robot Kit (WSRK) Arduino Pro + Arduino Motor Shield 
  * FTDI compatible USB serial module/cable
  * Pololu QTR-3RC or QTR-3A Line sensor connected to A0,A1,A2
  * optional Adafruit Bluefruit EZ-Link Module connected to FTDI connector

*/
#include 
#include 
#include 
#include "iomapping.h"
#include 
#include 
#include 

#define LOW_SPEED 50
#define MID_SPEED 70
#define TOP_SPEED 100

#define BUFFERSIZE 20
#define DEFAULT_speedMultiplier 5 
//#define USE_BLUETOOTH_SERIAL2    // we use Bluetooth over Serial2

// ** GENERAL SETTINGS ** - General preference settings
#define DEBUG_LEVEL 2
int debugLevel = DEBUG_LEVEL;
boolean DEBUGGING = true; // Whether debugging output over serial is on by defauly (can be flipped with 'h' command)

WRSK_MotorControl motors( m1DirectionControl, m1SpeedControl, m2DirectionControl, m2SpeedControl, DEBUG_LEVEL);

int speedMultiplier = DEFAULT_speedMultiplier; // Default speed setting. Uses a range from 1-10 

// No config required for these parameters
unsigned long stopTime=millis(); // used for calculating the run time for motors

//Define Variables we'll be connecting to
double Setpoint, Input, Output;

//Define the aggressive and conservative Tuning Parameters
double aggKp=4, aggKi=0.2, aggKd=1;
double consKp=1, consKi=0.0, consKd=0.0;
//double consKp=1, consKi=0.05, consKd=0.25;

//Specify the links and initial tuning parameters
PID myPID(&Input, &Output, &Setpoint, consKp, consKi, consKd, DIRECT);

Servo myServo;

void setup() 
{
  myServo.attach(servoPin);
  myServo.write(90);

  Serial.begin(38400);
#ifdef USE_BLUETOOTH_SERIAL2
  Serial2.begin(115200);
#endif
  if (debugLevel) { Serial.println("MURCS Line Follower V1.0");  }
  initLineFollow();
//  initLineFollowPID();

} 


// Stop the bot
void stopBot() 
{
  motors.driveWheels(0,0);
  if (debugLevel){ Serial.println("Stopping both wheels"); 
  }
  serialReply("i", "st"); // Tell the phone that the robot stopped
}

// sensors 0 through 2 are connected to analog inputs 0 through 2, respectively
QTRSensorsRC qtr((unsigned char[]) {line1Pin, line2Pin, line3Pin}, 
  NUM_LINESENSORS);
unsigned int sensorValues[NUM_LINESENSORS];


void initLineSensors(int debugLevel)
{
  delay(1000);
  for (int i = 0; i < 10; i++)  // make the calibration take about 1.25 seconds
  {
    qtr.calibrate();       // reads all sensors 10 times at 2.5 ms per six sensors (i.e. ~25 ms per call)
    motors.driveWheels(-LOW_SPEED,LOW_SPEED);
  }
  motors.driveWheels(0,0);
  delay(500);
  for (int i = 0; i < 15; i++)  // make the calibration take about 2.5 seconds
  {
    qtr.calibrate();       // reads all sensors 10 times at 2.5 ms per six sensors (i.e. ~25 ms per call)
    motors.driveWheels(LOW_SPEED,-LOW_SPEED);
  }
  motors.driveWheels(0,0);
  delay(500);
  for (int i = 0; i < 10; i++) // make the calibration take about 1.25 seconds { qtr.calibrate(); // reads all sensors 10 times at 2.5 ms per six sensors (i.e. ~25 ms per call) motors.driveWheels(-LOW_SPEED,LOW_SPEED); } motors.driveWheels(0,0); delay(500); // print the calibration minimum values measured when emitters were on if (debugLevel > 1)
  {
    for (int i = 0; i < NUM_LINESENSORS; i++)
    {
      Serial.print(qtr.calibratedMinimumOn[i]);
      Serial.print(' ');
    }
    Serial.println();

    // print the calibration maximum values measured when emitters were on
    for (int i = 0; i < NUM_LINESENSORS; i++) { Serial.print(qtr.calibratedMaximumOn[i]); Serial.print(' '); } Serial.println(); Serial.println(); } delay(1000); } unsigned int readLineSensors(int debugLevel) { // read calibrated sensor values and obtain a measure of the line position from 0 to 5000 // To get raw sensor values, call: // qtra.read(sensorValues); instead of unsigned int position = qtra.readLine(sensorValues); unsigned int position; static int count = 0; // qtr.read(sensorValues); position = qtr.readLine(sensorValues); if (debugLevel > 1)
  {
  // print the sensor values as numbers from 0 to 1000, where 0 means maximum reflectance and
  // 1000 means minimum reflectance, followed by the line position
    for (unsigned char i = 0; i < NUM_LINESENSORS; i++) { Serial.print(sensorValues[i]); Serial.print('\t'); } //Serial.println(); // uncomment this line if you are using raw values Serial.println(position); // comment this line out if you are using raw values } if (count > 10)
  {
//    Serial2.write((position >> 8) & 0xFF);
//    Serial2.write(position & 0xFF);
    count = 0;
  }
  return position;
}

void initLineFollow()
{
//  myServo.write(90);
  initLineSensors(debugLevel);
}

void initLineFollowPID()
{
//  myServo.write(90);
  initLineSensors(debugLevel);
  Input = 0.0;
  Setpoint = 0.0;
  //tell the PID to range between -50 and 50 
  myPID.SetOutputLimits(-2000, 2000); 
  //turn the PID on
  myPID.SetMode(AUTOMATIC);
}


// Replies out over serial and handles pausing and flushing the data to deal with Android serial comms
void serialReply(char* sensorname, char* tmpmsg) 
{
#ifdef USE_BLUETOOTH_SERIAL2
  Serial2.print(sensorname);
  Serial2.print(":");
  Serial2.println(tmpmsg); // Send the message back out the serial line
  //Wait for the serial debugger to shut up
  delay(200); //this is a magic number
  Serial2.flush(); //clears all incoming data
#else
  Serial.print(sensorname);
  Serial.print(":");
  Serial.println(tmpmsg); // Send the message back out the serial line
  //Wait for the serial debugger to shut up
  delay(200); //this is a magic number
  Serial.flush(); //clears all incoming data
#endif
}

// Check if enough time has elapsed to stop the bot and if it is safe to proceed
void checkIfStopBot() 
{
  if (stopTime < millis()) 
  {
    stopBot();
  }
}

void doLineFollow()
{
  int speed_l, speed_r;
  unsigned int position;

  position = readLineSensors(debugLevel);

  if (position < 500) { // far to the right if (debugLevel > 2) { Serial.println("far to the right");}
    speed_l = MID_SPEED;
    speed_r = -LOW_SPEED;
  }
  else if (position > 1500)
  {  // far to the left
    if (debugLevel > 2) { Serial.println("far to the left");}
    speed_l = -LOW_SPEED;
    speed_r = MID_SPEED;
  }
  else
  {  // centered on line 
    if (debugLevel > 2) { Serial.println("on line");}
    speed_l = MID_SPEED;
    speed_r = MID_SPEED;
  }
  stopTime = motors.driveWheels(speed_l, speed_r);
  delay(20); 
}

void doLineFollowPID()
{
  int speed_l, speed_r, speedDiff;
  int position;

  position = readLineSensors(0);
  Input = position - 2000.0;
  myPID.Compute();

  speedDiff = map(abs((int)Output), -2000, 2000, -50, 50);
//  if (Output < 0.0) // speedDiff = -speedDiff; if (debugLevel > 1) 
  {
    Serial.print("Input: ");
    Serial.print(Input, DEC);
    Serial.print(" Output: ");
    Serial.print(Output, DEC);
    Serial.print(" SDiff: ");
    Serial.println(speedDiff, DEC);
  }
//  speedDiff = (int) power_difference;
  // Compute the actual motor settings.  We never set either motor
  // to a negative value.
  const int max = TOP_SPEED;
  if(speedDiff > max)
      speedDiff = max;
  if(speedDiff < -max)
      speedDiff = -max;

  if(speedDiff < 0)
     stopTime = motors.driveWheels(max+speedDiff, max);
  else
     stopTime =  motors.driveWheels(max, max-speedDiff);
  delay(40); 
}


// Main loop running at all times
void loop() 
{
  doLineFollow();
  checkIfStopBot();
}

Bluetooth Erweiterung

Die Bluetooth Erweiterung ermöglicht die Fernbedienung des Roboter über Bluetooth. Mit dem Adafruit BLuetooth EZ-Link ist es auch möglich, den Arduino über Bluetooth zu programmieren.

Was wird benötigt?

  • Adafruit Bluetooth EZ Link Modul
  • Arduino Pro 5V/16MHz
  • oder 10polige Stiftleiste, 100nF Kondensator für Arduino Uno

Durchführung

Leider funktioniert dies Erweiterung nicht so ohne weiteres mit dem Arduino Uno. Einfacher geht es mkt einem Arduino Pro. Dort kann man einfach das Bluetooth Modul an der 6-poligen FTDI -Stiftleite anstecken. fertig.

[pe2-image src="https://lh3.googleusercontent.com/-q4-M1XD3KQM/VyYQYuvZ0LI/AAAAAAAAO-4/iaIKhZ2sODgJRBRviU4hN8AGK8biURh-ACHM/s144-c-o/IMG_0460.JPG" href="https://picasaweb.google.com/100614490999857774768/RoboterStarterKitV2#6279724747464495282" caption="" type="image" alt="IMG_0460.JPG" ]

Verdrahtung Arduino Pro

[pe2-image src="https://lh3.googleusercontent.com/-prlS_tCqP28/VyYPgpzFmjI/AAAAAAAAO-w/16wPpyX2klU1-uXPYcKEFNNXQeM_DvN-ACHM/s144-c-o/Bluetooth-Erweiterung_Steckplatine.jpg" href="https://picasaweb.google.com/100614490999857774768/RoboterStarterKitV2#6279723784065096242" caption="" type="image" alt="Bluetooth-Erweiterung_Steckplatine.jpg" ]

Verdrahtung Arduino Uno

[pe2-image src="https://lh3.googleusercontent.com/-VdApFc2ejJ4/VzN3hN63DTI/AAAAAAAAPAQ/dGxvJA-b2Eki42IGrejpGBSN8am845huwCHM/s144-c-o/Bluetooth-Erweiterung-Uno_Steckplatine.jpg" href="https://picasaweb.google.com/100614490999857774768/RoboterStarterKitV2#6283497317667900722" caption="" type="image" alt="Bluetooth-Erweiterung-Uno_Steckplatine.jpg" ]

Arduino Sketch

t.b.c

Weblinks

3 Antworten auf „Watterott Roboter Starter Kit – Erweiterungen“

  1. Zum Liniensensor:
    der Pololu Sensor ist zurzeit nicht zu bekommen.
    Ich habe mir einen aus zwei Fotowiderständen (LDR) und zwei Ultrahellen LEDs auf Lochraster selber gebaut. Die Vorwiderstände für die LDRs sollten so um 4,7 kOhm liegen, die LEDs müssen über zwei 150 Ohm Widerstände parallel betrieben werden, weil die Durchlassspannung > 2,5V ist. Die LEDs können über einen Ausgang geschaltet werden, so dass eine „optische Debug Anzeige“ zur Verfügung steht (Blinkcodes o.ä.).
    Eine Arduino Uno mit SMD 328 hat übrigens 2 zusätzliche Analogeingänge (A6 u. A7).

  2. Habe endlich das auf der MF2015 in Hannover erstandene WRSK zusammengebaut und auch die hier empfohlenen Erweiterungen mit übernommen:
    – Step Up Wandler für eine „geregelte“ Stromversorgung;
    – Kippschalter und die ganzen Stützkondensatoren.
    Damit der Robbi die Motoren nicht über den USB Port mit Spannung versorgt, hier noch eine Erweiterung:
    Auf dem Motorshield die Verbindung Vin auftrennen, und eine Diode (1N4005) so einlöten, dass zwar Vin vom Shield zum Arduino gelangt, aber nicht umgekehrt.

Schreibe einen Kommentar

Deine E-Mail-Adresse wird nicht veröffentlicht. Erforderliche Felder sind mit * markiert