BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a...

29
2015 BeerBot FINAL REPORT DALTON VERHAGEN

Transcript of BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a...

Page 1: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

2015

BeerBot

Final ReportDalton Verhagen

Page 2: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

Table of Contents

Abstract..............................................................................................................................2

Executive Summary............................................................................................................3

Introduction.......................................................................................................................4

Integrated System..............................................................................................................5

Arduino Mega.................................................................................................................5

Raspberry Pi Model 2.....................................................................................................6

Teensy 3.2......................................................................................................................6

Mobile Platform.................................................................................................................6

Actuation........................................................................................................................... 7

Sensors...............................................................................................................................7

Sound Activation............................................................................................................7

Camera...........................................................................................................................7

Ultrasonic Distance Sensors...........................................................................................7

Behaviors........................................................................................................................... 7

Experimental Layout and Results.......................................................................................8

Conclusion..........................................................................................................................8

Documentation..................................................................................................................9

Appendix............................................................................................................................9

Arduino Main................................................................................................................. 9

Arduino Pins.................................................................................................................11

Arduino RobotCtrl........................................................................................................12

Arduino Motor............................................................................................................. 17

Teensy Pulse.................................................................................................................18

OpenCV Code...............................................................................................................19

Page 3: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

AbstractBeerBot is an autonomous robot designed to ensure you never have to get out of

your chair to get your next beer. Aided with an array of ultrasonic sensors and a camera, BeerBot will search for a red box that you place next to you, so that you can grab a beer out of the cooler built into it. The box placed next to the user also has a speaker built into it, so that when the speaker is turned on BeerBot will begin its search for the box.

Page 4: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

Executive SummaryBeerBot is an autonomous robot that uses various sensors in order to find a user in a

room when signaled by the user. A sound remote built into a red box with a speaker and a microphone on BeerBot is used to signal that BeerBot is being called. The microphone also has a bandpass filter on it to allow only a narrow range of frequencies that the red speaker box transmits.

A camera is also mounted on BeerBot so that it can find the red box with a speaker with computer vision. A Rasberry Pi with an opencv script controls this camera. The vision script looks for a rectangular red box and signals an Arduino to move BeerBot until the box is in the center of the image. The Arduino is controlling both the motors moving BeerBot and the array of ultrasonic distance sensors in the front of BeerBot. These distance sensors will stop BeerBot when it is 15cm away from the red speaker box.

The Arduino is also attached to the microphone circuit on the robot, so that it can start searching for the red speaker box when a start signal comes from the box. The actual search for the box simply involves BeerBot rotating about an expanding spiral until the box is found with the camera. BeerBot will also avoid obstacles at any point in this search by backing up, turning, and going forward if any obstacle is detected by the ultrasonic distance sensors.

Once BeerBot approaches the red speaker box it will notify the user by “wiggling” back and forth and flashing some LEDs mounted on it.

Page 5: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

IntroductionBeerBot is designed to have almost no user interaction but still know when and where

to find the user. This means there are two main problems to solve for BeerBot to be successful. One, how to get BeerBot to find the user when they do not have a static predefined position, and two, how to get BeerBot to start finding the user with minimum user interaction.

To solve the first problem I implemented an expanding spiral search algorithm. This makes BeerBot search for the user in an expanding spiral pattern. This was chosen as it maximizes the amount of area BeerBot is searching while minimizing the time it takes to do so. This of course works best if BeerBot is placed at the center of the room, but it will still function otherwise. Roomba’s actually employ a similar method in order to cover a large area in little time.

The second problem could be solved by making a remote system for BeerBot that initiates search, but a traditional IR remote would require the user to point something directly at BeerBot, and I want BeerBot to minimize user interaction. A sound remote, on the other hand, would not require this and is relatively cheap to make. For the sound remote to function BeerBot would need to only be activated at a specific frequency of sound, so some filtering will need to be done.

Page 6: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

Integrated System

BeerBot has 3 main microcontrollers to control various functions, so I will cover BeerBot’s integrated system one microcontroller at a time.

Arduino MegaThe Arduino is used to controls obstacle avoidance sensors and the 2 6V DC

motors that BeerBot is equipped with. To control the motors, the Arduino uses an Arduino Motor shield. The Motor Shield has the added benefit of powering the Mega board from the motor power terminal on it too. The obstacle avoidance sensors the Mega controls are 4 Ultrasonic Sensors. Furthermore, the Mega has a serial connection with Raspberry Pi in order to communicate with it.

The Arduino also takes in the search command from the speaker box placed next to the user. An external analog circuit is used to send the command from the speaker to the Arduino.

Page 7: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

Raspberry Pi Model 2The Raspberry Pi’s main function is to act as a master to the Arduino Mega, as

well as control the PS3 Eye with OpenCV. It has a serial connection with both the Teensy and Arduino so it can communicate with them.

Teensy 3.2 The Teensy is just used to control the sound signal coming from the red speaker

box the user places next to them.

Mobile PlatformBeerBot consists of a wooden chassis with a slot to hold the Styrofoam cooler in the

middle of it. The power circuitry is placed on the top back of the chassis. The microcontrollers are then placed on top of the power circuitry with a raised platform. The two motors are placed at the front bottom of the chassis with a ball caster placed in the rear for support. The front part of the chassis contains all the ultrasonic sensors and the PS3 Eye.

To help manage cables the chassis also has a runway for the cables running from the front to the back of BeerBot to be placed. I also made the top end of the chassis that houses the ultrasonic sensors removable so there would be easy access to the sensors and motors.

Page 8: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

Actuation BeerBot is outfitted with two 25Dmm 99:1 dc brushed motors from Pololu as this

provided the best torque to weight ratio for BeerBot’s needs. With these motors BeerBot can, theoretically, take loads of up to 10 lbs. while maintaining a .25 m/s velocity. BeerBot should be able to carry 6 beers at minimum so 10lbs. match 6 beers and then some.

SensorsSound Activation

BeerBot uses an analog circuit and microphone to interpret when to start searching for the red speaker box. This analog circuit acts as a bandpass filter accepting only frequency values between 4900Hz to 5100Hz, and it returns a logical 0 if there is a frequency in this range and a 1 if there is not a frequency in this range.

The analog circuit uses an LM567 tone decoder to achieve this functionality. This IC requires an external R/C circuit to specify the center frequency of the internal band pass filter. I used a %2 tolerant capacitor for the R/C circuit as lower tolerant capacitors would cause the center frequency to drift too much. The resistor is actually a 2 kΩ potentiometer so that the center frequency can be fine-tuned to the exact frequency required.

The teensy in the red speaker box is configured to generate 4 5kHz square waves lasting 500ms each with 500ms of silence separating each of them. The Arduino is programmed to read look for this signal from the analog circuit. If this value is detected the Arduino will begin to search for the red speaker box.

CameraBeerBot is also outfitted with a PS3 camera that the Raspberry Pi controls with a python

script using the opencv library. The python script is programmed to look for a red box larger than a certain area. The Raspberry Pi communicates with the Arduino through a serial connection.

Ultrasonic Distance SensorsFour ultrasonic distance sensors are placed at the front of BeerBot to help it avoid

obstacles. If BeerBot detects anything 25cm away from its front it will consider that an obstacle to avoid. Four LEDs are mounted above the sensors as well. If an obstacle is detected by a sensor than the LED will turn on.

BehaviorsBeerBot sits idle until it receives the activation signal from the red speaker box. Once

the signal was correctly read in by the Arduino, BeerBot begins searching for the red box with

Page 9: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

an expanding spiral search algorithm. This algorithm has BeerBot’s right wheel set at a constant speed while the left wheel is left idle. The idle wheel gradually increases its speed until it is equal to the speed of the right wheel, so that an expanding spiral movement pattern is achieved. If an obstacle is detected at any point, BeerBot will avoid the obstacle by backing up and then turning left or right 30 degrees, and then heading straight.

If the PS3 eye camera detects the red speaker box at any point after the spiral motion began, BeerBot will stop and begin moving towards the speaker box. This is done by stopping BeerBot and turning left or right until the red speaker box is in the center of the image the PS3 eye is reading. Once this is achieved BeerBot will go straight towards the box until it is 10cm away from the box. The distance is measured with the ultrasonic sensors in the front of BeerBot.

Finally once BeerBot has arrived in front of the box, it will notify the user by flashing the LEDs mounted above the ultrasonic sensors, and “dancing” by moving left and right in place. This will last for 1 minute and afterwards BeerBot will return for the idle mode again waiting for the activation signal once more.

Experimental Layout and ResultsIn order to create a good expanding spiral for BeerBot I needed to experiment with

different speeds for the idle wheel. If the idle wheel speeds up too fast then the spiral will end too soon, but if it speeds up too slow then the spiral will have large gaps in it. I experimented with the values determined the speed of the wheel with trial and error until the spiral achieved was a good spiral of about 6 feet in diameter.

The sound remote needed to have a really good bandpass filter so that no sounds other than the one sent from the red speaker box are used to activate BeerBot. The LM567 IC takes care of the bandpass but some experimentation needed to be done to get the center frequency stable. I originally tested the circuit with a pure sine wave tone and some 20% tolerant capacitors and changed capacitor and resistor values until the waveform for the center frequency was the most stable.

ConclusionBeerBot performed well with its current setup. If BeerBot is within 6-10feet of the user

it was able to find the target in under 5 minutes. However, if BeerBot was placed a much farther distance away from the user it would take an exceedingly long time to find the user, especially so if obstacles were in the way. This is a limitation inherent to searching the environment somewhat randomly for the user.

If I were designing BeerBot from the bottom up again I would have opted for a method involving sound localization. I originally tried this but the analog circuitry behind it proved to difficult. Instead I would redesign BeerBot to use a sound localization sensor that was done entirely in the digital domain with a DSP, perhaps something like a MSP432.

Page 10: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

I definitely learned a whole lot from this project. I had never done a large open project for a class like this before, and I feel like I took away a lot of lessons from this that I can use on future projects. Just some of the skills I learned from building robot include opencv programming, solidworks, and high level Arduino development.

Documentation LM567 Tone Decoder DataSheet - http://www.ti.com.cn/cn/lit/ds/symlink/lm567c.pdf LM386 Powe OpAmp DataSheet - http://www.ti.com/lit/ds/symlink/lm386.pdf Circuit Diagram -

AppendixArduino Main#include "RobotCtrl.h"#include <NewPing.h>

Page 11: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

RobotCtrl BeerBot(25);

void setup()

Serial.begin(115200);Expanding_Spiral_Search();

void loop()

BeerBot.checkSonar();if(BeerBot.FL_b || BeerBot.FML_b || BeerBot.FMR_b || BeerBot.FR_b)

avoidObstacle();else

BeerBot.goForward(200);

void Expanding_Spiral_Search() int speed = 200;

BeerBot.leftMotor.disableBrake();BeerBot.rightMotor.disableBrake();

BeerBot.leftMotor.setForward();BeerBot.rightMotor.setForward();

int leftSpeed = 0;BeerBot.leftMotor.setSpeed(leftSpeed);BeerBot.rightMotor.setSpeed(speed);

int updateInterval = 500; //half a second

while(leftSpeed != speed) BeerBot.checkSonar();if(BeerBot.FL_b || BeerBot.FML_b || BeerBot.FMR_b || BeerBot.FR_b)

avoidObstacle();return;

delay(updateInterval);leftSpeed = leftSpeed + 1;BeerBot.leftMotor.setSpeed(leftSpeed);

void avoidObstacle() BeerBot.stop();BeerBot.goReverse(200);delay(2000);

if((BeerBot.FLM_b || BeerBot.FLR_b) && !BeerBot.FL_b && !BeerBot.FR_b) int seed = random(100);if (seed > 55)

Page 12: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

BeerBot.turnLeft(200);else

BeerBot.turnRight(200);

else if(((BeerBot.FML_b && BeerBot.FL_b) || (!BeerBot.FML_b &&

BeerBot.FL_b)) && !BeerBot.FR_b && !BeerBot.FMR_b) BeerBot.turnRight(200);

delay(2000);BeerBot.stop();

/* function that will handle zeroing in on the target once the camera has signaled thatit has been detected. There are 3 basic responses: Go left if the target is to the left,Go right if the target is to the right, and Go forward until the target is 25cm away. */void goToTarget()

BeerBot.stop();

while(cmd != 0) int speed = 120;updateCmd();

if(cmd == 'l') BeerBot.turnLeft(speed);while(cmd == 'l')

updateCmd();BeerBot.stop();

else if(cmd == 'r')

BeerBot.turnRight(speed);while(cmd == 'r')

updateCmd();BeerBot.stop();

else if(cmd == 'f')

BeerBot.goForward(180);while(cmd == 'f')

BeerBot.checkSonar();updateCmd();if((BeerBot.FL >= 5 && BeerBot.FL <= 15) || (BeerBot.FR

<= 15 && BeerBot.FR >= 5)) BeerBot.stop();

delay(5000);digitalWrite(SONAR_LED_FML,HIGH);digitalWrite(SONAR_LED_FMR,HIGH);

digitalWrite(SONAR_LED_FML,LOW);digitalWrite(SONAR_LED_FMR,LOW);

Page 13: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

else if(cmd == '0')

return;

BeerBot.stop();

void updateCmd() if(Serial.available())

cmd = Serial.read();

Arduino Pins/* * Pins.h * * Created: 10/13/2015 1:57:49 PM * Author: dalton */

#ifndef INCPINS_H_#define INCPINS_H_

#define ECHO_PIN_FL 22#define TRIGGER_PIN_FL 24#define ECHO_PIN_FML 26#define TRIGGER_PIN_FML 28#define ECHO_PIN_FMR 30#define TRIGGER_PIN_FMR 31#define ECHO_PIN_FR 32#define TRIGGER_PIN_FR 33

#define SONAR_LED_FL 34#define SONAR_LED_FML 35#define SONAR_LED_FMR 36#define SONAR_LED_FR 37

#define MOTORA_DIR 12#define MOTORB_DIR 13#define MOTORA_BRAKE 9#define MOTORB_BRAKE 8#define MOTORA_SPEED 3#define MOTORB_SPEED 11

#endif /* INCPINS_H_ */

Arduino RobotCtrl// RobotCtrl.h

#ifndef _ROBOTCTRL_h#define _ROBOTCTRL_h

Page 14: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

#include "Motor.h"#include "NewPing.h"#include "Pins.h"

#if defined(ARDUINO) && ARDUINO >= 100#include "arduino.h"

#else#include "WProgram.h"

#endif

class RobotCtrl protected:

NewPing SonarFL;NewPing SonarFR;NewPing SonarFML;NewPing SonarFMR;

int threshold_distance;

public:Motor leftMotor;Motor rightMotor;

int FL,FR,FML,FMR;boolean FL_b,FR_b,FML_b,FMR_b;

RobotCtrl(int thres_d);

/* MOVEMENT CTRLS */void goForward(int speed);void goForward(int speed, int duration);void goReverse(int speed);void goReverse(int speed, int duration);void turnLeft(int speed);void turnLeft(int speed, int duration);void turnRight(int speed);void turnRight(int speed, int duration);void stop();

/* SONAR CTRLS */void checkSonar();int getMinDistance();

;

#endif

// // //

#include "RobotCtrl.h"

RobotCtrl::RobotCtrl(int thres_d)

Page 15: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

: SonarFL(TRIGGER_PIN_FL,ECHO_PIN_FL,400), SonarFML(TRIGGER_PIN_FML,ECHO_PIN_FML,400),

SonarFMR(TRIGGER_PIN_FMR,ECHO_PIN_FMR,400),SonarFR(TRIGGER_PIN_FR,ECHO_PIN_FR,400)

threshold_distance = thres_d;leftMotor.init(MOTORA_DIR,MOTORA_SPEED,MOTORA_BRAKE);rightMotor.init(MOTORB_DIR,MOTORB_SPEED,MOTORB_BRAKE);pinMode(SONAR_LED_FL,OUTPUT);pinMode(SONAR_LED_FML,OUTPUT);pinMode(SONAR_LED_FMR,OUTPUT);pinMode(SONAR_LED_FR,OUTPUT);

/* MOVEMENT FUNCTIONS */

void RobotCtrl::goForward(int speed) leftMotor.disableBrake();//disable any brakes on motorsrightMotor.disableBrake();

leftMotor.setForward(); //set both motors direction to forwardrightMotor.setForward();

leftMotor.setSpeed(speed); //set the speed of both motorsrightMotor.setSpeed(speed);

void RobotCtrl::goForward(int speed, int duration) leftMotor.disableBrake();//disable any brakes on motorsrightMotor.disableBrake();

leftMotor.setForward(); //set both motors direction to forwardrightMotor.setForward();

leftMotor.setSpeed(speed); //set the speed of both motorsrightMotor.setSpeed(speed);

delay(duration);

leftMotor.enableBrake();rightMotor.enableBrake();

leftMotor.setSpeed(0);rightMotor.setSpeed(0);

void RobotCtrl::goReverse(int speed) leftMotor.disableBrake();//disable any brakes on motorsrightMotor.disableBrake();

leftMotor.setReverse(); //set both motors direction to reverserightMotor.setReverse();

Page 16: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

leftMotor.setSpeed(speed); //set both motors speedrightMotor.setSpeed(speed);

void RobotCtrl::goReverse(int speed, int duration) leftMotor.disableBrake();//disable any brakes on motorsrightMotor.disableBrake();

leftMotor.setReverse(); //set both motors direction to reverserightMotor.setReverse();

leftMotor.setSpeed(speed); //set both motors speedrightMotor.setSpeed(speed);

delay(duration);

leftMotor.enableBrake();rightMotor.enableBrake();

leftMotor.setSpeed(0);rightMotor.setSpeed(0);

void RobotCtrl::turnLeft(int speed) leftMotor.disableBrake();//disable any brakes on motorsrightMotor.disableBrake();

leftMotor.setReverse(); //set left motor to reverserightMotor.setForward(); //set right motor to forward

leftMotor.setSpeed(speed); //set the speed of both motorsrightMotor.setSpeed(speed);

void RobotCtrl::turnLeft(int speed, int duration) leftMotor.disableBrake();//disable any brakes on motorsrightMotor.disableBrake();

leftMotor.setReverse(); //set left motor to reverserightMotor.setForward(); //set right motor to forward

leftMotor.setSpeed(speed); //set the speed of both motorsrightMotor.setSpeed(speed);

delay(duration);

leftMotor.enableBrake();rightMotor.enableBrake();

leftMotor.setSpeed(0);rightMotor.setSpeed(0);

void RobotCtrl::turnRight(int speed)

Page 17: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

leftMotor.disableBrake();//disable any brakes on motorsrightMotor.disableBrake();

leftMotor.setForward(); //set the left motor to forwardrightMotor.setReverse(); //set thr right motor to reverse

leftMotor.setSpeed(speed); //set the speed of both motorsrightMotor.setSpeed(speed);

void RobotCtrl::turnRight(int speed, int duration) leftMotor.disableBrake();//disable any brakes on motorsrightMotor.disableBrake();

leftMotor.setForward(); //set the left motor to forwardrightMotor.setReverse(); //set thr right motor to reverse

leftMotor.setSpeed(speed); //set the speed of both motorsrightMotor.setSpeed(speed);

delay(duration);

leftMotor.enableBrake();rightMotor.enableBrake();

leftMotor.setSpeed(0);rightMotor.setSpeed(0);

void RobotCtrl::stop() leftMotor.enableBrake(); //enable the brakes on both motorsrightMotor.enableBrake();leftMotor.setSpeed(0);rightMotor.setSpeed(0);

/* SONAR FUNCTIONS */

void RobotCtrl::checkSonar() FL = SonarFL.ping_cm();FML = SonarFML.ping_cm();FMR = SonarFMR.ping_cm();FR = SonarFR.ping_cm();

if (FL < threshold_distance && FL != 0) FL_b = true;digitalWrite(SONAR_LED_FL,HIGH);

else

FL_b = false;digitalWrite(SONAR_LED_FL,LOW);

if (FML < threshold_distance && FML != 0) FML_b = true;

Page 18: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

digitalWrite(SONAR_LED_FML,HIGH);else

FML_b = false;digitalWrite(SONAR_LED_FML,LOW);

if (FMR < threshold_distance && FMR != 0) FMR_b = true;digitalWrite(SONAR_LED_FMR,HIGH);

else

FMR_b = false;digitalWrite(SONAR_LED_FMR,LOW);

if (FR < threshold_distance && FR != 0) FR_b = true;digitalWrite(SONAR_LED_FR,HIGH);

else

FR_b = false;digitalWrite(SONAR_LED_FR,LOW);

int RobotCtrl::getMinDistance() int minDistance = FL;

if(FML < minDistance) minDistance = FML;

if(FMR < minDistance)

minDistance = FMR;if(FR < minDistance)

minDistance = FR;

return minDistance;

// RobotCtrl.h

#ifndef _ROBOTCTRL_h#define _ROBOTCTRL_h

#include "Motor.h"#include "NewPing.h"#include "Pins.h"

#if defined(ARDUINO) && ARDUINO >= 100#include "arduino.h"

#else#include "WProgram.h"

Page 19: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

#endif

class RobotCtrl protected:

NewPing SonarFL;NewPing SonarFR;NewPing SonarFML;NewPing SonarFMR;

int threshold_distance;

public:Motor leftMotor;Motor rightMotor;

int FL,FR,FML,FMR;boolean FL_b,FR_b,FML_b,FMR_b;

RobotCtrl(int thres_d);

/* MOVEMENT CTRLS */void goForward(int speed);void goForward(int speed, int duration);void goReverse(int speed);void goReverse(int speed, int duration);void turnLeft(int speed);void turnLeft(int speed, int duration);void turnRight(int speed);void turnRight(int speed, int duration);void stop();

/* SONAR CTRLS */void checkSonar();int getMinDistance();

;

#endif

Arduino Motor// Motor.h

#ifndef _MOTOR_h#define _MOTOR_h

#if defined(ARDUINO) && ARDUINO >= 100#include "arduino.h"

#else#include "WProgram.h"

#endif

class Motor protected:

int _directionPin;

Page 20: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

int _speedPin;int _brakePin;

public:void init(int directionPin, int speedPin, int brakePin);

void setForward();void setReverse();void setSpeed(int speed);void enableBrake();void disableBrake();

;

#endif

// // //

#include "Motor.h"

void Motor::init(int directionPin, int speedPin, int brakePin)

_directionPin = directionPin;_speedPin = speedPin;_brakePin = brakePin;

//enables the motor to go forwardvoid Motor::setForward()

digitalWrite(_directionPin, HIGH);

//enables the motor to go backwardsvoid Motor::setReverse()

digitalWrite(_directionPin, LOW);

//change speed of motorvoid Motor::setSpeed(int speed)

if(speed > 255) speed = 255; //protect out of range valueselse if(speed < 0) speed = 0;

analogWrite(_speedPin,speed);

//enable the brake on the motorvoid Motor::enableBrake()

digitalWrite(_brakePin,HIGH);

//disable the brake on the motorvoid Motor::disableBrake()

Page 21: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

digitalWrite(_brakePin,LOW);

Teensy Pulseconst int pin = 3;

void setup()

pinMode(pin,OUTPUT);

void loop()

tone(pin,4620,500);

delay(1000);

OpenCV Codeimport imutils

import numpy as np

import serial

import cv2

from time import sleep

cap = cv2.VideoCapture(0)

ser = serial.Serial('/dev/ttyACM0', baudrate=115200, bytesize=8, parity='N',stopbits = 1)

ser.write('r')

while(True):

ret, frame = cap.read()

Page 22: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

#do some preproccessing of the image

frame = imutils.resize(frame, width=600)

#convert image to hsv color format

hsv = cv2.cvtColor(frame, cv2.COLOR_BGR2HSV)

#specify the color range

lower_red = np.array([5,100,100])

upper_red = np.array([20,255,255])

#get image with only the specified color range showing

mask = cv2.inRange(hsv, lower_red, upper_red)

mask = cv2.erode(mask,None,iterations=2)

mask = cv2.dilate(mask,None,iterations=2)

res = cv2.bitwise_and(frame,frame,mask=mask)

#get contours from the color mask

cnts = cv2.findContours(mask.copy(), cv2.RETR_TREE,cv2.CHAIN_APPROX_SIMPLE)[-2]

if cnts:

#get the countour with the largest area

cnt = max(cnts, key = cv2.contourArea)

#get the rectange bounding box

rect = cv2.minAreaRect(cnt)

box = cv2.boxPoints(rect)

Page 23: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

box = np.int0(box)

#draw the bounding box on the frame

cv2.drawContours(frame,[box],0,(0,0,255),2)

#get the center x position

M = cv2.moments(cnt);

cx = int(M['m10']/M['m00']);

#print(cx);

area = cv2.contourArea(cnt)

#print(area)

if area > 2000:

if cx > 363:

ser.write('r')

print("Go Right")

elif cx < 182:

ser.write('l')

print("Go Left")

else:

ser.write('f')

print("Go Forward")

else:

ser.write('0')

else:

Page 24: BeerBot  · Web view2015. 12. 10. · The Raspberry Pi communicates with the Arduino through a serial connection. Ultrasonic Distance Sensors. Four ultrasonic distance sensors are

ser.write('0')

#cv2.imshow('frame',frame)

#cv2.imshow('mask',mask)

#cv2.imshow('res',res)

#k = cv2.waitKey(5) & 0xFF

#if k == 27:

#break

cv2.destroyAllWindows()

cap.release()

cv2.destroyAllWindows()