FollowMe Dog

/media/uploads/dshah80/group.png

Conor Culhane, Darshan Shah, Nzinga Eduardo, Curtis Ezell.

Meet FollowMe, your next robot companion that you can’t leave behind.

/media/uploads/dshah80/1214171058.jpg

/media/uploads/dshah80/projdes.png

The Alexa operated FollowMe can be controlled via three distinct modes; /media/uploads/dshah80/modes.png

Sonar

The two ultrasonic Sonar sensor's receivers are covered with electrical tape over the transmit cans to prevent their own signal from transmitting upon doing the 10 micro second trigger square wave process. This allows us to constantly listen for the sonar transmitter beacon coming from the user who holds the transmitter device.

Sonar transmitter had it’s sonar receive can desoldered to inspect the assembly of the can. The can of the sonar transmit was shortened to effectively widened the beam of transmission so that our transmission signal spreads out the sides as well as behind the user. This allows the robot to receive a relative signal regardless of the orientation of the sonar sensor.

/media/uploads/dshah80/sonar.png

Bluetooth Mode

/media/uploads/dshah80/bluetooth.jpg (Photo from Adafruit)

A master/slave relationship is created between the BLE module and an iPhone via the control pad on the Bluefruit LE app. Upon receiving directional inputs and numerical inputs as shown in picture above, movement and various commands can be implemented. Currently, command value #1 disengages Bluetooth control, though more commands can be added for the remaining numbers based on the preferences of the users. The following provides an overview of the functionality of the robot based on the user input on the control pad.

Up arrow: Move forward.

Down arrow: Move backward.

Left arrow: counterclockwise robot spin

Right arrow: clockwise robot spin

1: Deactivate Bluetooth mode

Alexa Mode

Via internet connection with the ESP8266 WiFi chip, Alexa takes commands that are interpreted based on a custom lambda function. Upon receiving certain commands, Alexa sends RPC commands to the WiFi chip, that are then sent to the Mbed. In response to these RPC commands, the functions on the Mbed are triggered. For example, asking Alexa “Enable Bluetooth control” sends the command “/bluetooth/run”, which trigger Bluetooth controlled movement on the robot. The following are the responses of Alexa following the command by the user:

“Bark”- produces a dog bark

“Scream”- plays R2D2 noise

“Enable Sonar”- starts the Sonar Beacon mode

“Enable Bluetooth”- uses the bluetooth app for movement

Parts List

1) LPC1768 mbed microcontrollers (3) /media/uploads/dshah80/mbed.jpg

2) HC-SR04 ultrasonic receiving sensors (2)

/media/uploads/dshah80/reccccc.png

3) HC-SR04 ultrasonic transmitting sensor(1)

/media/uploads/dshah80/transsss.png

4) TB6612FNG Sparkfun Motors Driver - Dual Breakout

/media/uploads/dshah80/h.png

5) Sparkfun Level Shifting microSD Breakout /media/uploads/dshah80/sd.jpg

6)TPA2005D1 Sparkfun Audio Amplifier Breakout

/media/uploads/dshah80/audioamp.jpg

7) PCB-Mount Speaker

/media/uploads/dshah80/speaker.jpg

8) External Power Supply (Sparkfun)

/media/uploads/dshah80/ext.jpg

9) Adafruit Bluetooth Low-Energy (BLE) breakout board /media/uploads/dshah80/blue.jpg

10)ESP8266 Wi Fi chip /media/uploads/dshah80/wifi.jpg

11) Amazon ECHO Dot

/media/uploads/dshah80/dot.png

12) Battery Holder - 4xAA to Barrel Jack Connector /media/uploads/dshah80/batteryholger.png

13) External Battery Phone Charger: 10400mAh Power Pack, 2.5A and 2.0A USB Ports, 2A input port /media/uploads/dshah80/1400mah.png

14) PRT 00119 2.1mm DC barrel power jack (2)

/media/uploads/dshah80/barelljack.png

15) 2A SPST toggle switch

/media/uploads/dshah80/toogle.png

16) 10K Trimpot potentiometer

/media/uploads/dshah80/pot.png

17) SparkFun Ardumoto Shield Kit

/media/uploads/dshah80/sheild.png

18) SparkFun Shadow Chassis

/media/uploads/dshah80/shadow.png

Demo Video

Pin Outs

/media/uploads/dshah80/piiinnn.png

/media/uploads/dshah80/pinnout2.png

Pictures

Top view of the robot showing the connection on the Mbed /media/uploads/dshah80/reciver.jpg

Side view of the robot /media/uploads/dshah80/fullrobotside.jpg

Picture of the transmitter circuit that is held by the user for Sonar mode /media/uploads/dshah80/transmiter.jpg

Code

Lambda Function

"""
This sample demonstrates a simple skill built with the Amazon Alexa Skills Kit.
The Intent Schema, Custom Slots, and Sample Utterances for this skill, as well
as testing instructions are located at http://amzn.to/1LzFrj6
 
For additional samples, visit the Alexa Skills Kit Getting Started guide at
http://amzn.to/1LGWsLG
"""
 
from __future__ import print_function
import socket
HOST = '76.17.115.1'    # The remote host
PORT = 1035              # The same port as used by the server
 
 
# --------------- Helpers that build all of the responses ----------------------
 
def build_speechlet_response(title, output, reprompt_text, should_end_session):
    return {
        'outputSpeech': {
            'type': 'PlainText',
            'text': output
        },
        'card': {
            'type': 'Simple',
            'title': "SessionSpeechlet - " + title,
            'content': "SessionSpeechlet - " + output
        },
        'reprompt': {
            'outputSpeech': {
                'type': 'PlainText',
                'text': reprompt_text
            }
        },
        'shouldEndSession': should_end_session
    }
 
 
def build_response(session_attributes, speechlet_response):
    return {
        'version': '1.0',
        'sessionAttributes': session_attributes,
        'response': speechlet_response
    }
 
 
# --------------- Functions that control the skill's behavior ------------------
 
def get_welcome_response():
    """ If we wanted to initialize the session to have some attributes we could
    add those here
    """
 
    session_attributes = {}
    card_title = "Welcome"
    speech_output = "hello"
    # If the user either does not reply to the welcome message or says something
    # that is not understood, they will be prompted again with this text.
    reprompt_text = "Please tell me your command.  For example, say enable app control"
    should_end_session = False
    return build_response(session_attributes, build_speechlet_response(
        card_title, speech_output, reprompt_text, should_end_session))
 
 
def handle_session_end_request():
    card_title = "Session Ended"
    speech_output = "goodbye!"
    # Setting this to true ends the session and exits the skill.
    should_end_session = True
    return build_response({}, build_speechlet_response(
        card_title, speech_output, None, should_end_session))
 
"""
def create_command_attributes(command):
    return {"command": command}
"""
def BluetoothFunction(intent, session):
 
    card_title = intent['name']
    session_attributes = {}
    should_end_session = False
    s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
    s.connect((HOST, PORT))
    msg = '/bluetooth/run'
    msg = str(unichr(48+len(msg))) + msg
    s.sendall(msg)
    payload = s.recv(1024)
    s.close()
    speech_output = "Ok. I will enable bluetooth app control." 
    reprompt_text = "I'm bored. Give me something to do."
    return build_response(session_attributes, build_speechlet_response(
        card_title, speech_output, reprompt_text, should_end_session))
		
def SonarFunction(intent, session):
 
    card_title = intent['name']
    session_attributes = {}
    should_end_session = False
    s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
    s.connect((HOST, PORT))
    msg = '/sonar/run'
    msg = str(unichr(48+len(msg))) + msg
    s.sendall(msg)
    payload = s.recv(1024)
    s.close()
    speech_output = "Ok. I will follow the sonar beacon!" 
    reprompt_text = "I'm bored. Give me something to do."
    return build_response(session_attributes, build_speechlet_response(
        card_title, speech_output, reprompt_text, should_end_session))
		
def BarkFunction(intent, session):
 
    card_title = intent['name']
    session_attributes = {}
    should_end_session = False
    s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
    s.connect((HOST, PORT))
    msg = '/bark/run'
    msg = str(unichr(48+len(msg))) + msg
    s.sendall(msg)
    payload = s.recv(1024)
    s.close()
    speech_output = "Ok. I will make the robot bark." 
    reprompt_text = "I'm bored. Give me something to do."
    return build_response(session_attributes, build_speechlet_response(
        card_title, speech_output, reprompt_text, should_end_session))		
		
def GrowlFunction(intent, session):
 
    card_title = intent['name']
    session_attributes = {}
    should_end_session = False
    s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
    s.connect((HOST, PORT))
    msg = '/growl/run'
    msg = str(unichr(48+len(msg))) + msg
    s.sendall(msg)
    payload = s.recv(1024)
    s.close()
    speech_output = "Ok. I will make the robot growl." 
    reprompt_text = "I'm bored. Give me something to do."
    return build_response(session_attributes, build_speechlet_response(
        card_title, speech_output, reprompt_text, should_end_session))	

def TailFunction(intent, session):
 
    card_title = intent['name']
    session_attributes = {}
    should_end_session = False
    s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
    s.connect((HOST, PORT))
    msg = '/tail/run'
    msg = str(unichr(48+len(msg))) + msg
    s.sendall(msg)
    payload = s.recv(1024)
    s.close()
    speech_output = "Ok. I will make the robot dance." 
    reprompt_text = "I'm bored. Give me something to do."
    return build_response(session_attributes, build_speechlet_response(
        card_title, speech_output, reprompt_text, should_end_session))	
        
def StopFunction(intent, session):
 
    card_title = intent['name']
    session_attributes = {}
    should_end_session = False
    s = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
    s.connect((HOST, PORT))
    msg = '/stop/run'
    msg = str(unichr(48+len(msg))) + msg
    s.sendall(msg)
    payload = s.recv(1024)
    s.close()
    speech_output = "Ok. I will stop the robot" 
    reprompt_text = "I'm bored. Give me something to do."
    return build_response(session_attributes, build_speechlet_response(
        card_title, speech_output, reprompt_text, should_end_session))
 
# --------------- Events ------------------
 
def on_session_started(session_started_request, session):
    """ Called when the session starts """
 
    print("on_session_started requestId=" + session_started_request['requestId']
          + ", sessionId=" + session['sessionId'])
 
 
def on_launch(launch_request, session):
    """ Called when the user launches the skill without specifying what they
    want
    """
 
    print("on_launch requestId=" + launch_request['requestId'] +
          ", sessionId=" + session['sessionId'])
    # Dispatch to your skill's launch
    return get_welcome_response()
 
 
def on_intent(intent_request, session):
    """ Called when the user specifies an intent for this skill """
 
    print("on_intent requestId=" + intent_request['requestId'] +
          ", sessionId=" + session['sessionId'])
 
    intent = intent_request['intent']
    intent_name = intent_request['intent']['name']
 
    # Dispatch to your skill's intent handlers
    if intent_name == "Bluetooth_Intent":
        return BluetoothFunction(intent, session)
    elif intent_name == "Sonar_Intent":
        return SonarFunction(intent, session)
    elif intent_name == "Bark_Intent":
        return BarkFunction(intent, session)
    elif intent_name == "Growl_Intent":
        return GrowlFunction(intent, session)
    elif intent_name == "Tail_Intent":
        return StopFunction(intent, session)
    elif intent_name == "Stop_Intent":
        return TailFunction(intent, session)
    elif intent_name == "AMAZON.HelpIntent":
        return get_welcome_response()
    elif intent_name == "AMAZON.CancelIntent" or intent_name == "AMAZON.StopIntent":
        return handle_session_end_request()
    else:
        raise ValueError("Invalid intent")
 
 
def on_session_ended(session_ended_request, session):
    """ Called when the user ends the session.
 
    Is not called when the skill returns should_end_session=true
    """
    print("on_session_ended requestId=" + session_ended_request['requestId'] +
          ", sessionId=" + session['sessionId'])
    # add cleanup logic here
 
 
# --------------- Main handler ------------------
 
def lambda_handler(event, context):
    """ Route the incoming request based on type (LaunchRequest, IntentRequest,
    etc.) The JSON body of the request is provided in the event parameter.
    """
    print("event.session.application.applicationId=" +
          event['session']['application']['applicationId'])
 
    """
    Uncomment this if statement and populate with your skill's application ID to
    prevent someone else from configuring a skill that sends requests to this
    function.
    """
    # if (event['session']['application']['applicationId'] !=
    #         "amzn1.echo-sdk-ams.app.[unique-value-here]"):
    #     raise ValueError("Invalid Application ID")
 
    if event['session']['new']:
        on_session_started({'requestId': event['request']['requestId']},
                           event['session'])
 
    if event['request']['type'] == "LaunchRequest":
        return on_launch(event['request'], event['session'])
    elif event['request']['type'] == "IntentRequest":
        return on_intent(event['request'], event['session'])
    elif event['request']['type'] == "SessionEndedRequest":
        return on_session_ended(event['request'], event['session'])

Intent Schema

{
  "intents": [
    {
      "intent": "AMAZON.CancelIntent"
    },
    {
      "intent": "AMAZON.HelpIntent"
    },
    {
      "intent": "AMAZON.StopIntent"
    },
    {
      "intent": "Bark_Intent"
    },
    {
      "intent": "Bluetooth_Intent"
    },
    {
      "intent": "Growl_Intent"
    },
    {
      "intent": "Sonar_Intent"
    },
    {
      "intent": "Stop_Intent"
    },
    {
      "intent": "Tail_Intent"
    }
  ]
}

Sample utterances

Bark_Intent Bark
Bluetooth_Intent Enable Bluetooth mode
Bluetooth_Intent Enable App Mode
Bluetooth_Intent Connect to my phone
Bluetooth_Intent Activate Bluetooth mode
Growl_Intent Growl
Sonar_Intent Activate Sonar mode
Sonar_Intent Follow me
Sonar_Intent Enable Sonar mode
Sonar_Intent Start Sonar
Tail_Intent Dance
Stop_Intent Stop Robot
Stop_Intent Stop Movement
Stop_Intent Freeze

WiFi BLE Movement

#include "mbed.h"
#include "Motor.h"
#include "wave_player.h"
#include "PinDetect.h"
#include "Servo.h"



InterruptIn  echoLeft(p15); //trigger pin on Left Sonar
InterruptIn  echoRight(p16); //trigger pin on Right Sonar
DigitalOut trigger(p17); //shared sonar trigger
Motor  left_motor(p21, p6, p5); // pwm, fwd, rev, has brake feature
Motor right_motor(p22, p8, p7); // pwm, fwd, rev, has brake feature

Servo myservo(p24);

DigitalOut led1(LED1);
DigitalOut led4(LED4);

BusOut myled(LED1, LED2, LED3, LED4);
//SDFileSystem sd(p11, p12, p13, p5, "sd");      // SD Card


Serial blue(p9, p10);
Serial blue2(p28, p27);

RawSerial  pc(USBTX, USBRX);


Timer        leftTimer;
Timer        rightTimer;
volatile bool left_interrupted = false;
volatile bool right_interrupted = false;
volatile bool Blue_mode = false;

int diff_r = 0;
int abs_diff_r = 0;
float left_motor_speed = 0.0;
float right_motor_speed = 0.0;
volatile int mode = 2;
float range = 0.0010;
float position = 0.5;


//======================================================
//=================== SONAR FUNCTIONS ==================
//======================================================
void echoLeftFunction()
{
    left_interrupted = true;
    leftTimer.stop(); //stop timer on left sensor
}

void echoRightFunction()
{
    right_interrupted = true;
    rightTimer.stop(); //stop timer on right sensor
}


void Cereal()

{
    while (blue.readable()) {
        char myChar = blue.getc(); //pull the character

        switch (myChar) {
            case 'W' :
                mode = 1;
                //pc.printf("YOU DID IT1!");
                break;
            case 'X' :
                left_motor.speed(0);
                right_motor.speed(0);
                mode = 2;
                //pc.printf("YOU DID IT2!");
                break;
            case 'Y' :

                mode = 3;
                //pc.printf("YOU DID IT3!");
                break;
            case 'Z' :

                mode = 0;
                //pc.printf("YOU DID IT4!");
                break;

        }
    }
}



void Stop_Function()
{
    while (mode == 0)

    {


        left_motor.speed(0);
        right_motor.speed(0);


        Cereal();
    }


}

void sonarFunction()
{
    while (mode == 1)

    {
        //pc.printf("ahhhhhhhhhhhhhhh");
        //reset the timers.
        leftTimer.reset();
        rightTimer.reset();

        //reset the l/r sonar interrupted flags
        left_interrupted = false;
        right_interrupted = false;

        //start the l/r sonar timers
        leftTimer.start();
        rightTimer.start();

        //send the special 10us square pulse to start listening on sonars
        trigger = 1;
        wait_us(10.0); //need a real system wait, because we need EXACTLY 10us
        trigger = 0;

        while (!(right_interrupted && left_interrupted)) {
            //do nothing, just spinning here
            //printf("spinning\n\r");  //uncomment this to see that since this thread has highest priority, it's never interrupted
        }

        //we now have both timers stopped..
        diff_r = leftTimer.read_us() - rightTimer.read_us(); //if diff_r positive, then source is on the right
        abs_diff_r = abs(diff_r);

        printf("diff_r = %d    left = %d    right = %d\n\r",diff_r, leftTimer.read_us(), rightTimer.read_us());

        //+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
        //++ Now, decide the motor speeds left_motor_speed and right_motor_speed ++
        //+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++

        if (abs_diff_r > 2000) {
            //ONLY ONE sonar sees the ping.. quickly and accurately rotate in place.
            if (diff_r > 0) {
                //SOURCE IS FAR RIGHT
                left_motor_speed = 0.5;
                right_motor_speed = -0.5;
            } else {
                //SOURCE IS FAR LEFT
                left_motor_speed = -0.5;
                right_motor_speed = 0.5;
            }
        } else if (abs_diff_r > 600) {
            //NO sonars see the ping.. slowly rotate in place... trying to find source.
            left_motor_speed = 0.6;
            right_motor_speed = -0.6;
        } else {
            //BOTH sonars see the ping.
            if (abs_diff_r < 30) {
                //SOURCE IN MIDDLE - drive straight
                left_motor_speed = 1;
                right_motor_speed = 1;
            } else {
                if (diff_r < 0) {
                    //=== SOURCE ON RIGHT ===
                    if (abs_diff_r < 100) {
                        //turn just a little to the right..
                        left_motor_speed = 1.0;
                        right_motor_speed = 0.8;
                    } else if (abs_diff_r < 200) {
                        //turn more to the right..
                        left_motor_speed = 1.0;
                        right_motor_speed = 0.7;
                    } else if (abs_diff_r < 300) {
                        //turn alot to the right..
                        left_motor_speed = 1.0;
                        right_motor_speed = 0.6;
                    } else if (abs_diff_r < 400) {
                        left_motor_speed = 1.0;
                        right_motor_speed = 0.5;
                    } else if (abs_diff_r < 500) {
                        left_motor_speed = 1.0;
                        right_motor_speed = 0.4;
                    }
                } else {
                    //=== SOURCE ON LEFT ===
                    if (abs_diff_r < 100) {
                        //turn just a little to the left..
                        left_motor_speed = 0.8;
                        right_motor_speed = 1.0;
                    } else if (abs_diff_r < 200) {
                        //turn more to the right..
                        left_motor_speed = 0.7;
                        right_motor_speed = 1.0;
                    } else if (abs_diff_r < 300) {
                        //turn alot to the right..
                        left_motor_speed = 0.6;
                        right_motor_speed = 1.0;
                    } else if (abs_diff_r < 400) {
                        left_motor_speed = 0.5;
                        right_motor_speed = 1.0;
                    } else if (abs_diff_r < 500) {
                        left_motor_speed = 0.4;
                        right_motor_speed = 1.0;
                    }
                }
            }
        }

        //+++++++++++++++++++++++++++++
        //Now, set the motor speed to the values decided above.
        left_motor.speed(left_motor_speed);
        right_motor.speed(right_motor_speed);


        Cereal();
    }
}

void Bluetooth_control()

{

    char bnum = 0;
    char bhit = 0;
    while (mode == 2) {
        if (blue2.getc() == '!') {
            if (blue2.getc() == 'B') { //button data packet
                bnum = blue2.getc(); //button number
                bhit = blue2.getc(); //1=hit, 0=release
                if (blue2.getc() == char(~('!' + 'B' + bnum + bhit))) { //checksum OK?
                    myled = bnum - '0'; //current button number will appear on LEDs
                    switch (bnum) {
                        case '1': //number button 1
                            if (bhit == '1') {

                                //add hit code here
                                mode = 0;
//                                wave_file = fopen("/sd/train.wav", "r");
//                                waver.play(wave_file);
//                                fclose(wave_file);
                            } else {
                                //add release code here
                            }
                            break;
                        case '2': //number button 2
                            if (bhit == '1') {
                                //add hit code here
                            } else {
                                //add release code here
                            }
                            break;
                        case '3': //number button 3
                            if (bhit == '1') {
                                //add hit code here
                            } else {
                                //add release code here
                            }
                            break;
                        case '4': //number button 4
                            if (bhit == '1') {
                                //add hit code here

                            } else {
                                //add release code here
                            }
                            break;
                        case '5': //button 5 up arrow
                            if (bhit == '1') {

                                left_motor.speed(1);
                                right_motor.speed(1);

                                //add hit code here
                            } else {

                                left_motor.speed(0);
                                right_motor.speed(0);
                                //add release code here
                            }
                            break;
                        case '6': //button 6 down arrow
                            if (bhit == '1') {

                                left_motor.speed(-1);
                                right_motor.speed(-1);
                                //add hit code here
                            } else {
                                left_motor.speed(0);
                                right_motor.speed(0);
                                //add release code here
                            }
                            break;
                        case '7': //button 7 left arrow
                            if (bhit == '1') {
                                left_motor.speed(1);
                                right_motor.speed(-1);
                                //add hit code here
                            } else {
                                left_motor.speed(0);
                                right_motor.speed(0);
                                //add release code here
                            }
                            break;
                        case '8': //button 8 right arrow
                            if (bhit == '1') {
                                left_motor.speed(-1);
                                right_motor.speed(1);
                                //add hit code here
                            } else {
                                left_motor.speed(0);
                                right_motor.speed(0);
                                //add release code here
                            }
                            break;
                        default:
                            break;
                    }
                }
            }

        }



    }

    Cereal();
}

void Spin_Function()
{
    while (mode == 3)

    {


        left_motor.speed(-1);
        right_motor.speed(1);
        wait(1.5);
        left_motor.speed(0);
        right_motor.speed(0);


        for (position = 0.0; position <= 1.0; position += .5) {
            wait(.75);
            myservo = position;

        }
        wait(.75);
        myservo = .5;

        left_motor.speed(1);
        right_motor.speed(-1);
        wait(1.5);
        left_motor.speed(0);
        right_motor.speed(0);

        for (position = 0.0; position <= 1.0; position += .5) {
            wait(.75);
            myservo = position;

        }
        wait(.75);
        myservo = .5;

        Cereal();
    }


}



int main()
{

    //--- INITIALIZATION ---

    pc.baud(9600);
    blue.baud(9600);
        blue2.baud(9600);
    myservo.calibrate(range, 45.0);

    //interrupts
    echoLeft.fall(&echoLeftFunction);
    echoRight.fall(&echoRightFunction);


    while (1) {
        sonarFunction();
        Bluetooth_control();
        Spin_Function();
        Stop_Function();
        Cereal();
        // sleep();
    }

}

Mbed_Alexa

#include "mbed.h"
#include "mywifi.h"   // this includes function templates for wifi
#include "Motor.h"
#include "mbed_rpc.h"
#include "SDFileSystem.h"
#include "wave_player.h"

//hook up the audio amp according to this cookbook example
//https://os.mbed.com/users/4180_1/notebook/using-a-speaker-for-audio-output/

//pin declarations for the speaker and sd card 
SDFileSystem sd(p5, p6, p7, p8, "sd"); //SD card
AnalogOut DACout(p18); //analog out for the audio amp
wave_player waver(&DACout); //wave player attached to the analog output on p18

Serial pc(USBTX, USBRX); //SERIAL over USB to terminal tera-term
Serial esp(p9, p10); //SERIAL to the wifi chip 
Serial slave_mbed(p28,p27); //SERIAL to the secondary slave_mbed which does our motor controls p28 is a TX and p27 is a RX

char ssid[32] = "MortySmith"; //wifi network
char pwd[32] = "password1"; //wifi password
char port[32] = "1035"; // must be port forwarded
char timeout[32] = "28800"; // 28800 is max
volatile int tx_in=0;
volatile int tx_out=0;
volatile int rx_in=0;
volatile int rx_out=0;
const int buffer_size = 4095;
char tx_buffer[buffer_size+1];
char rx_buffer[buffer_size+1];
char cmdbuff[1024];
char rx_line[1024];


DigitalOut led1(LED1);
DigitalOut led2(LED2);
DigitalOut led3(LED3);
DigitalOut led4(LED4);

//====== RPC Call back service function templates =======
void bluetoothFunction(Arguments *in, Reply *out);
void sonarFunction(Arguments *in, Reply *out);
void barkFunction(Arguments *in, Reply *out);
void screamFunction(Arguments *in, Reply *out);
void tailFunction(Arguments *in, Reply *out);
void stopFunction(Arguments *in, Reply *out);

//===== RPCFunctions ========
RPCFunction RPCBluetoothFunction(&bluetoothFunction, "bluetooth"); 
RPCFunction RPCSonarFunction(&sonarFunction, "sonar"); 
RPCFunction RPCBarkFunction(&barkFunction, "bark"); 
RPCFunction RPCScreamFunction(&screamFunction, "scream"); 
RPCFunction RPCTailFunction(&tailFunction, "tail"); 
RPCFunction RPCStopFunction(&stopFunction, "stop");



//here, we are exporting the bluetoothFunction() as a rpc callable function with the name "bluetooth"
/*  
    RPC EXAMPLE CALL:
    https://os.mbed.com/cookbook/RPC-Interface-Library
    run the bluetoothFunction() by doing an rpc call =>    /bluetooth/run
*/



void bluetoothFunction(Arguments *in, Reply *out){
    bool writeable = slave_mbed.writeable(); //check if the slave is writeable
    while(!writeable){
        writeable = slave_mbed.writeable();  
    }
    slave_mbed.putc('X'); //put the character X for bluetooth mode
}


void sonarFunction(Arguments *in, Reply *out){
   
   bool writeable = slave_mbed.writeable(); //check if the slave is writeable
    while(!writeable){
        writeable = slave_mbed.writeable();  
    }
    slave_mbed.putc('W'); //put the character 'W' for sonar mode   
    
}


void barkFunction(Arguments *in, Reply *out){
    
    //disable interrupts
    NVIC_DisableIRQ(UART1_IRQn);
    
    FILE *wave_file;
    printf("\n\n\nHello, wave world!\n");
    wave_file=fopen("/sd/dogBark.wav","r");
    waver.play(wave_file);
    fclose(wave_file);
    
    //enable interrupts
    NVIC_EnableIRQ(UART1_IRQn);
    
}


void screamFunction(Arguments *in, Reply *out){
    
    //disable interrupts
    NVIC_DisableIRQ(UART1_IRQn);
    
    FILE *wave_file;
    printf("\n\n\nHello, wave world!\n");
    wave_file=fopen("/sd/r2d2.wav","r");
    waver.play(wave_file);
    fclose(wave_file);
    
    //enable interrupts
    NVIC_EnableIRQ(UART1_IRQn);
    
}



void tailFunction(Arguments *in, Reply *out){
    
    bool writeable = slave_mbed.writeable(); //check if the slave is writeable
    while(!writeable){
        writeable = slave_mbed.writeable();  
    }
    slave_mbed.putc('Y'); //put the character Y for dance function
    
}

void stopFunction(Arguments *in, Reply *out){
    
    bool writeable = slave_mbed.writeable(); //check if the slave is writeable
    while(!writeable){
        writeable = slave_mbed.writeable();  
    }
    slave_mbed.putc('Z'); //put the character Z for stop mode
}





int main() {
    
    //==== set baud rates for each serial device ====
    pc.baud(9600);
    esp.baud(9600);
    slave_mbed.baud(9600); //set baud rate for communicating with the slave_mbed over serial
    
    esp.attach(&Rx_interrupt, Serial::RxIrq);
    esp.attach(&Tx_interrupt, Serial::TxIrq);
    wait(5);
    
    led3 = 0;
    connectToNetwork(); //
    led3 = 1;
    char rpc_in[256];
    char rpc_out[256];
    
    
    while (1) {
        getReply();
        memset(&rpc_in[0], 0, sizeof(rpc_in));
        memset(&rpc_out[0], 0, sizeof(rpc_out));
        int length = (int)rx_line[3] - 48; // bytes 0 to 2 are trash; byte 3 is length of message
        if (length > 0 && length < 256) {
            for (int i = 0; i < length; i++) {
                rpc_in[i] = rx_line[i+4]; // bytes 4 to length+3 are the valid data
            }
            RPC::call(rpc_in, rpc_out);
        }
        // lambda function is event-triggered and non-persistent
        // after it terminates, we need to close the existing connection and start another one
        strcpy(cmdbuff, "srv:close()\r\n"); 
        sendCMD();
        wait(.5);
        getReply();
        strcpy(cmdbuff, "srv=net.createServer(net.TCP,");
        strcat(cmdbuff, timeout);
        strcat(cmdbuff, ")\r\n");
        sendCMD();
        wait(.5);
        getReply();
        strcpy(cmdbuff, "srv:listen(");
        strcat(cmdbuff, port);
        strcat(cmdbuff, ",function(conn)\r\n");
        sendCMD();
        wait(.5);
        getReply();
        strcpy(cmdbuff, "conn:on(\"receive\", function(conn, payload) \r\n");
        sendCMD();
        wait(.5);
        getReply();
        strcpy(cmdbuff, "conn:send('");
        strcat(cmdbuff, reportStatus());
        strcat(cmdbuff, "')\r\n");
        sendCMD();
        wait(.5);
        getReply();
        strcpy(cmdbuff, "print(payload)\r\n");
        sendCMD();
        wait(.5);
        getReply();
        strcpy(cmdbuff, "end)\r\n");
        sendCMD();
        wait(.5);
        getReply();
        strcpy(cmdbuff, "end)\r\n");
        sendCMD();
        wait(.5);
        getReply();
    }
    
}


/* WIFI FUNCTIONS */

void connectToNetwork() {
    pc.printf("# Resetting ESP\r\n");
    strcpy(cmdbuff,"node.restart()\r\n");
    sendCMD();
    wait(5);
    getReply();

    pc.printf("# Setting Mode\r\n");
    strcpy(cmdbuff, "wifi.setmode(wifi.STATION)\r\n");
    sendCMD();
    getReply();

    wait(2);
    pc.printf("# Connecting to AP\r\n");
    pc.printf("# ssid = %s\t\tpwd = %s\r\n", ssid, pwd);
    strcpy(cmdbuff, "wifi.sta.config(\"");
    strcat(cmdbuff, ssid);
    strcat(cmdbuff, "\",\"");
    strcat(cmdbuff, pwd);
    strcat(cmdbuff, "\")\r\n");
    sendCMD();
    getReply();

    wait(2);
    pc.printf("# Get IP Address\r\n");
    strcpy(cmdbuff, "print(wifi.sta.getip())\r\n");
    sendCMD();
    getReply();

    wait(2);
    pc.printf("# Get Connection Status\r\n");
    strcpy(cmdbuff, "print(wifi.sta.status())\r\n");
    sendCMD();
    getReply();

    wait(2);
    pc.printf("# Listen on Port\r\n");
    strcpy(cmdbuff, "srv=net.createServer(net.TCP,");
    strcat(cmdbuff, timeout);
    strcat(cmdbuff, ")\r\n");
    sendCMD();
    getReply();

    wait(2);
    strcpy(cmdbuff, "srv:listen(");
    strcat(cmdbuff, port);
    strcat(cmdbuff, ",function(conn)\r\n");
    sendCMD();
    getReply();

    wait(2);
    strcpy(cmdbuff, "conn:on(\"receive\", function(conn, payload) \r\n");
    sendCMD();
    getReply();

    wait(2);
    strcpy(cmdbuff, "conn:send('");
    strcat(cmdbuff, reportStatus());
    strcat(cmdbuff, "')\r\n");
    sendCMD();
    getReply();

    wait(2);
    strcpy(cmdbuff, "print(payload)\r\n");
    sendCMD();
    getReply();

    wait(2);
    strcpy(cmdbuff, "end)\r\n");
    sendCMD();
    getReply();

    wait(2);
    strcpy(cmdbuff, "end)\r\n");
    sendCMD();
    getReply();

    wait(2);
    pc.printf("# Ready\r\n");
}

void sendCMD()
{
    int i;
    char temp_char;
    bool empty;
    i = 0;
// Start Critical Section - don't interrupt while changing global buffer variables
    NVIC_DisableIRQ(UART1_IRQn);
    empty = (tx_in == tx_out);
    while ((i==0) || (cmdbuff[i-1] != '\n')) {
// Wait if buffer full
        if (((tx_in + 1) % buffer_size) == tx_out) {
// End Critical Section - need to let interrupt routine empty buffer by sending
            NVIC_EnableIRQ(UART1_IRQn);
            while (((tx_in + 1) % buffer_size) == tx_out) {
            }
// Start Critical Section - don't interrupt while changing global buffer variables
            NVIC_DisableIRQ(UART1_IRQn);
        }
        tx_buffer[tx_in] = cmdbuff[i];
        i++;
        tx_in = (tx_in + 1) % buffer_size;
    }
    if (esp.writeable() && (empty)) {
        temp_char = tx_buffer[tx_out];
        tx_out = (tx_out + 1) % buffer_size;
// Send first character to start tx interrupts, if stopped
        esp.putc(temp_char);
    }
// End Critical Section
    NVIC_EnableIRQ(UART1_IRQn);
    return;
}

// Read a line from the large rx buffer from rx interrupt routine
void getReply() {
    int i;
    i = 0;
// Start Critical Section - don't interrupt while changing global buffer variables
    NVIC_DisableIRQ(UART1_IRQn);
// Loop reading rx buffer characters until end of line character
    while ((i==0) || (rx_line[i-1] != '\r')) {
// Wait if buffer empty
        if (rx_in == rx_out) {
// End Critical Section - need to allow rx interrupt to get new characters for buffer
            NVIC_EnableIRQ(UART1_IRQn);
            while (rx_in == rx_out) {
            }
// Start Critical Section - don't interrupt while changing global buffer variables
            NVIC_DisableIRQ(UART1_IRQn);
        }
        rx_line[i] = rx_buffer[rx_out];
        i++;
        rx_out = (rx_out + 1) % buffer_size;
    }
// End Critical Section
    NVIC_EnableIRQ(UART1_IRQn);
    rx_line[i-1] = 0;
    return;
}

char* reportStatus() {
    char str[30];
    return str;
}

// Interupt Routine to read in data from serial port
void Rx_interrupt() {
// Loop just in case more than one character is in UART's receive FIFO buffer
// Stop if buffer full
    while ((esp.readable()) && (((rx_in + 1) % buffer_size) != rx_out)) {
        rx_buffer[rx_in] = esp.getc();
// Uncomment to Echo to USB serial to watch data flow
        pc.putc(rx_buffer[rx_in]);
        rx_in = (rx_in + 1) % buffer_size;
    }
    return;
}


// Interupt Routine to write out data to serial port
void Tx_interrupt() {
// Loop to fill more than one character in UART's transmit FIFO buffer
// Stop if buffer empty
    while ((esp.writeable()) && (tx_in != tx_out)) {
        esp.putc(tx_buffer[tx_out]);
        tx_out = (tx_out + 1) % buffer_size;
    }
    return;
}

Sonar transmitter button

#include "mbed.h"
 
DigitalOut trigger(p6);
DigitalOut myled1(LED1); //monitor trigger
DigitalOut myled2(LED2); //monitor echo
DigitalOut myled3(LED3); //monitor button works
DigitalIn  button(p8); //input button
DigitalIn  echo(p7);
 
int main(){
    while(1){
        myled3 = 1; //initially, our led is not working..
        while(button ==1) {
            myled3 = 0; //process is working
            // trigger sonar to send a ping
            trigger = 1;  //set trigger high
            myled1 = 1;  //turn on led for trigger (high)
            myled2 = 0;  //turn off led2 for echo low
            wait_us(10.0);
            trigger = 0;
            myled3 = 0;

            //wait(1);
            myled3 = 1; // process is done working turn off the led3.
        }
    }
}

Future work

In future, we will incorporate the usage of encoders for swift robot movement. Encoders will help the robot to move accurately in relatively straight line. Also, the robot will be modified to perform obstacle detection and distance detection. Currently the robot does not stop when it reaches the user. The team investigated Lidar sensors but it detected walls and decide to stop early before even reaching the user. So, in future design, the robot will have a precise stopping distance. Our sonar transmitter tends to bounce of walls and can cause stray interference, which causes the robot to drive into the walls. Adding more voice commands on Alexa ECHO bot could also be improved. Lastly, we will add a camera to record video of the user and prepare a mobile application to watch it.


1 comment on FollowMe Dog:

27 Dec 2017

Good job Darshan!

Please log in to post comments.