Benutzer-Werkzeuge

Webseiten-Werkzeuge


projekte2014:beerbot:dokumentation:software

Unterschiede

Hier werden die Unterschiede zwischen zwei Versionen gezeigt.

Link zu dieser Vergleichsansicht

Beide Seiten der vorigen Revision Vorhergehende Überarbeitung
Nächste Überarbeitung
Vorhergehende Überarbeitung
projekte2014:beerbot:dokumentation:software [2014/07/29 13:29]
wuxmax [BeerBotLib]
projekte2014:beerbot:dokumentation:software [2016/01/21 12:45] (aktuell)
Zeile 1: Zeile 1:
-====== ​Softwaredokumentation ​======+====== ​Quellcode ​====== 
 + 
 +===== Main Sketch ===== 
 + 
 +<code c++ BeerBot.ino>​ 
 +#include <​NewPing.h>​ 
 +#include <​Servo.h>​ 
 +#include "​i2c_t3.h"​ 
 +#include "​teensy3_Melexis90620.h"​ 
 +#include "​BeerBotLib.h"​ 
 +#include "​ThermalCam.h"​ 
 + 
 + 
 +ThermalCam thermCam; 
 +int thermCamServoPin = 14; 
 +int temperatureBorder = 24; 
 + 
 +ContactSensor frontSensor;​ 
 +int frontLeftPushButtonPin = 8; 
 +int frontRightPushButtonPin = 15; 
 + 
 +ContactSensor capSensor;​ 
 +int capRightPushButtonPin = 7; 
 +int capLeftPushButtonPin = 6; 
 +int capConductorPin = 9; 
 + 
 +Pusher pusher; 
 +int pusherPin = 21; 
 + 
 +Barrier lowBarrier;​ 
 +int lowBarrierServoPin = 12; 
 +int lowBarrierClosedPos = 150; 
 +int lowBarrierOpenPos = 60; 
 + 
 +Barrier highBarrier;​ 
 +int highBarrierServoPin = 13; 
 +int highBarrierClosedPos = 130; 
 +int highBarrierOpenPos = 83; 
 + 
 +Gear myGear; 
 +float wheelDiameter = 9.0; 
 +float axisDistance = 24.0; 
 +int leftMotorStepPin = 5; 
 +int leftMotorDirPin = 4; 
 +int rightMotorStepPin = 3; 
 +int rightMotorDirPin = 2; 
 + 
 +int phase = 0; 
 +boolean bottleFound = false; 
 +int lastFoundPos = 90; 
 + 
 +void setup() { 
 +  Serial.begin(9600);​ // for debugging purposes only 
 +   
 +  thermCam.setup(thermCamServoPin,​ temperatureBorder);​ 
 +  myGear.setup(wheelDiameter,​ axisDistance,​ leftMotorStepPin,​ leftMotorDirPin,​ rightMotorStepPin,​ rightMotorDirPin);​ 
 +  frontSensor.setup(frontRightPushButtonPin,​ frontLeftPushButtonPin,​ -1); 
 +  capSensor.setup(capRightPushButtonPin,​ capLeftPushButtonPin,​ capConductorPin);​ 
 +  pusher.setup(pusherPin);​ 
 +  lowBarrier.setup(lowBarrierServoPin,​ lowBarrierClosedPos,​ lowBarrierOpenPos);​ 
 +  highBarrier.setup(highBarrierServoPin,​ highBarrierClosedPos,​ highBarrierOpenPos); ​    
 +
 + 
 +void loop() { 
 +   
 + main1(); 
 +   
 +
 + 
 +/** 
 +* test functions for the different components of the robot. 
 +* for debugging and presentation purposes. 
 +*/ 
 + 
 +void testOpen() { 
 +  lowBarrier.closeBarrier();​ 
 +  delay(500);​ 
 +  highBarrier.closeBarrier();​ 
 +  delay(1000);​ 
 +  pusher.push(300);​ 
 +  delay(2000);​ 
 +
 + 
 +void testPusher() { 
 +  pusher.push(300);​ 
 +  delay(3000);​ 
 +
 + 
 +void testBarriers() { 
 +  highBarrier.closeBarrier();​ 
 +  delay(15);​ 
 +  lowBarrier.closeBarrier();​ 
 +  delay(1000);​ 
 +  lowBarrier.openBarrier();​ 
 +  delay(15);​ 
 +  highBarrier.openBarrier();​ 
 +  delay(1000);​ 
 +
 + 
 +void testDrive() { 
 +  myGear.drive(20,​ 12, true); 
 +  myGear.turnAngle(90,​ true, 12); 
 +
 + 
 +/** 
 +* the main function of the robots software. 
 +* defines the different phases of the process 
 +* it is not working pefectly in its current state due to some problems with e.g. the contact sensors. 
 +* it is modified to work as good as possible under the given circumstances. 
 +*/ 
 + 
 +void main1() { 
 +   
 +  switch (phase) { 
 +     
 +    case 0: 
 +      if (bottleLoaded()) { 
 +        phase = 4; 
 +      } 
 +      else if (thermCam.searchColdSpot()) { 
 +        phase = 2; 
 +      } 
 +      else if (bottleClose()) { 
 +        phase = 3; 
 +      } 
 +      else { 
 +        phase = 1; 
 +      } 
 +       
 +      break; 
 +     
 +    case 1: 
 +      easySearch(100,​ 5); 
 +      if (bottleFound) { 
 +        phase = 2; 
 +      } 
 +       
 +      break; 
 +       
 +    case 2: 
 +      myGear.turnToServoPos(thermCam.getPos(),​ 12, 10, 10); 
 +      delay(500);​ 
 +      myGear.drive(5,​ 12, true); 
 +      delay(500);​ 
 +       
 +      if (bottleClose()) { 
 +        phase = 3; 
 +      } 
 +      if (bottleLoaded()) { 
 +        phase = 4; 
 +      } 
 +      else { 
 +        bottleFound = thermCam.searchColdSpot();​ 
 +        if (thermCam.getPos() != 90) { 
 +          lastFoundPos = thermCam.getPos();​ 
 +        } 
 +        Serial.println(lastFoundPos);​ 
 + 
 +        if (!bottleFound) { 
 +          phase = 3; 
 +        } 
 +      } 
 +       
 +      break; 
 +     
 +    case 3: 
 +     // adjustPosition();​ 
 +     ​myGear.turnToServoPos(lastFoundPos,​ 12, 0, 5); 
 +     ​myGear.drive(3,​ 12, true); 
 +     ​delay(1000);​ 
 +       
 +      if (bottleLoaded()) { 
 +        phase = 4; 
 +      } 
 +       
 +      break; 
 +    
 +   case 4: 
 +     ​lowBarrier.closeBarrier();​ 
 +     for (int i = 0; i < 4; i++) { 
 +       ​highBarrier.openBarrier();​ 
 +       ​delay(500);​ 
 +       ​highBarrier.closeBarrier();​ 
 +       ​delay(500);​ 
 +     } 
 +      
 +     phase = 5; 
 +      
 +     ​break;​ 
 +    
 +   case 5: 
 +     if (capSensor.isConducting()) { 
 +       ​pusher.push(300);​ 
 +       ​delay(2000);​  
 +     } 
 +      
 +     ​break;​ 
 +  } 
 +
 + 
 +/** 
 +* helper function to check if the bottle is loaded by the robot. 
 +*/ 
 + 
 +boolean bottleLoaded() { 
 +  return (capSensor.leftButtonPushed() || capSensor.rightButtonPushed());​ 
 +
 + 
 +/** 
 +* helper function to check if the robot touched the bottle. 
 +*/ 
 + 
 +boolean bottleClose() { 
 +  return (frontSensor.leftButtonPushed() || frontSensor.rightButtonPushed());​ 
 +
 + 
 +/** 
 +* an easy algorithm that makes the robot drive forward and scan for cold bottles in steps. 
 +*/ 
 + 
 +boolean easySearch(float totalDistance,​ float partDistance) { 
 +  for (float driven = 0; driven < totalDistance;​ driven += partDistance) { 
 +    myGear.drive(partDistance,​ 12, true); ​    
 +     
 +    if (thermCam.searchColdSpot()) { 
 +      bottleFound = true; 
 +      break; 
 +    } 
 +     
 +  } 
 +
 + 
 +/** 
 +* a more complex function to scan the room for cold bottles. 
 +* has not been tested. 
 +*/ 
 + 
 +boolean complexSearch(float totalDistance,​ float partDistance) { 
 +  for (float driven = 0; driven < totalDistance;​ driven += partDistance) { 
 +    myGear.drive(partDistance,​ 12, true); 
 +    if (thermCam.searchColdSpot()) { 
 +      return true; 
 +    } 
 +  } 
 +   
 +  myGear.turnAngle(90,​ false, 12); 
 +  myGear.drive(partDistance,​ 12, true); 
 +  myGear.turnAngle(90,​ false, 12); 
 +   
 +  for (float driven = 0; driven < totalDistance;​ driven += partDistance) { 
 +    myGear.drive(partDistance,​ 12, true); 
 +    if (thermCam.searchColdSpot()) { 
 +      return true; 
 +    } 
 +  } 
 +   
 +  myGear.turnAngle(90,​ true, 12); 
 +  myGear.drive(partDistance,​ 12, true); 
 +  myGear.turnAngle(90,​ true, 12); 
 +  
 +  return false;  
 +
 + 
 +/** 
 +* a function to adjust the postion of the robot as it touches the bottle. 
 +*/ 
 + 
 +void adjustPosition() { 
 +  if (frontSensor.leftButtonPushed()) { 
 +    myGear.turnAngle(2,​ true, 12); 
 +  } 
 +  else if (frontSensor.rightButtonPushed()) { 
 +    myGear.turnAngle(2,​ false, 12); 
 +  } 
 +  myGear.drive(1,​ 12, true); 
 +
 + 
 +</​code>​
  
 ===== Libraries ===== ===== Libraries =====
  
 ==== BeerBotLib ==== ==== BeerBotLib ====
 +
 +This library defines and implements all classes that are needed to control the different components of the robot, except for the thermal camera.
  
 === BeerBotLib.h === === BeerBotLib.h ===
Zeile 175: Zeile 454:
  this-> position = pos;  this-> position = pos;
 } }
- 
-// void NewServo::​moveLeft(int servoSpeed, int servoDelay) { 
-// if (position > 0) { 
-// setPos(position - servoSpeed);​ 
-// delay(servoDelay);​ 
-// } 
-// } 
-// 
-// void NewServo::​moveRight(int servoSpeed, int servoDelay) { 
-// if (position < 180) { 
-// setPos(position + servoSpeed);​ 
-// delay(servoDelay);​ 
-// } 
-// } 
  
 /** /**
Zeile 503: Zeile 768:
 * *
 * @param angle: amount of degrees (0 - 360) by which the robot should turn, * @param angle: amount of degrees (0 - 360) by which the robot should turn,
-* turnDirection: ​rue --> anti-clockwise turning, false --> clockwise turning,+* turnDirection: ​true --> anti-clockwise turning, false --> clockwise turning,
 * stepSpeed: the delay between two steps oft the stepper motors. * stepSpeed: the delay between two steps oft the stepper motors.
 */ */
Zeile 526: Zeile 791:
  
 ==== ThermalCam ==== ==== ThermalCam ====
 +
 +This library defines and implements only the ThermalCam class. We seperated the thermal camera library, because it is the largest and most complex part of the software.
  
 === ThermalCam.h === === ThermalCam.h ===
 +
 +<code c++ ThermalCam.h>​
 +#ifndef ThermalCam_h
 +#define ThermalCam_h
 +
 +
 +#include "​Arduino.h"​
 +#include "​i2c_t3.h"​
 +#include "​teensy3_Melexis90620.h"​
 +#include "​BeerBotLib.h"​
 +  ​
 +class ThermalCam {
 + private:
 + Melexis90620 sensor;
 + NewServo myServo;
 +
 + int sweepSpeed;
 +
 + double* pixelTemps;
 + double temperatureBorder;​
 + int servoRange;
 +
 + boolean foundColdPixel();​
 + void getThermalData();​
 +
 + public:
 + void setup(int servoPin, int temperatureBorder);​
 + boolean searchColdSpot();​
 + int getPos();
 +};
 +
 +#endif
 +</​code>​
  
 === ThermalCam.cpp === === ThermalCam.cpp ===
 +
 +<code c++ ThermalCam.cpp>​
 +#include <​ThermalCam.h>​
 +
 +void ThermalCam::​setup(int servoPin, int temperatureBorder){
 + myServo.setup(servoPin,​ 90, true);
 + sensor.init(16);​
 +  ​
 + this-> sweepSpeed = 2;
 + this-> temperatureBorder = temperatureBorder;​
 + this-> servoRange = 90;
 +}
 +
 +/*
 +    Function for getting the thermaldata.
 +*/
 +
 +void ThermalCam::​getThermalData() {
 +    sensor.readTemperatures();​
 +    pixelTemps = sensor.getPixelTemperatures();​
 +}
 +
 +/*
 +    Function sets thermalcam-servo to 90 degrees.
 +    Servo does a complete sweep and every degree the thermaldata gets checked for a cold source.
 +    If there is a cold source, "​true"​ is returned back, else "​false"​.
 +*/
 +
 +boolean ThermalCam::​searchColdSpot() {
 +    myServo.setPos(90);​
 +    delay(100);
 +    for (int i = 0; i < servoRange; i++) {
 +        myServo.sweep((int)sweepSpeed,​ servoRange, 15);
 +        getThermalData();​
 + if (foundColdPixel()) {
 +     return true;
 + }
 +    }
 +    return false;
 +}
 +
 +/*
 +    Function, which gives back the current position (angle) of the thermalcam-servo.
 +*/
 +
 +int ThermalCam::​getPos() {
 +    return myServo.getPos();​
 +}
 +
 +/*
 +    Function, which checks the two rows in the middle of the thermalcam-pixelarray for a cold source.
 +*/
 +
 +boolean ThermalCam::​foundColdPixel() {
 +    for( int i = 28; i < 35; i++ ) {
 +    if( pixelTemps[i] < temperatureBorder ) return true;
 +    }
 +    return false;
 +}
 +
 +</​code>​
 +
 +==== 3rd party libraries ====
 +
 +=== i2c_t3 ====
 +
 +I2C library for Teensy3
 +
 +http://​forum.pjrc.com/​threads/​21680-New-I2C-library-for-Teensy3
 +
 +=== teensy3_Melexis90620 ===
 +
 +Library to control the Melexis90620 thermal camera
 +
 +https://​github.com/​Zapalot/​teensy3_Melexis90620
 +
 +=== NewPing ===
 +
 +Library for improved usage of an ultrasonic distance sensor with a Teensy.
 +
 +https://​github.com/​PaulStoffregen/​NewPing
 +
 +
 +
  
projekte2014/beerbot/dokumentation/software.1406633380.txt.gz · Zuletzt geändert: 2016/01/21 12:45 (Externe Bearbeitung)