aboutsummaryrefslogtreecommitdiff
path: root/car/car.ino
blob: c9c6b8e54ac5d0c9cc54e12e13dd6a9177dc26e1 (plain)
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
// Dimitri Sokolyuk
// 01.01.2017

#include <Servo.h>
#include <IRremote.h>
#include <os48.h>
#include "config.h"
#include "ir.h"

Servo head;
IRrecv irrecv(IR);

void motor(int e, int a, int b, int v) {
  if (v > 0) {
    digitalWrite(a, LOW);
    digitalWrite(b, HIGH);
  }
  if (v < 0) {
    digitalWrite(a, HIGH);
    digitalWrite(b, LOW);
    v = -v;
  }
  analogWrite(e, v);
}

void move(int l, int r) {
  motor(ENA, IN1, IN2, l);
  motor(ENB, IN3, IN4, r);
}

#define forward(v)  do move( v,  v); while (0)
#define backward(v) do move(-v, -v); while (0)
#define toleft(v)   do move( v, -v); while (0)
#define toright(v)  do move(-v,  v); while (0)
#define stop()      do move( 0,  0); while (0)

int distance() {
  digitalWrite(Trig, LOW);
  delayMicroseconds(2);
  digitalWrite(Trig, HIGH);
  delayMicroseconds(18);
  digitalWrite(Trig, LOW);
  return pulseIn(Echo, HIGH, TimeOut) / ToCM;
}

void look(int deg) {
  head.write(90 + deg);
  delay(1000); // wait to finish
}

#define lookahead()     do look(   0); while (0)
#define lookleft(deg)   do look( deg); while (0)
#define lookright(deg)  do look(-deg); while (0)

int sensor() {
  int s1 = digitalRead(S1);
  int s2 = digitalRead(S2);
  int s3 = digitalRead(S3);
  return s1 | (s2 << 1) | (s3 << 2);
}

void ultra() {
  if (distance() > dist) {
    forward(velo);
    return;
  }
  stop();
  lookleft(60);
  if (distance() > dist) {
    toleft(velo);
    lookahead();
    return;
  }
  lookright(60);
  if (distance() > dist) {
    toright(velo);
    lookahead();
    return;
  }
}

void ir() {
  decode_results results;
  if (irrecv.decode(&results)) {
    switch (results.value) {
      case KeyUp:
        forward(velo);
        break;
      case KeyDown:
        backward(velo);
        break;
      case KeyLeft:
        toleft(velo);
        break;
      case KeyRight:
        toright(velo);
        break;
      case KeyOk:
        stop();
        break;
    }
    irrecv.resume();
    delay(150);
  }
}

void setup() {
  Serial.begin(57600);

  pinMode(Echo, INPUT);
  pinMode(Trig, OUTPUT);

  pinMode(IN1, OUTPUT);
  pinMode(IN2, OUTPUT);
  pinMode(IN3, OUTPUT);
  pinMode(IN4, OUTPUT);

  pinMode(ENA, OUTPUT);
  pinMode(ENB, OUTPUT);

  pinMode(S1, INPUT);
  pinMode(S2, INPUT);
  pinMode(S3, INPUT);

  pinMode(IR, INPUT);
  irrecv.enableIRIn();

  head.attach(SRV);
  lookahead();
  stop();
}

void loop() {
  //ultra();
  ir();
}