...

Vector


Vector:

Vision Enabled Cellphone Tricycle Oriented Robot

#include <Servo.h>

const byte MOTOR_PORT = 11; // port to drive motor (pwm)
const byte SERVO_PORT = 9; // port to drive servo
const int SERVO_MIN = 700;
const int SERVO_MAX = 2400;
char commandValue = '\0';// holds the command code, sent over serial
int dataValue = 0;// holds the data, sent over serial
Servo servo1;

//
void setup() {
    Serial.begin(9600);
    // setup pins for output
    pinMode(MOTOR_PORT, OUTPUT);
    // using a HS422 servo, was able to get 180 deg.
    // might have to tweak SERVO_MIN, SERVO_MAX to get proper rotation.
    servo1.attach(SERVO_PORT, SERVO_MIN, SERVO_MAX);
}

//
void loop() {
    // priority is for commands coming over serial
    if (Serial.available()) {
        char incomingChar = Serial.read();
        if ('\n' == incomingChar) { // eol recvd, so process command and value collected so far
            processCommand(commandValue, dataValue);
            Serial.print("(");Serial.print(commandValue);Serial.print(dataValue);
            Serial.println(") ok >");// reply back to calling device
            commandValue = '\0'; // reset
            dataValue = 0; // reset
        } else if (isDigit(incomingChar)) {
            dataValue = (dataValue * 10) + (incomingChar - '0'); // accumulate the data value
        } else { // non-digit, so consider as a command code
            commandValue = incomingChar; // set the current command
        }
    }
}

//
void processCommand(char commandValue, int dataValue) {
    if ('m' == commandValue) {// set motor speed
        analogWrite(MOTOR_PORT, normalize(dataValue, 0, 255));
    } else if ('s' == commandValue) {// set steering servo position
        servo1.write(normalize(dataValue, 0, 180));
    }
}

// returns true if 'digit' represents an ascii digit between 0 and 9
boolean isDigit (char digit) {
    return (digit >= '0' && digit <= '9');
}

// chops off valueToNormalize to be between minValue and maxValue
int normalize(int valueToNormalize, int minValue, int maxValue) {
    if (valueToNormalize < minValue)
        return minValue;
    else if (valueToNormalize > maxValue)
        return maxValue; 
    else 
        return valueToNormalize;
}








#!/usr/bin/python

from bluetooth import *
server_address = "00:12:05:11:90:32"
port = 1

print "connecting to \"%s\" on %s" % (server_address, port)

sock = BluetoothSocket( RFCOMM )
sock.connect((server_address, port))

print "connected.  ready for input..."

while True:
    data = raw_input() # read stdin, stripping the trailing newline
    if data == 'x':
        break
    data = data + '\n'
    print 'sending', data
    sock.send(data)
sock.close()