-
Notifications
You must be signed in to change notification settings - Fork 0
/
sketch-blue-joycon.ino
416 lines (351 loc) · 11 KB
/
sketch-blue-joycon.ino
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
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
//Programa: NodeMCU e MQTT - Remote Car Control IoT
#include <Ultrasonic.h> //Importa a Biblioteca Ultrasonic
#include <ESP8266WiFi.h> // Importa a Biblioteca ESP8266WiFi
#include <PubSubClient.h> // Importa a Biblioteca PubSubClient
//Definindo a id mqtt e tópicos para publicação e subscribe
#define TOPICO_SUBSCRIBE "mqttInterfaceEnvia" //tópico MQTT de recepção de mensagem
#define TOPICO_PUBLISH "mqttNodeMCURecebe" //tópico MQTT de envio de mensagem
#define ID_MQTT "IdCarroMestre" //id mqtt (para identificação de sessão)
//Definindo mapeamento de pinos do NodeMCU
#define D0 16
#define D1 5
#define D2 4
#define D3 0
#define D4 2
#define D5 14
#define D6 12
#define D7 13
#define D8 15
#define D9 3
#define D10 1
// WIFI
const char* SSID = "suaRedeWifi"; // SSID / nome da rede WI-FI que deseja se conectar
const char* PASSWORD = "suaSenha"; // Senha da rede WI-FI que deseja se conectar
// MQTT
const char* BROKER_MQTT = "broker.hivemq.com"; //URL do broker MQTT que se deseja utilizar
int BROKER_PORT = 1883; // Porta do Broker MQTT
//Variáveis e objetos globais
WiFiClient espClient; // Cria o objeto espClient
PubSubClient MQTT(espClient); // Instancia o Cliente MQTT passando o objeto espClient
char EstadoSaida = '0'; //variável que armazena o estado atual da saída
// Define os pinos de controle da L298N
int leftMotorForward = 2; /* GPIO2(D4) -> IN3 */
int rightMotorForward = 15; /* GPIO15(D8) -> IN1 */
int leftMotorBackward = 0; /* GPIO0(D3) -> IN4 */
int rightMotorBackward = 13; /* GPIO13(D7) -> IN2 */
// Define os pinos de habilitar a L298N
int rightMotorENB = 14; /* GPIO14(D5) -> Motor-A Enable */
int leftMotorENB = 12; /* GPIO12(D6) -> Motor-B Enable */
//Prototypes
void initSerial();
void initWiFi();
void initMQTT();
void reconectWiFi();
void mqtt_callback(char* topic, byte* payload, unsigned int length);
void VerificaConexoesWiFIEMQTT(void);
void InitOutput(void);
int teste = 1;
//Define os pinos do sensor ultrassônico e implementa a função de leitura
Ultrasonic ultrasonic(5, 4);
int distance;
/*
* Implementações das funções
*/
void setup()
{
//inicializações:
InitOutput();
initSerial();
initWiFi();
initMQTT();
Serial.begin(9600);
//Inicializa os pinos de controle do motor como outputs
pinMode(leftMotorForward, OUTPUT);
pinMode(rightMotorForward, OUTPUT);
pinMode(leftMotorBackward, OUTPUT);
pinMode(rightMotorBackward, OUTPUT);
//Inicializa os pinos de habilitado do motor como outputs
pinMode(leftMotorENB, OUTPUT);
pinMode(rightMotorENB, OUTPUT);
}
//Função: inicializa comunicação serial com baudrate 115200 (para fins de monitorar no terminal serial
// o que está acontecendo.
//Parâmetros: nenhum
//Retorno: nenhum
void initSerial()
{
Serial.begin(115200);
}
//Função: inicializa e conecta-se na rede WI-FI desejada
//Parâmetros: nenhum
//Retorno: nenhum
void initWiFi()
{
delay(10);
Serial.println("------Conexao WI-FI------");
Serial.print("Conectando-se na rede: ");
Serial.println(SSID);
Serial.println("Aguarde");
reconectWiFi();
}
//Função: inicializa parâmetros de conexão MQTT(endereço do
// broker, porta e seta função de callback)
//Parâmetros: nenhum
//Retorno: nenhum
void initMQTT()
{
MQTT.setServer(BROKER_MQTT, BROKER_PORT); //informa qual broker e porta deve ser conectado
MQTT.setCallback(mqtt_callback); //atribui função de callback (função chamada quando qualquer informação de um dos tópicos subescritos chega)
}
//Função: função de callback
// esta função é chamada toda vez que uma informação de
// um dos tópicos subescritos chega)
//Parâmetros: nenhum
//Retorno: nenhum
void mqtt_callback(char* topic, byte* payload, unsigned int length)
{
String msg;
//Obtém a string do payload recebido
for(int i = 0; i < length; i++)
{
char c = (char)payload[i];
msg += c;
}
//toma ação dependendo da string recebida:
//verifica se deve colocar nivel alto de tensão na saída D0:
//IMPORTANTE: o Led já contido na placa é acionado com lógica invertida (ou seja,
//enviar HIGH para o output faz o Led apagar / enviar LOW faz o Led acender)
if (msg.equals("L"))
{
digitalWrite(D0, LOW);
EstadoSaida = '1';
MotorForward();
}
//verifica se deve colocar nivel alto de tensão na saída D0:
if (msg.equals("D"))
{
digitalWrite(D0, HIGH);
EstadoSaida = '0';
MotorStop();
}
// gira para esquerda
if (msg.equals("A"))
{
digitalWrite(D0, HIGH);
EstadoSaida = '1';
TurnLeft();
delay(200);
MotorStop();
}
//gira para direita
if (msg.equals("B"))
{
digitalWrite(D0, HIGH);
EstadoSaida = '1';
TurnRight();
delay(200);
MotorStop();
}
//recuar
if (msg.equals("C"))
{
digitalWrite(D0, HIGH);
EstadoSaida = '1';
MotorBackward();
}
/*
//joycon vermelho avança
if (msg.equals("E"))
{
digitalWrite(D0, LOW);
EstadoSaida = '1';
MotorForward();
}
//joycon vermelho para
if (msg.equals("F"))
{
digitalWrite(D0, HIGH);
EstadoSaida = '0';
MotorStop();
}
// joycon vermelho gira para esquerda
if (msg.equals("G"))
{
digitalWrite(D0, HIGH);
EstadoSaida = '1';
TurnLeft();
delay(200);
MotorStop();
}
//joycon vermelho gira para direita
if (msg.equals("H"))
{
digitalWrite(D0, HIGH);
EstadoSaida = '1';
TurnRight();
delay(200);
MotorStop();
}
//joycon vermelho recua
if (msg.equals("I"))
{
digitalWrite(D0, HIGH);
EstadoSaida = '1';
MotorBackward();
}*/
}
//Função: reconecta-se ao broker MQTT (caso ainda não esteja conectado ou em caso de a conexão cair)
// em caso de sucesso na conexão ou reconexão, o subscribe dos tópicos é refeito.
//Parâmetros: nenhum
//Retorno: nenhum
void reconnectMQTT()
{
while (!MQTT.connected())
{
Serial.print("* Tentando se conectar ao Broker MQTT: ");
Serial.println(BROKER_MQTT);
if (MQTT.connect(ID_MQTT))
{
Serial.println("Conectado com sucesso ao broker MQTT!");
MQTT.subscribe(TOPICO_SUBSCRIBE);
}
else
{
Serial.println("Falha ao reconectar no broker.");
Serial.println("Havera nova tentativa de conexao em 2s");
delay(2000);
}
}
}
//Função: reconecta-se ao WiFi
//Parâmetros: nenhum
//Retorno: nenhum
void reconectWiFi()
{
//se já está conectado a rede WI-FI, nada é feito.
//Caso contrário, são efetuadas tentativas de conexão
if (WiFi.status() == WL_CONNECTED)
return;
WiFi.begin(SSID, PASSWORD); // Conecta na rede WI-FI
while (WiFi.status() != WL_CONNECTED)
{
delay(100);
Serial.print(".");
}
Serial.println();
Serial.print("Conectado com sucesso na rede ");
Serial.print(SSID);
Serial.println("IP obtido: ");
Serial.println(WiFi.localIP());
}
//Função: verifica o estado das conexões WiFI e ao broker MQTT.
// Em caso de desconexão (qualquer uma das duas), a conexão
// é refeita.
//Parâmetros: nenhum
//Retorno: nenhum
void VerificaConexoesWiFIEMQTT(void)
{
if (!MQTT.connected())
reconnectMQTT(); //se não há conexão com o Broker, a conexão é refeita
reconectWiFi(); //se não há conexão com o WiFI, a conexão é refeita
}
//Função: envia ao Broker o estado atual do output
//Parâmetros: nenhum
//Retorno: nenhum
void EnviaEstadoOutputMQTT(void)
{
if (EstadoSaida == '0')
MQTT.publish(TOPICO_PUBLISH, "D");
if (EstadoSaida == '1')
MQTT.publish(TOPICO_PUBLISH, "L");
Serial.println("- Estado da saida D0 enviado ao broker!");
delay(1000);
}
//Função: inicializa o output em nível lógico baixo
//Parâmetros: nenhum
//Retorno: nenhum
void InitOutput(void)
{
//IMPORTANTE: o Led já contido na placa é acionado com lógica invertida (ou seja,
//enviar HIGH para o output faz o Led apagar / enviar LOW faz o Led acender)
pinMode(D0, OUTPUT);
digitalWrite(D0, HIGH);
}
void TurnRight(void)
{
digitalWrite(leftMotorENB,HIGH);
digitalWrite(rightMotorENB,HIGH);
digitalWrite(leftMotorForward,HIGH);
digitalWrite(rightMotorForward,HIGH);
digitalWrite(leftMotorBackward,LOW);
digitalWrite(rightMotorBackward,LOW);
teste = 1;
}
/********************************************* BACKWARD *****************************************************/
void TurnLeft(void)
{
digitalWrite(leftMotorENB,HIGH);
digitalWrite(rightMotorENB,HIGH);
digitalWrite(leftMotorBackward,HIGH);
digitalWrite(rightMotorBackward,HIGH);
digitalWrite(leftMotorForward,LOW);
digitalWrite(rightMotorForward,LOW);
teste = 1;
}
/********************************************* TURN LEFT *****************************************************/
void MotorForward(void)
{
teste = 2;
digitalWrite(leftMotorENB,HIGH);
digitalWrite(rightMotorENB,HIGH);
digitalWrite(leftMotorForward,LOW);
digitalWrite(rightMotorForward,HIGH);
digitalWrite(rightMotorBackward,LOW);
digitalWrite(leftMotorBackward,HIGH);
}
/********************************************* TURN RIGHT *****************************************************/
void MotorBackward(void)
{
digitalWrite(leftMotorENB,HIGH);
digitalWrite(rightMotorENB,HIGH);
digitalWrite(leftMotorForward,HIGH);
digitalWrite(rightMotorForward,LOW);
digitalWrite(rightMotorBackward,HIGH);
digitalWrite(leftMotorBackward,LOW);
teste = 1;
}
/********************************************* STOP *****************************************************/
void MotorStop(void)
{
digitalWrite(leftMotorENB,LOW);
digitalWrite(rightMotorENB,LOW);
digitalWrite(leftMotorForward,LOW);
digitalWrite(leftMotorBackward,LOW);
digitalWrite(rightMotorForward,LOW);
digitalWrite(rightMotorBackward,LOW);
teste = 1;
}
//programa principal
void loop()
{
//Parar de acordo com a leitura do sensor
if(ultrasonic.read() <= 40 && teste==2){
MotorStop();
MQTT.publish(TOPICO_PUBLISH, "Z");
}
// Pass INC as a parameter to get the distance in inches
distance = ultrasonic.read();
Serial.print("Distância em CM: ");
Serial.println(distance);
delay(200);
if(distance <= 40){
Serial.print("Obstáculo a menos de 40 cm! Os carros vão parar.");
delay(5000);
}
//garante funcionamento das conexões WiFi e ao broker MQTT
VerificaConexoesWiFIEMQTT();
//envia o status de todos os outputs para o Broker no protocolo esperado
EnviaEstadoOutputMQTT();
//keep-alive da comunicação com broker MQTT
MQTT.loop();
}