« Observation Assignment - Part 2 | Main | Getting info from Google in Processing »

Ultrasonic scanner v.4

Finally got to version 4 of the ultrasonic sonar scanner!

This one now has fully functioning comms between the Arduino microcontroller and a Processing program working on the laptop.

There are some minor glitches: servomotor motion is somewhat jerky (possibly a data rate issue) [fixed!], sensor readings lag somewhat, readings are sometimes a bit erratic. I understand that it may be possible to improve quality of the readings by decoupling the signal line, using a capacitor.

Next big step: analyzing transitions & changes in the sensor data in order to trigger MIDI (sound) events.

Keep reading for source code of the Processing and Arduino projects.

===================================================
The Arduino program
===================================================

/*
Rangefinder control v2
Gian Pablo Villamil
October 10, 2006

This program waits for a signal from processing to move to an angle, then returns a
rangefinder reading at that angle.

Key points:
use long for lastPulse
use Serial.available before every read
problem with scaling function (scale in processing)

*/

int servoPin = 9; // Control pin for servo motor
int minPulse = 500; // Minimum servo position
int maxPulse = 2500; // Maximum servo position
int pulse = 0; // Amount to pulse the servo

long lastPulse = 0; // the time in milliseconds of the last pulse
int refreshTime = 20; // the time needed in between pulses

int analogValue = 0; // the value returned from the analog sensor
int analogPin = 0; // the analog pin that the sensor's on

int rangeFinderValue = 0;
int rangeFinderPin = 1;

int servoAngle = 0;
byte incomingByte ;
byte done ;

int scale(int inputValue, int inputMin, int inputMax, int outputMin, int outputMax);
void moveServoTo(int angle) ;
void returnReading() ;

void setup() {
pinMode(servoPin, OUTPUT); // Set servo pin as an output pin
pulse = minPulse; // Set the motor position value to the minimum
Serial.begin(9600);
servoAngle = 0;
lastPulse = millis();
}

void loop() {
if (Serial.available()) { // message available?
incomingByte = Serial.read();
switch (incomingByte) { // what is it?
case 'a':
// set servo angle and get reading
servoAngle = 0;
bytesReceived = 0;
done = false;
while (!done) {
if (Serial.available()) {
incomingByte = Serial.read();
if (incomingByte >= 48 && incomingByte <= 57) { // it's a number
servoAngle = servoAngle * 10 + (incomingByte - 48);
}
else {
done = true; // or else we're done
};
}
};
pulse = (servoAngle * 19) / 10 + minPulse;
moveServoTo(pulse); // move the motor
returnReading(); // return the reading
break; // Break from the switch
case 'i':
// set minimum
Serial.println("minimum");
break;
case 'o':
// set maximum
Serial.println("maximum");
break;
}
while (Serial.available()) {
incomingByte = Serial.read(); // clear the buffer
};

}

// if nothing else happened, refresh the servo

if (millis() - lastPulse >= refreshTime) {
moveServoTo(pulse);
lastPulse = millis(); // save the time of the last pulse
}
}

void moveServoTo(int pulse) {
digitalWrite(servoPin, HIGH); // Turn the motor on
delayMicroseconds(pulse); // Length of the pulse sets the motor position
digitalWrite(servoPin, LOW); // Turn the motor off
}

void returnReading() {
rangeFinderValue = analogRead(rangeFinderPin);
Serial.print("r"); // we are returning a reading
Serial.print(rangeFinderValue, DEC); // send the reading
Serial.println(); // send a carriage return
}

int scale(int inputValue, int inputMin, int inputMax, int outputMin, int outputMax) {
return ((outputMax-outputMin)*(inputValue-inputMin)/(inputMax-inputMin)+outputMin);
}


===================================================
The Processing program
===================================================
import processing.serial.*;
import processing.opengl.*;

/* Sonarscan v4

Enhanced version of sonar scan, with better support for sweeping back and forth.

Major change from v2.0 - got rid of the Trails array completely, now using alpha rect
to achieve trail fading.

Major change from v3.0 - now actually turning the motor and reading the sensor.

Gian Pablo Villamil
October 10, 2006

*/

// constants

int motorMin = 100;
int motorMax = 900;

int angleMin = 0;
int angleMax = 127;

int numReadings = 128;
int numTrails = 255;

int distanceMin = 0;
int distanceMax = 0;

int sensorMin = 0;
int sensorMax = 255;

float ONE_AND_HALF_PI = PI + HALF_PI ;

// variables

int sweepMin = angleMin;
int sweepMax = angleMax;

int currentTrail = 0;
int sweepDir = 1;

Reading[] roomReadings = new Reading[numReadings];

int i;

// interface stuff

Serial serialPort;

void setup() {
// size(screen.width, screen.height, OPENGL);

size(640, 480, OPENGL);
frameRate(60);
smooth();
background(0,0,0);
strokeWeight(3);
distanceMax = width/2;

// check the serial ports

println(Serial.list());

serialPort = new Serial(this, "COM4", 9600);

// setup the room & trail arrays

for (i = 0; i < numReadings; i++) {
roomReadings[i] = new Reading();
}
i = 0;
println("finished setup");
}

void draw() {
fill(0,1);
noStroke();
rect(0,0,width,height);
translate(width/2,height);

roomReadings[i].current = GetReadings(i);
DrawTrail ();
roomReadings[i].previous = roomReadings[i].current;

i = i + sweepDir ;
if (i > sweepMax) {
sweepDir = -sweepDir;
i = sweepMax;
}
if (i < sweepMin) {
sweepDir = -sweepDir;
i = sweepMin;
}
}

// Get sensor reading for an angle, store the value in the roomReadings array and in the
// Trail array.

int GetReadings (int angle) {
int bytesReceived = 0;
int returnValue = 0;
int motorAngle = scaleInteger(angle,angleMin,angleMax,motorMin,motorMax);
int incomingByte;
String motorString = str(motorAngle);
// println("sent a"+motorString);
serialPort.write("a");
serialPort.write(motorString);
serialPort.write("\r");
boolean done = false;

while (serialPort.available() == 0) {
}; // wait for something to come back
incomingByte = serialPort.read();
if (incomingByte == 114){ // we are receiving a reading
while (!done) {
if (serialPort.available()>0){
incomingByte = serialPort.read();
if (incomingByte >= 48 && incomingByte <= 57) { // it's a number
returnValue = returnValue * 10 + (incomingByte - 48);
}
else {
done = true; // or else we're done
}
}
}
while (serialPort.available()>0) {
incomingByte = serialPort.read(); // clear the buffer
}
}
// println("got back " + returnValue);
return returnValue;

}

// Draw the sweep

void DrawTrail () {
float lineAngle ;
float lineDistance ;

lineAngle = scaleFloat(i, angleMin, angleMax, HALF_PI,ONE_AND_HALF_PI);
lineDistance = scaleInteger(roomReadings[i].current, sensorMin, sensorMax, 0, distanceMax);

if (roomReadings[i].current >= roomReadings[i].previous) {
stroke(0,255,0);
}
else {
stroke(255,255,0);
}
strokeWeight(3);

pushMatrix();
rotate(lineAngle);
line(0,0,0,lineDistance);
popMatrix();
}


// general purpose scaling function for float return

float scaleFloat(int inputValue, float inputMin, float inputMax, float outputMin, float outputMax) {
return ((outputMax-outputMin)*(inputValue-inputMin)/(inputMax-inputMin)+outputMin);
}

// general purpose scaling function for integer return

int scaleInteger(int inputValue, int inputMin, int inputMax, int outputMin, int outputMax) {
return ((outputMax-outputMin)*(inputValue-inputMin)/(inputMax-inputMin)+outputMin);
}

TrackBack

TrackBack URL for this entry:
http://itp.nyu.edu/~gpv206/cgi-bin/mt/mt-tb.cgi/25

Post a comment

(If you haven't left a comment here before, you may need to be approved by the site owner before your comment will appear. Until then, it won't appear on the entry. Thanks for waiting.)