<font face="Verdana">
//3rd version
#include <Servo.h>
#include "SPI.h"
#include <LiquidCrystal_I2C.h>
#include <Wire.h>
#define GPIO_MOT_LEFT_EN 5
#define GPIO_MOT_RIGHT_EN 6
#define GPIO_MOT_LEFT_DIR 4
#define GPIO_MOT_RIGHT_DIR 7
#define GPIO_SENSOR_SERVO 8
#define GPIO_BUZZER 3
#define GPIO_KEY A7
#define GPIO_LED 13
#define NAVI_DISTANCE_K 0.04
#define NAVI_MOT_PULSEWIDTH 100
#define IDLE_L 127
#define IDLE_R 127
#define SCAN_STARTPOS 50
#define SCAN_ENDPOS 130
#define SCAN_CENTER 90
#define CONTROL_KP 3
#define CONTROL_RUNSPEED 60
#define CONTROL_TURNSPEED 50
#define NAVI_TURNTHRE 6
#define SIGNAL_COIN 20000
#define SERVO_SLPTIME 3
#define SCAN_SLPTIME 50
const int CSB = 10;
//Hardware driver
Servo ScannerArm;
LiquidCrystal_I2C lcd(0x27,16,2);
void SetMotorDuty(byte L,byte R) {
analogWrite(GPIO_MOT_LEFT_EN,L);
analogWrite(GPIO_MOT_RIGHT_EN,R);
}
void Motor_Crank() {
digitalWrite(GPIO_MOT_LEFT_DIR,HIGH);
digitalWrite(GPIO_MOT_RIGHT_DIR,HIGH);
}
void Motor_Standby() {
digitalWrite(GPIO_MOT_LEFT_DIR,LOW);
digitalWrite(GPIO_MOT_RIGHT_DIR,LOW);
}
void GPIO_Init() {
pinMode(GPIO_MOT_LEFT_EN,OUTPUT);
pinMode(GPIO_MOT_RIGHT_EN,OUTPUT);
pinMode(GPIO_MOT_LEFT_DIR,OUTPUT);
pinMode(GPIO_MOT_RIGHT_DIR,OUTPUT);
pinMode(GPIO_BUZZER,OUTPUT);
pinMode(GPIO_LED,OUTPUT);
SetMotorDuty(0,0);
}
void Serial_LDCSensor_Init() {
unsigned int data = 0;
Serial.begin(9600);
// start SPI library/ activate BUS
SPI.begin();
pinMode(CSB, OUTPUT);
SPI.setBitOrder(MSBFIRST);
SPI.setDataMode(SPI_MODE0); // CPOL = 0 and CPH = 0 mode 3 also works
SPI.setClockDivider(SPI_CLOCK_DIV4); // set SCLK @ 4MHz, LDC1000 max is 4MHz DIV2 also works
// set power mode to idle to configure stuff
digitalWrite(CSB, LOW);
SPI.transfer(0x0B);
SPI.transfer(0x00);
digitalWrite(CSB, HIGH);
delay(100);
// Set RpMax
digitalWrite(CSB, LOW);
SPI.transfer(0x01);
SPI.transfer(0x0E);
digitalWrite(CSB, HIGH);
delay(100);
// Set RpMin
digitalWrite(CSB, LOW);
SPI.transfer(0x02);
SPI.transfer(0x3B);
digitalWrite(CSB, HIGH);
delay(100);
// Set Sensor frequency
digitalWrite(CSB, LOW);
SPI.transfer(0x03);
SPI.transfer(0x94);
digitalWrite(CSB, HIGH);
delay(100);
// Set LDC configurationn
digitalWrite(CSB, LOW);
SPI.transfer(0x04);
SPI.transfer(0x17);
digitalWrite(CSB, HIGH);
delay(100);
// Set clock configuration
digitalWrite(CSB, LOW);
SPI.transfer(0x05);
SPI.transfer(0x00);
digitalWrite(CSB, HIGH);
delay(100);
// disable all interrupt modes
digitalWrite(CSB, LOW);
SPI.transfer(0x0A);
SPI.transfer(0x00);
digitalWrite(CSB, HIGH);
// set thresh HiLSB value
digitalWrite(CSB, LOW);
SPI.transfer(0x06);
SPI.transfer(0x50);
digitalWrite(CSB, HIGH);
delay(100);
// set thresh HiMSB value
digitalWrite(CSB, LOW);
SPI.transfer(0x07);
SPI.transfer(0x14);
digitalWrite(CSB, HIGH);
delay(100);
// set thresh LoLSB value
digitalWrite(CSB, LOW);
SPI.transfer(0x08);
SPI.transfer(0xC0);
digitalWrite(CSB, HIGH);
delay(100);
// set thresh LoMSB value
digitalWrite(CSB, LOW);
SPI.transfer(0x09);
SPI.transfer(0x12);
digitalWrite(CSB, HIGH);
delay(100);
// set power mode to active mode
digitalWrite(CSB, LOW);
SPI.transfer(0x0B);
SPI.transfer(0x01);
digitalWrite(CSB, HIGH);
delay(100);
}
void Alarm(byte type) {
switch(type)
{
case 1:
tone(GPIO_BUZZER,1109,220);
delay(220);
tone(GPIO_BUZZER,1245,220);
delay(220);
tone(GPIO_BUZZER,1397,220);
delay(220);
noTone(GPIO_BUZZER);
break;
case 2:
tone(GPIO_BUZZER,1397,220);
delay(220);
tone(GPIO_BUZZER,1109,220);
delay(220);
tone(GPIO_BUZZER,1661,220);
delay(220);
noTone(GPIO_BUZZER);
break;
case 3:
tone(GPIO_BUZZER,1109,50);
delay(50);
noTone(GPIO_BUZZER);
break;
case 4:
tone(GPIO_BUZZER,1397,150);
delay(150);
tone(GPIO_BUZZER,1661,150);
delay(150);
tone(GPIO_BUZZER,2794,150);
delay(150);
tone(GPIO_BUZZER,2217,150);
delay(150);
tone(GPIO_BUZZER,2489,150);
delay(150);
tone(GPIO_BUZZER,3322,150);
delay(150);
}
}
void Servo_Init() {
ScannerArm.attach(GPIO_SENSOR_SERVO);
ScannerArm.write(90);
}
void Display_Init(){
lcd.init();
lcd.backlight();
//lcd.blink();
}
bool CoinFoundFlag = false;
int LDC_SingleScan() {
unsigned int val = 0;
unsigned int dataLSB = 0;
unsigned int dataMSB = 0;
unsigned int proximitydata = 0;
// Read proximity data LSB register
digitalWrite(CSB, LOW);
SPI.transfer(0xA1); // 0x80 + 0x21
dataLSB = SPI.transfer(0x00);
digitalWrite(CSB, HIGH);
delay(SERVO_SLPTIME);
// Read proximity data MSB register
digitalWrite(CSB, LOW);
SPI.transfer(0xA2); // 0x80 + 0x22
dataMSB = SPI.transfer(0x00);
digitalWrite(CSB, HIGH);
delay(SERVO_SLPTIME);
proximitydata = ((unsigned int)dataMSB << 8) | (dataLSB);// combine two registers to form 16bit resolution proximity data
if(proximitydata == 0) Alarm(3);
Serial.println(proximitydata);
// Serial.print("\t");
return proximitydata;
}
byte LDC_AutoScan() {
static signed char ScanDirection = 1;
int MaxSignalOnPos = 0;
int MaxSignal = 0;
int LDCReadBuf = 0;
int Start;
int End;
if(ScanDirection == 1)
{
Start = SCAN_STARTPOS;
End = SCAN_ENDPOS;
}
else
{
End = SCAN_STARTPOS;
Start = SCAN_ENDPOS;
}
for(int CurrentPos = Start ; CurrentPos != End ; CurrentPos += ScanDirection)
{
LDCReadBuf = LDC_SingleScan();
ScannerArm.write(CurrentPos);
if(LDCReadBuf > MaxSignal)
{
MaxSignal = LDCReadBuf;
MaxSignalOnPos = CurrentPos;
}
}
ScanDirection = -ScanDirection;
if(MaxSignal >= SIGNAL_COIN) {
Alarm(4);
CoinFoundFlag = true;
}
return MaxSignalOnPos;
}
int LDCValueMax = 1;
int LDCValueMin = 0;
void LDC_StartCalibration()
{
}
void LCD_Format() {
lcd.setCursor(0,0);
lcd.print("STATUS Dir= ");
lcd.setCursor(0,1);
lcd.print("Dst= Tim= ");
}
void LCD_ShowInfo(int dir,int dst,int time) {
lcd.setCursor(12,0);
lcd.print(dir);
lcd.setCursor(4,1);
lcd.print(dst);
lcd.setCursor(12,1);
lcd.print(time);
}
byte SpeedWidthLimit(int orig){
byte dest = orig;
if(orig >= 255) dest = 254;
if(orig <= 0 ) dest = 1;
return dest;
}
int Run_Time;
void setup() {
Serial_LDCSensor_Init();
GPIO_Init();
Servo_Init();
Display_Init();
lcd.setCursor(0,0);
lcd.print("Press any key");
lcd.setCursor(0,1);
lcd.print(" [PLL MODE]");
Alarm(1);
while(analogRead(GPIO_KEY) > 900);
Alarm(2);
delay(1000);
SetMotorDuty(IDLE_L,IDLE_R);
delay(1000);
Run_Time = millis() / 1000;
// while(1) LDC_SingleScan();
}
int Distance = 0;
void loop() {
int Duty_Left;
int Duty_Right;
int PeakAngle = LDC_AutoScan() - 90;
if(PeakAngle <= NAVI_TURNTHRE && PeakAngle >= -NAVI_TURNTHRE)
{
Duty_Left = IDLE_L + CONTROL_RUNSPEED + (CONTROL_KP * PeakAngle);
Duty_Right = IDLE_R + CONTROL_RUNSPEED - (CONTROL_KP * PeakAngle);
}
else
{
Duty_Left = IDLE_L + CONTROL_TURNSPEED + (CONTROL_KP * PeakAngle);
Duty_Right = IDLE_R + CONTROL_TURNSPEED - (CONTROL_KP * PeakAngle);
}
Motor_Crank();
if(CoinFoundFlag)
{
SetMotorDuty(IDLE_L + CONTROL_RUNSPEED + 20,IDLE_R + CONTROL_RUNSPEED + 20);
CoinFoundFlag = false;
}
else
{
SetMotorDuty(SpeedWidthLimit(Duty_Left),SpeedWidthLimit(Duty_Right));
}
Distance += NAVI_DISTANCE_K * CONTROL_RUNSPEED;
delay(NAVI_MOT_PULSEWIDTH);
SetMotorDuty(IDLE_L,IDLE_R);
LCD_Format();
LCD_ShowInfo(PeakAngle , Distance , millis() / 1000 - Run_Time);
Motor_Standby();
//Serial.println(LDC_AutoScan());
}
</font>