#include <Arduino.h>
#include <Wire.h>
#include <Servo.h>
#include "Adafruit_TCS34725.h"
Adafruit_TCS34725 tcs = Adafruit_TCS34725(TCS34725_INTEGRATIONTIME_50MS, TCS34725_GAIN_4X);
#define commonAnode true;
byte gammatable[256];
int flag = 0;
int r=0;
float colorMax[3];
int color = 0;
int precolor = 0;
int value;
int pos = 90;
void ____doRobotErgeh();
void ____doZuraasDagah();
void ____doZuraasTooloh();
void ____doMedregchiinUtga();
void ____doGulsuuraaDeeshluuleh();
void ____doBombogUnagaah();
void ____doUragshaaYvah();
void ____doBombogErguuleh();
void ____doZuunErgeh();
void ____doUhrah();
void ____doBaruunErgeh();
void ____doZogsoh();
void colorDetect();
double ___S;
double ___SData;
double ___HighSpeefd;
double ___MidlleSpeed;
double ___LowSpeed;
double ergeltiinHurd;
double ___BaruunHurd;
double ___ZuunHurd;
double ___SensorData;
double ___A;
double ___E;
double ___zuraastoologch;
double ___ErgehChiglel;
double ___pos1_1;
double ___pos1_2;
double ___pos3;
double ___pos2;
double timer;
int _input_Medregch4 = A3;
int _input_Medregch3 = A2;
int _input_Medregch2 = A1;
int _output_Motor1Hurd = 3;
int _input_Medregch1 = A0;
int _output_Motor2Hurd = 5;
Servo _servo_servo3;
int _output_Motor1Chiglel = 2;
Servo _servo_servo1;
Servo _servo_servo2;
int _output_Motor2Chiglel = 4;
void ____doRobotErgeh() {
___BaruunHurd = ergeltiinHurd;
___ZuunHurd = ergeltiinHurd;
if ( ___ErgehChiglel == 0 ) {
____doZuunErgeh();
} else {
____doBaruunErgeh();
}
while ( ___SensorData != 0 ) {
____doMedregchiinUtga();
___SensorData = ___SData;
}
if ( ___ErgehChiglel == 0 ) {
while ( ( ___SensorData != 6 ) && ( ___SensorData != 2 ) ) {
____doMedregchiinUtga();
___SensorData = ___SData;
}
} else {
while ( ( ___SensorData != 12 ) && ( ___SensorData != 6 ) ) {
____doMedregchiinUtga();
___SensorData = ___SData;
delay(40);
}
}
____doZogsoh();
delay(1);
}
void ____doZuraasDagah() {
___A = 0;
while ( ___A < ___zuraastoologch ) {
____doMedregchiinUtga();
____doZuraasTooloh();
if ( ___SData == 6 ) {
___BaruunHurd = ___HighSpeefd;
___ZuunHurd = ___HighSpeefd;
} else if ( ___SData == 8 ) {
___BaruunHurd = ___HighSpeefd;
___ZuunHurd = ___LowSpeed;
} else if ( ___SData == 12 ) {
___BaruunHurd = ___HighSpeefd;
___ZuunHurd = ___MidlleSpeed;
} else if ( ___SData == 4 ) {
___BaruunHurd = ___HighSpeefd;
___ZuunHurd = ___MidlleSpeed;
} else if ( ___SData == 1 ) {
___BaruunHurd = ___LowSpeed;
___ZuunHurd = ___HighSpeefd;
} else if ( ___SData == 3 ) {
___BaruunHurd = ___MidlleSpeed;
___ZuunHurd = ___HighSpeefd;
} else if ( ___SData == 2 ) {
___BaruunHurd = ___MidlleSpeed;
___ZuunHurd = ___HighSpeefd;
} else {
}
____doUragshaaYvah();
}
____doZogsoh();
delay(45);
___BaruunHurd = 80;
___ZuunHurd = 80;
____doUragshaaYvah();
delay(160); //tsagaan zuraas toolj zogsood uragshaa ywah hugatsaa
____doZogsoh();
}
void ____doZuraasTooloh() {
___SensorData = ___SData;
if ( ___SensorData == 15 ) {
if ( ___E == 0 ) {
___A = ___A + 1;
___E = 1;
}
} else {
___E = 0;
}
}
void ____doMedregchiinUtga() {
___S = 15;
if ( digitalRead(_input_Medregch1) == 0 ) {
___S = ___S - 8;
}
if ( digitalRead(_input_Medregch2) == 0 ) {
___S = ___S - 4;
}
if ( digitalRead(_input_Medregch3) == 0 ) {
___S = ___S - 2;
}
if ( digitalRead(_input_Medregch4) == 0 ) {
___S = ___S - 1;
}
___SData = ___S;
}
void ____doGulsuuraaDeeshluuleh() {
_servo_servo3.write(___pos3);
delay(25);
}
void ____doBombogUnagaah() {
_servo_servo2.write(___pos1_1);
delay(190);
_servo_servo2.write(___pos1_2);
delay(170);
}
void ____doUragshaaYvah() {
digitalWrite(_output_Motor1Chiglel, (int)0);
digitalWrite(_output_Motor2Chiglel, (int)0);
analogWrite(_output_Motor1Hurd, (int)___BaruunHurd);
analogWrite(_output_Motor2Hurd, (int)___ZuunHurd);
}
void BallRotation() {
if (value > 90){
for (pos = 90; pos <= value; pos += 1) {
_servo_servo1.write(pos);
delay(10);
}
// delay(1000);
for (pos = value; pos >= 90; pos -= 1) {
_servo_servo1.write(pos);
delay(10);
}
____doBombogUnagaah();
delay(150);
}else if (value < 90){
for (pos = 90; pos >= value; pos -= 1) {
_servo_servo1.write(pos);
delay(10);
}
// delay(1000);
for (pos = value; pos <= 90; pos += 1) {
_servo_servo1.write(pos);
delay(10);
____doBombogUnagaah();
delay(150);
}
}
}
void ____doBombogErguuleh() {
if (color == 1) {
value = 30;
BallRotation();
value = 90;
} else if (color == 2) {
value = 60;
BallRotation();
value = 90;
} else if (color == 3) {
value = 90;
BallRotation();
value = 90;
} else if (color == 4) {
value = 120;
BallRotation();
value = 90;
} else if (color == 5) {
value = 150;
BallRotation();
value = 90;
} else if (color == 6) {
value = 180;
BallRotation();
value = 90;
}
}
void ____doZuunErgeh() {
digitalWrite(_output_Motor1Chiglel, (int)0);
digitalWrite(_output_Motor2Chiglel, (int)1);
analogWrite(_output_Motor1Hurd, (int)___BaruunHurd);
analogWrite(_output_Motor2Hurd, (int)10 - ___ZuunHurd);
}
void ____doUhrah() {
digitalWrite(_output_Motor1Chiglel, (int)1);
digitalWrite(_output_Motor2Chiglel, (int)1);
analogWrite(_output_Motor1Hurd, (int)60 - ___BaruunHurd);
analogWrite(_output_Motor2Hurd, (int)60 - ___ZuunHurd);
}
void ____doBaruunErgeh() {
digitalWrite(_output_Motor1Chiglel, (int)1);
digitalWrite(_output_Motor2Chiglel, (int)0);
analogWrite(_output_Motor1Hurd, (int)40 - ___BaruunHurd);
analogWrite(_output_Motor2Hurd, (int)___ZuunHurd);
}
void ____doZogsoh() {
digitalWrite(_output_Motor1Chiglel, (int)0);
digitalWrite(_output_Motor2Chiglel, (int)0);
analogWrite(_output_Motor1Hurd, (int)0);
analogWrite(_output_Motor2Hurd, (int)0);
}
void setup()
{
Serial.begin(9600);
//Serial.println("Color View Test!");
if (tcs.begin()) {
//Serial.println("Found sensor");
} else {
Serial.println("No TCS34725 found ... check your connections");
while (1); // halt!
}
pinMode(_input_Medregch4, INPUT_PULLUP);
pinMode(_input_Medregch3, INPUT_PULLUP);
pinMode(_input_Medregch2, INPUT_PULLUP);
pinMode(_output_Motor1Hurd, OUTPUT);
pinMode(_input_Medregch1, INPUT_PULLUP);
pinMode(_output_Motor2Hurd, OUTPUT);
_servo_servo3.attach(9);
pinMode(_output_Motor1Chiglel, OUTPUT);
_servo_servo1.attach(11);
_servo_servo2.attach(10);
pinMode(_output_Motor2Chiglel, OUTPUT);
___S = 0;
___SData = 0;
___HighSpeefd = 190;
___MidlleSpeed = 170;
___LowSpeed = 60;
___BaruunHurd = 0;
___ZuunHurd = 0;
___SensorData = 0;
___A = 0;
___E = 0;
___zuraastoologch = 0;
___ErgehChiglel = 0;
___pos1_1 = 180;
___pos1_2 = 90;
___pos3 = 60;
___pos2 = 67.5;
ergeltiinHurd=90;
____doGulsuuraaDeeshluuleh();
}
void loop()
{ ___BaruunHurd = 30;
___ZuunHurd = 30;
____doUragshaaYvah();
delay(10); //tsagaan zuraas toolj zogsood uragshaa ywah hugatsaa
___zuraastoologch = 1;
____doZuraasDagah();
___ErgehChiglel = 1;
____doRobotErgeh();
___zuraastoologch = 2;
____doZuraasDagah();
____doZogsoh();
delay(10);
____doBombogErguuleh();
___zuraastoologch = 2;
____doZuraasDagah();
____doZogsoh();
delay(10);
____doBombogErguuleh();
___zuraastoologch = 2;
____doZuraasDagah();
____doZogsoh();
delay(10);
____doBombogErguuleh();
___ErgehChiglel = 0;
____doRobotErgeh();
___zuraastoologch = 3;
____doZuraasDagah();
____doZogsoh();
delay(10);
___ErgehChiglel = 0;
____doRobotErgeh();
___zuraastoologch = 2;
____doZuraasDagah();
____doZogsoh();
delay(10);
____doBombogErguuleh();
___zuraastoologch = 2;
____doZuraasDagah();
____doZogsoh();
delay(10);
____doBombogErguuleh();
___zuraastoologch = 2;
____doZuraasDagah();
____doZogsoh();
delay(10);
____doBombogErguuleh();
___ErgehChiglel = 0;
____doRobotErgeh();
___zuraastoologch = 2;
____doZuraasDagah();
____doZogsoh();
delay(10);
___ErgehChiglel = 0;
____doRobotErgeh();
___zuraastoologch = 6;
____doZuraasDagah();
____doZogsoh();
delay(10);
___ErgehChiglel = 0;
____doRobotErgeh();
___zuraastoologch = 2;
____doZuraasDagah();
____doZogsoh();
___BaruunHurd = 70;
___ZuunHurd = 80;
____doUragshaaYvah();
delay(900); //tsagaan zuraas toolj zogsood uragshaa ywah hugatsaa
____doZogsoh();
while(1);
}
void colorDetect()
{
uint16_t red, green, blue, black, white, clear;
tcs.setInterrupt(false);
delay(60);
tcs.getRawData(&red, &green, &blue, &clear);
tcs.setInterrupt(true);
if (red > blue && red > green && clear > 100){
color = 1;
Serial.println("Red");
} else if (blue > green && blue > red && clear > 100){
color = 2;
Serial.println("Blue");
} else if (red < 250 && green > 150 && blue < 350 && clear < 1500){
color = 3;
Serial.println("Green");
} else if (red > 300 && green > 300 && blue > 300 && clear > 900) {
color = 4;
Serial.println("White");
} else if (red < 150 && green < 150 && blue < 150 && clear < 200) {
color = 5;
Serial.println("Black");
}
if (precolor - color > 0) {
flag = precolor - color;
}
else if (precolor - color < 0) {
flag = 6 + (precolor - color);
}
else flag = 0;
precolor = 1;
}