#include <Wire.h>
#include <Adafruit_PWMServoDriver.h>
#include "avdweb_VirtualDelay.h"
Adafruit_PWMServoDriver pwm = Adafruit_PWMServoDriver();
#define SERVOMIN 180
#define SERVOMAX 520
//Infra Vermelho, controle remoto
#include <IRremote.h>
// Define IR Remote Button Codes
#define irUp 16718055
#define irDown 16730805
#define irRight 16734885
#define irLeft 16716015
#define irOK 16726215
#define ir1 16753245
#define ir2 16736925
#define ir3 16769565
#define ir4 16720605
#define ir5 16712445
#define ir6 16761405
#define ir7 16769055
#define ir8 16754775
#define ir9 16748655
#define ir0 16750695
#define irStar 16738455
#define irHash 16756815
#define irRepeat 4294967295
int irReceiver = 12; // Usando pino 12 para o IR Sensor
IRrecv irrecv(irReceiver); // Criando uma nova instância para o Receptor
decode_results results;
unsigned long value;
unsigned long lastValue;
//sensor ultrassônico
#include <HCSR04.h>
#define Trig 10
#define Echo 11
UltraSonicDistanceSensor distanceSensor(Trig, Echo); // Inicializando sensor nos pinos digitais.
long distancia;
class Servos
{
int timeServos[8];
VirtualDelay delays[8];
boolean servosStatus[8];
int servosInicialAngles[8];
private:
void Attach() {
for (int aux = 0; aux <= 7; aux++) {
servosStatus[aux] = false;
}
}
public:
Servos(int velocidade)
{
int defaultSpeed = velocidade;
for (int aux = 0; aux <= 7; aux++) {
timeServos[aux] = defaultSpeed;
}
}
void RestartAngles() {
for (int aux = 0; aux <= 7; aux++) {
servosInicialAngles[aux] = 90;
}
}
void SetInicialAngle(int angle, int ServoNumber) {
servosInicialAngles[ServoNumber] = angle;
}
void SetSpeed(int Speed, int ServoNumber) {
timeServos[ServoNumber] = Speed;
}
void Begin() {
for (int aux = 0; aux <= 7; aux++) {
rotate(aux, servosInicialAngles[aux]);
}
}
void rotate(int pin, int angle) {
int value;
value = map(angle, 0, 180, SERVOMIN, SERVOMAX);
pwm.setPWM(pin, 0, value);
}
void ServoMove(int angle1, int angle2, int angle3, int angle4, int angle5, int angle6,
int angle7, int angle8) {
Attach();
int countServos[16] = {angle1, angle2, angle3, angle4, angle5, angle6, angle7, angle8,
};
int AtivosServos = 0;
int Final = 0;
for (int aux = 0; aux <= 7; aux++) {
if (countServos[aux] <= 180) {
AtivosServos ++;
}
}
Serial.println(AtivosServos);
while (true) {
for (int aux = 0; aux <= 7; aux++) {
delays[aux].start(timeServos[aux]);
}
//Inicia o controle dos 8 servos ao mesmo tempo
if (angle1 <= 180 and servosStatus[0] == false and delays[0].elapsed()) {
if (angle1 < servosInicialAngles[0]) {
servosInicialAngles[0] -= 1;
rotate(0, servosInicialAngles[0]);
}
if (angle1 > servosInicialAngles[0]) {
servosInicialAngles[0] += 1;
rotate(0, servosInicialAngles[0]);
}
}
if (angle2 <= 180 and servosStatus[1] == false and delays[1].elapsed()) {
if (angle2 < servosInicialAngles[1]) {
servosInicialAngles[1] -= 1;
rotate(1, servosInicialAngles[1]);
}
if (angle2 > servosInicialAngles[1]) {
servosInicialAngles[1] += 1;
rotate(1, servosInicialAngles[1]);
}
}
if (angle3 <= 180 and servosStatus[2] == false and delays[2].elapsed()) {
if (angle3 < servosInicialAngles[2]) {
servosInicialAngles[2] -= 1;
rotate(2, servosInicialAngles[2]);
}
if (angle3 > servosInicialAngles[2]) {
servosInicialAngles[2] += 1;
rotate(2, servosInicialAngles[2]);
}
}
if (angle4 <= 180 and servosStatus[3] == false and delays[3].elapsed()) {
if (angle4 < servosInicialAngles[3]) {
servosInicialAngles[3] -= 1;
rotate(3, servosInicialAngles[3]);
}
if (angle4 > servosInicialAngles[3]) {
servosInicialAngles[3] += 1;
rotate(3, servosInicialAngles[3]);
}
}
if (angle5 <= 180 and servosStatus[4] == false and delays[4].elapsed()) {
if (angle5 < servosInicialAngles[4]) {
servosInicialAngles[4] -= 1;
rotate(4, servosInicialAngles[4]);
}
if (angle5 > servosInicialAngles[4]) {
servosInicialAngles[4] += 1;
rotate(4, servosInicialAngles[4]);
}
}
if (angle6 <= 180 and servosStatus[5] == false and delays[5].elapsed()) {
if (angle6 < servosInicialAngles[5]) {
servosInicialAngles[5] -= 1;
rotate(5, servosInicialAngles[5]);
}
if (angle6 > servosInicialAngles[5]) {
servosInicialAngles[5] += 1;
rotate(5, servosInicialAngles[5]);
}
}
if (angle7 <= 180 and servosStatus[6] == false and delays[6].elapsed()) {
if (angle7 < servosInicialAngles[6]) {
servosInicialAngles[6] -= 1;
rotate(6, servosInicialAngles[6]);
}
if (angle7 > servosInicialAngles[6]) {
servosInicialAngles[6] += 1;
rotate(6, servosInicialAngles[6]);
}
}
if (angle8 <= 180 and servosStatus[7] == false and delays[7].elapsed()) {
if (angle8 < servosInicialAngles[7]) {
servosInicialAngles[7] -= 1;
rotate(7, servosInicialAngles[7]);
}
if (angle8 > servosInicialAngles[7]) {
servosInicialAngles[7] += 1;
rotate(7, servosInicialAngles[7]);
}
}
if (servosInicialAngles[0] == angle1 and servosStatus[0] == false) {
servosStatus[0] = true;
Final += 1;
}
if (servosInicialAngles[1] == angle2 and servosStatus[1] == false) {
servosStatus[1] = true;
Final += 1;
}
if (servosInicialAngles[2] == angle3 and servosStatus[2] == false) {
servosStatus[2] = true;
Final += 1;
}
if (servosInicialAngles[3] == angle4 and servosStatus[3] == false) {
servosStatus[3] = true;
Final += 1;
}
if (servosInicialAngles[4] == angle5 and servosStatus[4] == false) {
servosStatus[4] = true;
Final += 1;
}
if (servosInicialAngles[5] == angle6 and servosStatus[5] == false) {
servosStatus[5] = true;
Final += 1;
}
if (servosInicialAngles[6] == angle7 and servosStatus[6] == false) {
servosStatus[6] = true;
Final += 1;
}
if (servosInicialAngles[7] == angle8 and servosStatus[7] == false) {
servosStatus[7] = true;
Final += 1;
}
if (Final == AtivosServos) {
break;
}
}
}
};
Servos servoPca(5);
void setup() {
Serial.begin(9600);
pwm.begin();
pwm.setPWMFreq(60);
irrecv.enableIRIn(); //Iniciando o Receptor IR
}
// *************************************************************** \\
// ****************LOOP**********LOOP***********LOOP************** \\
// *************************************************************** \\
void loop() {
// Servo1, Servo2, Servo3, Servo4, Servo5, Servo6, Servo7, Servo8
//Se usar o valores maiores que 180 o servo é desligado
MedirDistancia();
Controle();
if (distancia < 10) {
VoltarRapido();
GiraEsquerda();
}
}
void Caminhar() {
servoPca.ServoMove( 90 , 80 , 90 , 100 , 180 , 80 , 0 , 100 );
servoPca.ServoMove( 180 , 100 , 0 , 80 , 90 , 100 , 90 , 80 );
servoPca.ServoMove( 90 , 80 , 90 , 100 , 180 , 80 , 0 , 100 );
servoPca.ServoMove( 180 , 100 , 0 , 80 , 90 , 100 , 90 , 80 );
}
void CaminharRapido() {
servoPca.ServoMove( 90 , 80 , 90 , 100 , 135 , 80 , 45 , 100 );
servoPca.ServoMove( 135 , 100 , 45 , 80 , 90 , 100 , 90 , 80 );
servoPca.ServoMove( 90 , 80 , 90 , 100 , 135 , 80 , 45 , 100 );
servoPca.ServoMove( 135 , 100 , 45 , 80 , 90 , 100 , 90 , 80 );
}
void GiraEsquerda() {
servoPca.ServoMove( 90 , 100 , 90 , 80 , 90 , 100 , 90 , 80 );
servoPca.ServoMove( 135 , 80 , 45 , 100 , 135 , 80 , 45 , 100 );
servoPca.ServoMove( 90 , 100 , 90 , 80 , 90 , 100 , 90 , 80 );
servoPca.ServoMove( 135 , 80 , 45 , 100 , 135 , 80 , 45 , 100 );
servoPca.ServoMove( 90 , 100 , 90 , 80 , 90 , 100 , 90 , 80 );
servoPca.ServoMove( 135 , 80 , 45 , 100 , 135 , 80 , 45 , 100 );
servoPca.ServoMove( 90 , 100 , 90 , 80 , 90 , 100 , 90 , 80 );
servoPca.ServoMove( 135 , 80 , 45 , 100 , 135 , 80 , 45 , 100 );
servoPca.ServoMove( 90 , 100 , 90 , 80 , 90 , 100 , 90 , 80 );
servoPca.ServoMove( 135 , 80 , 45 , 100 , 135 , 80 , 45 , 100 );
servoPca.ServoMove( 90 , 100 , 90 , 80 , 90 , 100 , 90 , 80 );
servoPca.ServoMove( 135 , 80 , 45 , 100 , 135 , 80 , 45 , 100 );
servoPca.ServoMove( 90 , 100 , 90 , 80 , 90 , 100 , 90 , 80 );
servoPca.ServoMove( 135 , 80 , 45 , 100 , 135 , 80 , 45 , 100 );
servoPca.ServoMove( 90 , 100 , 90 , 80 , 90 , 100 , 90 , 80 );
servoPca.ServoMove( 135 , 80 , 45 , 100 , 135 , 80 , 45 , 100 );
}
void GiraDireita() {
servoPca.ServoMove( 90 , 80 , 90 , 100 , 90 , 80 , 90 , 100 );
servoPca.ServoMove( 135 , 100 , 45 , 80 , 135 , 100 , 45 , 80 );
servoPca.ServoMove( 90 , 80 , 90 , 100 , 90 , 80 , 90 , 100 );
servoPca.ServoMove( 135 , 100 , 45 , 80 , 135 , 100 , 45 , 80 );
servoPca.ServoMove( 90 , 80 , 90 , 100 , 90 , 80 , 90 , 100 );
servoPca.ServoMove( 135 , 100 , 45 , 80 , 135 , 100 , 45 , 80 );
servoPca.ServoMove( 90 , 80 , 90 , 100 , 90 , 80 , 90 , 100 );
servoPca.ServoMove( 135 , 100 , 45 , 80 , 135 , 100 , 45 , 80 );
servoPca.ServoMove( 90 , 80 , 90 , 100 , 90 , 80 , 90 , 100 );
servoPca.ServoMove( 135 , 100 , 45 , 80 , 135 , 100 , 45 , 80 );
servoPca.ServoMove( 90 , 80 , 90 , 100 , 90 , 80 , 90 , 100 );
servoPca.ServoMove( 135 , 100 , 45 , 80 , 135 , 100 , 45 , 80 );
servoPca.ServoMove( 90 , 80 , 90 , 100 , 90 , 80 , 90 , 100 );
servoPca.ServoMove( 135 , 100 , 45 , 80 , 135 , 100 , 45 , 80 );
servoPca.ServoMove( 90 , 80 , 90 , 100 , 90 , 80 , 90 , 100 );
servoPca.ServoMove( 135 , 100 , 45 , 80 , 135 , 100 , 45 , 80 );
}
void Voltar() {
servoPca.ServoMove( 90 , 100 , 90 , 80 , 180 , 100 , 0 , 80 );
servoPca.ServoMove( 180 , 80 , 0 , 100 , 90 , 80 , 90 , 100 );
servoPca.ServoMove( 90 , 100 , 90 , 80 , 180 , 100 , 0 , 80 );
servoPca.ServoMove( 180 , 80 , 0 , 100 , 90 , 80 , 90 , 100 );
}
void VoltarRapido() {
servoPca.ServoMove( 90 , 100 , 90 , 80 , 135 , 100 , 45 , 80 );
servoPca.ServoMove( 135 , 80 , 45 , 100 , 90 , 80 , 90 , 100 );
servoPca.ServoMove( 90 , 100 , 90 , 80 , 135 , 100 , 45 , 80 );
servoPca.ServoMove( 135 , 80 , 45 , 100 , 90 , 80 , 90 , 100 );
}
void SentarDarPatinha() {
servoPca.ServoMove( 0 , 150 , 0 , 20 , 180 , 20 , 180 , 150 ); //senta
delay(300);
servoPca.ServoMove( 0 , 20 , 0 , 20 , 180 , 20 , 180 , 150 ); //Levanta a Pata
servoPca.ServoMove( 0 , 60 , 0 , 20 , 180 , 20 , 180 , 150 ); //Levanta a Pata
servoPca.ServoMove( 0 , 20 , 0 , 20 , 180 , 20 , 180 , 150 ); //Levanta a Pata
servoPca.ServoMove( 0 , 60 , 0 , 20 , 180 , 20 , 180 , 150 ); //Levanta a Pata
servoPca.ServoMove( 0 , 20 , 0 , 20 , 180 , 20 , 180 , 150 ); //Levanta a Pata
delay(3000);
}
void Descansar() {
servoPca.ServoMove( 90 , 90 , 90 , 90 , 90 , 90 , 90 , 90 );
delay(1000);
}
void Deita() {
servoPca.ServoMove( 90 , 20 , 90 , 20 , 90 , 20 , 90 , 20 );
delay(1000);
}
void Alto() {
servoPca.ServoMove( 90 , 145 , 90 , 145 , 90 , 145 , 90 , 145 );
delay(1000);
}
void BaixaTraseira() {
servoPca.ServoMove( 90 , 145 , 90 , 35 , 90 , 35 , 90 , 145 );
delay(1000);
}
void BaixaDianteira() {
servoPca.ServoMove( 90 , 35 , 90 , 145 , 90 , 145 , 90 , 35 );
delay(1000);
}
void BalancaTraseira() {
servoPca.ServoMove( 90 , 35 , 90 , 145 , 90 , 145 , 90 , 35 );
servoPca.ServoMove( 90 , 35 , 70 , 145 , 70 , 145 , 90 , 35 );
servoPca.ServoMove( 90 , 35 , 110 , 145 , 110 , 145 , 90 , 35 );
servoPca.ServoMove( 90 , 35 , 70 , 145 , 70 , 145 , 90 , 35 );
servoPca.ServoMove( 90 , 35 , 110 , 145 , 110 , 145 , 90 , 35 );
servoPca.ServoMove( 90 , 35 , 70 , 145 , 70 , 145 , 90 , 35 );
servoPca.ServoMove( 90 , 35 , 110 , 145 , 110 , 145 , 90 , 35 );
servoPca.ServoMove( 90 , 35 , 70 , 145 , 70 , 145 , 90 , 35 );
servoPca.ServoMove( 90 , 35 , 110 , 145 , 110 , 145 , 90 , 35 );
servoPca.ServoMove( 90 , 35 , 70 , 145 , 70 , 145 , 90 , 35 );
servoPca.ServoMove( 90 , 35 , 110 , 145 , 110 , 145 , 90 , 35 );
servoPca.ServoMove( 90 , 35 , 70 , 145 , 70 , 145 , 90 , 35 );
servoPca.ServoMove( 90 , 35 , 110 , 145 , 110 , 145 , 90 , 35 );
}
void BalancaDeFrente() {
servoPca.ServoMove( 90 , 110 , 90 , 70 , 90 , 70 , 90 , 110 );
servoPca.ServoMove( 90 , 70 , 90 , 110 , 90 , 110 , 90 , 70 );
servoPca.ServoMove( 90 , 110 , 90 , 70 , 90 , 70 , 90 , 110 );
servoPca.ServoMove( 90 , 70 , 90 , 110 , 90 , 110 , 90 , 70 );
servoPca.ServoMove( 90 , 110 , 90 , 70 , 90 , 70 , 90 , 110 );
servoPca.ServoMove( 90 , 70 , 90 , 110 , 90 , 110 , 90 , 70 );
servoPca.ServoMove( 90 , 110 , 90 , 70 , 90 , 70 , 90 , 110 );
servoPca.ServoMove( 90 , 70 , 90 , 110 , 90 , 110 , 90 , 70 );
servoPca.ServoMove( 90 , 110 , 90 , 70 , 90 , 70 , 90 , 110 );
servoPca.ServoMove( 90 , 70 , 90 , 110 , 90 , 110 , 90 , 70 );
}
void BalancaDeLado() {
servoPca.ServoMove( 90 , 70 , 90 , 70 , 90 , 110 , 90 , 110 );
servoPca.ServoMove( 90 , 110 , 90 , 110 , 90 , 70 , 90 , 70 );
servoPca.ServoMove( 90 , 70 , 90 , 70 , 90 , 110 , 90 , 110 );
servoPca.ServoMove( 90 , 110 , 90 , 110 , 90 , 70 , 90 , 70 );
servoPca.ServoMove( 90 , 70 , 90 , 70 , 90 , 110 , 90 , 110 );
servoPca.ServoMove( 90 , 110 , 90 , 110 , 90 , 70 , 90 , 70 );
servoPca.ServoMove( 90 , 70 , 90 , 70 , 90 , 110 , 90 , 110 );
servoPca.ServoMove( 90 , 110 , 90 , 110 , 90 , 70 , 90 , 70 );
servoPca.ServoMove( 90 , 70 , 90 , 70 , 90 , 110 , 90 , 110 );
servoPca.ServoMove( 90 , 110 , 90 , 110 , 90 , 70 , 90 , 70 );
}
void BaixaEsquerda() {
servoPca.ServoMove( 90 , 35 , 90 , 35 , 90 , 145 , 90 , 145 );
delay(1000);
}
void BaixaDireita() {
servoPca.ServoMove( 90 , 145 , 90 , 145 , 90 , 35 , 90 , 35 );
delay(1000);
}
void Onda() {
servoPca.ServoMove( 90 , 90 , 90 , 90 , 90 , 90 , 90 , 90 );// meia altura
servoPca.ServoMove( 90 , 35 , 90 , 90 , 90 , 145 , 90 , 90 );// Baixa Dianteira Esquerda Levanta Traseira Direita
servoPca.ServoMove( 90 , 90 , 90 , 35 , 90 , 90 , 90 , 145 );// Baixa Traseira Esquerda Levanta Dianteira Direita
servoPca.ServoMove( 90 , 145 , 90 , 90 , 90 , 35 , 90 , 90 );// Baixa Traseira Direita Levanta Dianteira Esquerda
servoPca.ServoMove( 90 , 90 , 90 , 145 , 90 , 90 , 90 , 35 );// Baixa Dianteira Direita Levanta Traseira Esquerda
servoPca.ServoMove( 90 , 35 , 90 , 90 , 90 , 145 , 90 , 90 );// Baixa Dianteira Esquerda Levanta Traseira Direita
servoPca.ServoMove( 90 , 90 , 90 , 35 , 90 , 90 , 90 , 145 );// Baixa Traseira Esquerda Levanta Dianteira Direita
servoPca.ServoMove( 90 , 145 , 90 , 90 , 90 , 35 , 90 , 90 );// Baixa Traseira Direita Levanta Dianteira Esquerda
servoPca.ServoMove( 90 , 90 , 90 , 145 , 90 , 90 , 90 , 35 );// Baixa Dianteira Direita Levanta Traseira Esquerda
servoPca.ServoMove( 90 , 35 , 90 , 90 , 90 , 145 , 90 , 90 );// Baixa Dianteira Esquerda Levanta Traseira Direita
servoPca.ServoMove( 90 , 90 , 90 , 35 , 90 , 90 , 90 , 145 );// Baixa Traseira Esquerda Levanta Dianteira Direita
servoPca.ServoMove( 90 , 145 , 90 , 90 , 90 , 35 , 90 , 90 );// Baixa Traseira Direita Levanta Dianteira Esquerda
servoPca.ServoMove( 90 , 90 , 90 , 145 , 90 , 90 , 90 , 35 );// Baixa Dianteira Direita Levanta Traseira Esquerda
servoPca.ServoMove( 90 , 90 , 90 , 90 , 90 , 90 , 90 , 90 );// meia altura
}
void Dance() {
servoPca.ServoMove( 90 , 145 , 90 , 145 , 90 , 145 , 90 , 145 );// alto
servoPca.ServoMove( 90 , 35 , 90 , 145 , 90 , 145 , 90 , 35 );// baixa dianteira
servoPca.ServoMove( 90 , 35 , 90 , 145 , 90 , 145 , 90 , 35 );// baixa esquerda
servoPca.ServoMove( 90 , 145 , 90 , 35 , 90 , 35 , 90 , 145 );//baixa traseira
servoPca.ServoMove( 90 , 145 , 90 , 145 , 90 , 35 , 90 , 35 );//baixa direita
servoPca.ServoMove( 90 , 35 , 90 , 145 , 90 , 145 , 90 , 35 );// baixa dianteira
servoPca.ServoMove( 90 , 145 , 90 , 145 , 90 , 145 , 90 , 145 );// alto
servoPca.ServoMove( 90 , 35 , 90 , 145 , 90 , 145 , 90 , 35 );// baixa dianteira
servoPca.ServoMove( 90 , 35 , 90 , 145 , 90 , 145 , 90 , 35 );// baixa esquerda
servoPca.ServoMove( 90 , 145 , 90 , 35 , 90 , 35 , 90 , 145 );//baixa traseira
servoPca.ServoMove( 90 , 145 , 90 , 145 , 90 , 35 , 90 , 35 );//baixa direita
servoPca.ServoMove( 90 , 35 , 90 , 145 , 90 , 145 , 90 , 35 );// baixa dianteira
servoPca.ServoMove( 90 , 145 , 90 , 145 , 90 , 145 , 90 , 145 );// alto
servoPca.ServoMove( 90 , 35 , 90 , 145 , 90 , 145 , 90 , 35 );// baixa dianteira
servoPca.ServoMove( 90 , 35 , 90 , 145 , 90 , 145 , 90 , 35 );// baixa esquerda
servoPca.ServoMove( 90 , 145 , 90 , 35 , 90 , 35 , 90 , 145 );//baixa traseira
servoPca.ServoMove( 90 , 145 , 90 , 145 , 90 , 35 , 90 , 35 );//baixa direita
servoPca.ServoMove( 90 , 35 , 90 , 145 , 90 , 145 , 90 , 35 );// baixa dianteira
servoPca.ServoMove( 90 , 145 , 90 , 145 , 90 , 145 , 90 , 145 );// alto
servoPca.ServoMove( 90 , 35 , 90 , 145 , 90 , 145 , 90 , 35 );// baixa dianteira
servoPca.ServoMove( 90 , 35 , 90 , 145 , 90 , 145 , 90 , 35 );// baixa esquerda
servoPca.ServoMove( 90 , 145 , 90 , 35 , 90 , 35 , 90 , 145 );//baixa traseira
servoPca.ServoMove( 90 , 145 , 90 , 145 , 90 , 35 , 90 , 35 );//baixa direita
servoPca.ServoMove( 90 , 35 , 90 , 145 , 90 , 145 , 90 , 35 );// baixa dianteira
delay(1000);
}
void MedirDistancia() {
distancia = distanceSensor.measureDistanceCm();
Serial.println(distancia);
}
void Controle() {
if (irrecv.decode(&results)) // If para identificar o sinal recebido no IR
{
value = results.value;
if (value == irRepeat)
value = lastValue;
switch (value)
{
case irUp:
lastValue = irUp;
Caminhar();
break;
case irDown:
lastValue = irDown;
Voltar();
break;
case irRight:
lastValue = irRight;
GiraDireita();
break;
case irLeft:
lastValue = irLeft;
GiraEsquerda();
break;
case irOK:
lastValue = irOK;
Descansar();
SentarDarPatinha();
break;
case ir1:
lastValue = ir1;
BalancaTraseira();
break;
case ir2:
lastValue = ir2;
Onda();
break;
case ir3:
lastValue = ir3;
Dance();
break;
case ir4:
lastValue = ir4;
BaixaDianteira();
break;
case ir5:
lastValue = ir5;
BaixaTraseira();
break;
case ir6:
lastValue = ir6;
BaixaDireita();
break;
case ir7:
lastValue = ir7;
BaixaEsquerda();
break;
case ir8:
lastValue = ir8;
BalancaDeLado();
break;
case ir9:
lastValue = ir9;
BalancaDeFrente();
break;
case ir0:
lastValue = ir0;
Descansar();
break;
case irStar:
lastValue = irStar;
Deita();
break;
case irHash:
lastValue = irHash;
Alto();
break;
default:
break;
}
irrecv.resume(); //próximo valor
delay(50); // Pausa de 50ms
}// if irrecv.decode
}