O protótipo apresentado é o resultado inicial de uma pesquisa iniciada em julho de 2014. Trata-se de um veículo capaz de transportar cargar e, futuramente, detectar e resgatar objetos devidamente identificados, de maneira autônoma, fazendo o percurso de ida e volta. Atualmente é possível seu controle através de interface local ou por acesso remoto via VNC. Maiores detalhes podem ser encontrados na documentação disponível em: https://robolivre.org/conteudo/mutante/download/idDoc/231 e mais vídeos pode ser vistos em: .


Código do arduino:

#include 
#include 
#include 
#include 

/******** DECLARAÇÃO DE VARIÁVEIS E CONSTANTES **********************/

LiquidCrystal 
    lcd(43, 45, 47,49,51,53),
    lcd2(42, 44, 46, 48, 50, 52);

Servo 
    Sv1, 
    Sv2, 
    Sv3, 
    Sv4, 
    Sv5;
    
DistanceSRF04 
    usF, 
    usL, 
    usR;

 int  
    B = 37,
    B2 = 38,
    B3 = 39,
    B4 = 40,
    B5 = 41,
    S1 = 2, 
    S2 = 3, 
    S3 = 4,   
    S4 = 5, 
    S5 = 6,
    motRf = 8,
    motRb = 9,
    motLf = 10,
    motLb = 11,
    AcX, 
    AcY, 
    AcZ, 
    Tmp, 
    GyX, 
    GyY, 
    GyZ,
    base = 10,
    cotovelo = 70,
    pulso = 90;

char 
    d;
    
const 
      int 
         v1 = 255,
         v3 = 255,
         MPU = 0x68;  // I2C address of the MPU-6050
/*********************************************************************/
 

/************ FUNÇÃO BANNER ******************************************/

void Banner(){//Mensagem Inicial
  lcd.clear();
  lcd.setCursor(1,0);
  lcd.print("M.U.T.A.N.T.E.");
  Serial.print("M.U.T.A.N.T.E.");
  lcd.setCursor(1, 1);
  lcd.print("R 4.0 - LCD 1");
  Serial.print("\tR 4.0 - LCD 1");
  lcd2.clear();
  lcd2.setCursor(1,0);
  lcd2.print("M.U.T.A.N.T.E.");
  lcd2.setCursor(5, 1);
  lcd2.print("LCD 2");
  delay(1000);
  lcd.setCursor(0, 1);
  lcd.print("A. Oliveira 2015");
  lcd2.setCursor(0, 1);
  lcd2.print("#CPBR8 2015");
  Serial.print("\rA. Oliveira 2014\n#CPBR8 2015\n");
  delay(1000);
}
/*********************************************************************/

/************ INICIALIZADOR ACELERÔMETRO *****************************/

void ini_ace(){
  Wire.begin();
  Wire.beginTransmission(MPU);
  Wire.write(0x6B);  // PWR_MGMT_1 register
  Wire.write(0);     // set to zero (wakes up the MPU-6050)
  Wire.endTransmission(true);
}
/*********************************************************************/

/*********** LEITURA DO ACELERÔMETRO *********************************/

void le_ace(){
  Wire.beginTransmission(MPU);
  Wire.write(0x3B);  // starting with register 0x3B (ACCEL_XOUT_H)
  Wire.endTransmission(false);
  Wire.requestFrom(MPU,14,true);  // request a total of 14 registers
  AcX=Wire.read()<<8|Wire.read();  // 0x3B (ACCEL_XOUT_H) & 0x3C (ACCEL_XOUT_L)     
  AcY=Wire.read()<<8|Wire.read();  // 0x3D (ACCEL_YOUT_H) & 0x3E (ACCEL_YOUT_L)
  AcZ=Wire.read()<<8|Wire.read();  // 0x3F (ACCEL_ZOUT_H) & 0x40 (ACCEL_ZOUT_L)
  Tmp=Wire.read()<<8|Wire.read();  // 0x41 (TEMP_OUT_H) & 0x42 (TEMP_OUT_L)
  GyX=Wire.read()<<8|Wire.read();  // 0x43 (GYRO_XOUT_H) & 0x44 (GYRO_XOUT_L)
  GyY=Wire.read()<<8|Wire.read();  // 0x45 (GYRO_YOUT_H) & 0x46 (GYRO_YOUT_L)
  GyZ=Wire.read()<<8|Wire.read();  // 0x47 (GYRO_ZOUT_H) & 0x48 (GYRO_ZOUT_L)  
}
/*********************************************************************/

/********** TESTE DA BOTOEIRA ****************************************/

void botoes(){
lcd.clear();
lcd.setCursor(0, 0); 
lcd.print("Estado Botoes:");
lcd2.clear();
lcd2.setCursor(0,0);
lcd2.print(" B1+B4 para sair ");
do{
  if (digitalRead(B) == HIGH){
    lcd.setCursor(0, 1); 
    lcd.print("Bot 1 Pressd");
  }
  if (digitalRead(B2) == HIGH){
    lcd.setCursor(0, 1); 
    lcd.print("Bot 2 Pressd");
  }
  if (digitalRead(B3) == HIGH){
    lcd.setCursor(0, 1); 
    lcd.print("Bot 3 Pressd");
  }
  if (digitalRead(B4) == HIGH){
    lcd.setCursor(0, 1); 
    lcd.print("Bot 4 Pressd");
  }
  if (digitalRead(B5) == HIGH){
    lcd.setCursor(0, 1); 
    lcd.print("Bot 5 Pressd");
  }
}while((digitalRead(B) != HIGH) || (digitalRead(B4) != HIGH));
lcd2.setCursor(0, 1); 
lcd2.print("Botoes OK!!!!");
delay(1000);
}
/*********************************************************************/

/******** TESTE DE SENSORES ULTRASSÔNICOS ****************************/

void ultrassom(){
  int b;
lcd.clear();
lcd2.clear();
lcd.setCursor(0,0); 
lcd.print("  Ultrassonicos ");
lcd.setCursor(0,1);
lcd.print(" B4 para sair ");
delay(2000);
do{
  b = digitalRead(B4);
  lcd.setCursor(0,1);
  lcd.print("Frente: ");
  lcd.print(usF.getDistanceCentimeter());
  lcd.print("            ");
  lcd2.setCursor(0,0);
  lcd2.print("Esquerda: ");
  lcd2.print(usL.getDistanceCentimeter());
  lcd2.print("           ");
  lcd2.setCursor(0,1);
  lcd2.print("Direita: ");
  lcd2.print(usR.getDistanceCentimeter());
  lcd2.print("           ");
  delay(50);
}while(b != HIGH );
lcd2.setCursor(0, 1); 
lcd2.print("Ultrassoncos OK!");
delay(1000);

}

/********************************************************************/

/***** TESTE DE BOTÕES DO ANALOGPAD (R) ******************************/

void testaAngl(){
lcd.clear();
lcd.setCursor(0, 0); 
lcd.print(" AnalogPad (R) ");
lcd.setCursor(0,1);
lcd.print(" B4 para sair ");
  do{
      lcd2.setCursor(0,2);
      lcd2.clear();
      lcd2.print("Valor: ");
      lcd2.print(analogRead(A0));
      delay(100);
  }while(digitalRead(B4) != HIGH);
lcd2.setCursor(0, 1); 
lcd2.print("AnalogPad(R) OK!");
delay(1000); 
}
/*********************************************************************/

/********* TESTE DO ACELERÔMETRO *************************************/

void testeAce(){
 char bot, 
      p1;

 int x,
     y,
     z;
lcd.clear();
lcd2.clear();
lcd.setCursor(0, 0); 
lcd.print(" Acelerometro ");
lcd.setCursor(0,1);
lcd.print(" B1+B4 para sair ");
delay(2000);

  do{
      le_ace();
      x = map(AcX, -16000, 16000, 0, 255);
      y = map(AcY, -16000, 16000, 0, 255);
      z = map(AcZ, -16000, 16000, 0, 255);
      lcd.setCursor(0,1);
      lcd.print("Base: ");
      lcd.print(x);
      lcd.print("            ");
      lcd2.setCursor(0,0);
      lcd2.print("Cotovelo: ");
      lcd2.print(y);
      lcd2.print("           ");
      lcd2.setCursor(0,1);
      lcd2.print("Pulso: ");
      lcd2.print(z);
      lcd2.print("           ");
      delay(50);
  }while((digitalRead(B) != HIGH) || (digitalRead(B4) != HIGH) );
lcd2.setCursor(0, 1); 
lcd2.print("Acelerometro OK!");
delay(1000); 


}
/*********************************************************************/


/****** FUNÇÕES DE COMANDO DOS MOTORES *******************************/

/******** FRENTE *****************************************************/

void frente(){
analogWrite(motRf, v1);
analogWrite(motRb, 0);
analogWrite(motLf, v1);
analogWrite(motLb, 0);
}

/******** GIRA PARA ESQUERDA *****************************************/

void giraE(){
analogWrite(motRf, v1);
analogWrite(motRb, 0);
analogWrite(motLf, 0);
analogWrite(motLb, v1);
}

/********** GIRA PARA DIREITA ****************************************/

void giraD(){
analogWrite(motRf, 0);
analogWrite(motRb, v1);
analogWrite(motLf, v1);
analogWrite(motLb, 0);
}

/********** MARCHA À RÉ **********************************************/

void tras(){
analogWrite(motRf, 0);
analogWrite(motRb, v1);
analogWrite(motLf, 0);
analogWrite(motLb, v1);
}

/********* CARRO PARADO *********************************************/

void para(){
analogWrite(motRf, 0);
analogWrite(motRb, 0);
analogWrite(motLf, 0);
analogWrite(motLb, 0);
}
/*********************************************************************/


/********* MOVIMENTAÇÃO DO BRAÇO COM ACELERÔMETRO ********************/
void moveBraco(){
 char bot, 
      p1;

 int x,
     y,
     z;

     le_ace();

     x = map(AcX, -15000, 15000, 0, 115);
     y = map(AcY, -15000, 15000, 128, 0);
     z = map(AcZ, -15000, 15000, 45, 165);
     Sv5.write(x);
     Sv4.write(y);
     Sv3.write(z);
}
/*********************************************************************/

/********* MOVIMENTAÇÃO DO BRAÇO Serial *******************************/

void moveBracoSerial(char port){

/*controla pulso*/

       if (port == 'u')
         
           if (pulso >= 35){
               pulso++;
             
             if (pulso >= 180)
                 pulso = 180;
             
             Sv3.write(pulso);
             lcd2.setCursor(0,1);
             lcd2.print("Levantando...   ");
             Serial.println("Levanta pulso");
         }
         
        if (port == 'D')

             if (pulso <= 180){
               pulso--;

               if (pulso <= 35)
                 pulso = 35;

               Sv3.write(pulso);
               lcd2.setCursor(0,1);
               lcd2.print("Abaixando...    ");
               Serial.println("Abaixa pulso");
          }

/* controla cotovelo */

       if (port == 'b')
         
           if (cotovelo >= 0){
               cotovelo++;
             
             if (cotovelo >= 128)
                 pulso = 128;
             
             Sv4.write(cotovelo);
             lcd2.setCursor(0,1);
             lcd2.print("Sobe cotovelo...");
             Serial.println("Subindo Cotovelo...");
         }
         
        if (port == 't')

             if (cotovelo <= 128){
               cotovelo--;

               if (cotovelo <= 35)
                 cotovelo = 0;

               Sv4.write(cotovelo);
               lcd2.setCursor(0,1);
               lcd2.print("Abaixa cotovelo ");
               Serial.println("Abaixando cotovelo...");
          }

/* controla base */

       if (port == 'h')
         
           if (base >= 0){
               base++;
             
             if (base >= 110)
                 base = 110;
             
             Sv5.write(base);
             lcd2.setCursor(0,1);
             lcd2.print("Girando direita ");
             Serial.println("Girando base...");
         }
         
        if (port == 'n')

             if (base <= 110){
               base--;

               if (base <= 0)
                 base = 0;

               Sv5.write(base);
               lcd2.setCursor(0,1);
               lcd2.print("Girando esquerda");
               Serial.println("Girando base...");

      }

/*controla pulso modo rápido*/

       if (port == 'j')
         
           if (pulso >= 35){
               pulso = pulso + 10;
             
             if (pulso >= 180)
                 pulso = 180;
             
             Sv3.write(pulso);
             lcd2.setCursor(0,1);
             lcd2.print("Levantando...   ");
             Serial.println("Levanta pulso");
         }
         
        if (port == 'k')

             if (pulso <= 180){
               pulso = pulso - 10;

               if (pulso <= 35)
                 pulso = 35;

               Sv3.write(pulso);
               lcd2.setCursor(0,1);
               lcd2.print("Abaixando...    ");
               Serial.println("Abaixa pulso");
          }

/* controla cotovelo modo rápido*/

       if (port == 'l')
         
           if (cotovelo >= 20){
               cotovelo = cotovelo + 5;
             
             if (cotovelo >= 130)
                 cotovelo = 130;
             
             Sv4.write(cotovelo);
             lcd2.setCursor(0,1);
             lcd2.print("Sobe cotovelo...");
             Serial.println("Subindo Cotovelo...");
         }
         
        if (port == 'm')

             if (cotovelo <= 130){
               cotovelo = cotovelo - 5;

               if (cotovelo <= 20)
                 cotovelo = 20;

               Sv4.write(cotovelo);
               lcd2.setCursor(0,1);
               lcd2.print("Abaixa cotovelo ");
               Serial.println("Abaixando cotovelo...");
          }

/* controla base modo rápido*/

       if (port == 'p')
         
           if (base >= 0){
               base = base + 10;
             
             if (base >= 120)
                 base = 120;
             
             Sv5.write(base);
             lcd2.setCursor(0,1);
             lcd2.print("Girando direita ");
             Serial.println("Girando base...");
         }
         
        if (port == 'q')

             if (base <= 120){
               base = base - 10;

               if (base <= 0)
                 base = 0;

               Sv5.write(base);
               lcd2.setCursor(0,1);
               lcd2.print("Girando esquerda");
               Serial.println("Girando base...");

      }



    }
/*********************************************************************/

/******* MONITORAMENTO DE OBSTÁCULOS À FRENTE ************************/

void verFrente(){
  if (usF.getDistanceCentimeter() < 20)
        if (usL.getDistanceCentimeter() < 
          usR.getDistanceCentimeter())
        {
          do{
            tras();
          }while(usF.getDistanceCentimeter() < 50);
          giraE(); 
          delay(2000);      
        }
        else{
          do{
            tras();
            moveBraco();
          }while(usF.getDistanceCentimeter() < 50);
          giraD();
          delay(2000);      
        }
         delay(50); 
}

/*********************************************************************************************/

/******* OPERAÇÃO EM MODO LOCAL PELO PAINEL LATERAL ******************/

void modoLocal(){
  lcd.clear();
  lcd2.clear();
  lcd.print(" M.U.T.A.N.T.E.    ");
  lcd.setCursor(0,1);
  lcd.print("Modo Local");
  lcd2.print("B5 para sair ");
  lcd2.setCursor(0,1);
  lcd2.print("Aguardando comando...");
delay(1000);
do{
    para();
    lcd2.setCursor(0,1);
    lcd2.print("Carro Parado... ");
    moveBraco();

if (digitalRead(B) == HIGH){
  do{
      lcd2.setCursor(0,1);
      lcd2.print("Seguindo frente ");
      Serial.println("Seguindo a frente");
      frente();
      //moveBraco();
      //verFrente();
      delay(50);
  }while(digitalRead(B) == HIGH);
}

if (digitalRead(B2) == HIGH){
  do{
      lcd2.setCursor(0,1);
      lcd2.print("Dando Re... ");
      Serial.println("Dando Re");
      tras();
      moveBraco();
      delay(50);
  }while(digitalRead(B2) == HIGH);
}

if (digitalRead(B3) == HIGH){
  do{
      lcd2.setCursor(0,1);
      lcd2.print("Girando  direita");
      Serial.println("Girando a direira");
      giraD();
      delay(50);
  }while(digitalRead(B3) == HIGH);
}

if (digitalRead(B4) == HIGH){
  do{
      lcd2.setCursor(0,1);
      lcd2.print("Girando esquerda");
      Serial.println("Girando a esquerda");
      giraE();
      delay(50);
  }while(digitalRead(B4) == HIGH);
}

delay(50);
}while(digitalRead(B5) != HIGH);
lcd2.clear();
lcd2.print("Saindo do");
lcd2.setCursor(0,1);
lcd2.print("Modo Local");
delay(2000);
}
/*********************************************************************/

/****** OPERAÇÃO PELO ANALOGPAD (R) DA LUVA ******************************/

void analogPad(){
  lcd.clear();
  lcd2.clear();
lcd.print(" M.U.T.A.N.T.E.    ");
lcd.setCursor(0,1);
lcd.print("AnalogPac (R)");
lcd2.print("B4 para sair ");
lcd2.setCursor(0,1);
lcd2.print("Aguardando comando...");

do{
para();
      lcd2.setCursor(0,1);
      lcd2.print("Carro Parado... ");

moveBraco();
if (analogRead(A0) == 0){
  do{
      lcd2.setCursor(0,1);
      lcd2.print("Seguindo frente ");
      Serial.println("Seguindo a frente");
      frente();
      
      moveBraco();
      //verFrente();

  }while(analogRead(A0) == 0);
}

if (analogRead(A0) >= 420 && analogRead(A0) <=   470){
  do{
      lcd2.setCursor(0,1);
      lcd2.print("Dando Re...     ");
      Serial.println("Dando Re");
      tras();
      moveBraco();
      delay(50);
  }while(analogRead(A0) != 0);
}

if (analogRead(A0) >= 270 && analogRead(A0) <=   290){
  do{
      lcd2.setCursor(0,1);
      lcd2.print("Girando  direita");
      Serial.println("Girando a direira");
      giraD();
      delay(50);
  }while(analogRead(A0) != 0);
}

if (analogRead(A0) >= 120 && analogRead(A0) <=   140){
  do{
      lcd2.setCursor(0,1);
      lcd2.print("Girando esquerda");
      Serial.println("Girando a esquerda");
      giraE();
      delay(50);
  }while(analogRead(A0) != 0);
}
delay(50);
}while(digitalRead(B4) != HIGH);
lcd2.clear();
lcd2.print("Saindo do modo");
lcd2.setCursor(0,1);
lcd2.print(" AnalogPad (R) ");
delay(2000);
}
/*********************************************************************/


/****** OPERAÇÃO PELO MODO SERIAL ************************************/

void opSerial(){
char d;
lcd.print("M.U.T.A.N.T.E.    ");
lcd2.print("MODO DE OPERACAO");
lcd2.setCursor(0,1);
lcd2.print(" Comando Serial ");

do{
lcd.print("M.U.T.A.N.T.E.    ");
d = Serial.read();
para();
Serial.println("Aguardando comando...");
moveBracoSerial(d);
if (d == 'f'){
  do{
      Serial.println("Indo em frente...");
      d = Serial.read();
      frente();

      moveBracoSerial(d);
      //verFrente();
  }while(d != 'x');
}

if (d == 'B'){
  do{
      Serial.println("Dando Re...");
      d = Serial.read();
      tras();
      moveBracoSerial(d);
  }while(d != 'x');
}

if (d == 'd'){
  do{
      Serial.println("Girando a direira");
      giraD();
  }while(Serial.read() != 'x');
}

if (d == 'e'){
  do{
      Serial.println("Girando a esquerda");
      giraE();
  }while(Serial.read() != 'x');
}
delay(50);
}while(d != 'F');
lcd2.clear();
lcd2.print("Saindo do");
lcd2.setCursor(0,1);
lcd2.print("Modo Serial");
Serial.println("\nSaindo do Modo Local\n");
delay(2000);

}
/*********************************************************************/

/***** MENU INICIAL **************************************************/

void menu(){
    lcd.clear();
    lcd2.clear();
    lcd.setCursor(0,0);
    lcd.print("B1: Modo Local  ");
    lcd.setCursor(0,1);
    lcd.print("B2: AnalogPad(R)");
    lcd2.setCursor(0,0);
    lcd2.print("B3: Modo Serial ");
    lcd2.setCursor(0,1);
    lcd2.print("B4: Testes");   
}
/*********************************************************************/

/***** SEQUÊNCIA DE TESTE *******************************************/

void sequenciaTeste(){
  char d;
  do{
      menuTeste();
      d = Serial.read();
  
      if ((digitalRead(B) == HIGH) || (d == 'B'))
        botoes();
      
      if ((digitalRead(B2) == HIGH) || (d == 'z'))
        testaAngl();
      
      if ((digitalRead(B3) == HIGH) || (d == 'U'))
        ultrassom();

      if ((digitalRead(B5) == HIGH) || (d == 'Z'))
        testeAce();      

      delay(50);
  }while((digitalRead(B4) != HIGH));
  
}




/*********************************************************************/

/***** MENU DE TESTE *************************************************/

void menuTeste(){
    lcd.clear();
    lcd2.clear();
    lcd.setCursor(0,0);
    lcd.print("B1: Botoeira    ");
    lcd.setCursor(0,1);
    lcd.print("B2: AnalogPad(R)");
    lcd2.setCursor(0,0);
    lcd2.print("B3: Ultrassonicos");
    lcd2.setCursor(0,1);
    lcd2.print("B4: Menu Principl");
    //sequenciaTeste();    
}
/*********************************************************************/

/****** SETUP ********************************************************/

void setup(){
lcd.begin(16, 2); //inicializa o lcd
lcd2.begin(16, 2); //inicializa o lcd
ini_ace();
Serial.begin(9600);
Banner();
usF.begin(27,25);
usR.begin(31,29);
usL.begin(35,33);
pinMode(B, INPUT);
pinMode(B2, INPUT);
pinMode(B3, INPUT);
pinMode(B4, INPUT);
pinMode(B5, OUTPUT);
pinMode(S1, OUTPUT);
pinMode(S2, OUTPUT);
pinMode(S3, OUTPUT);
pinMode(S4, OUTPUT);
pinMode(S5, OUTPUT);
Sv1.attach(S1);
Sv2.attach(S2);
Sv3.attach(S3);
Sv4.attach(S4);
Sv5.attach(S5);
}

/*********************************************************************/

/****** FUNÇÃO PRINCIPAL *********************************************/

void loop(){

  menu();
  d = Serial.read();  
  
  if ((digitalRead(B) == HIGH) || (d == 'L'))
      modoLocal();

  if ((digitalRead(B2) == HIGH) || (d == 'A'))
      analogPad();

  if ((digitalRead(B3) == HIGH) || (d == 'S'))
      opSerial();

  if ((digitalRead(B4) == HIGH) || (d == 'T'))
      sequenciaTeste();
//moveBracoSerial();
  delay(50);

}  



Atividades recentes

  • Lucas Cavalcanti

    Por favor, com­pare­cer as 15:30 no palco Sat­urno para apre­sen­tar seu projeto!

    • Sábado, 07.02.2015 00:25
    • Adalberto Oliveira

      Teste de acesso remoto, uti­lizando VNC para con­tro­lar o carro e o braço através da rede WiFi.

      • Sexta, 06.02.2015 00:00
      • Adalberto Oliveira

        Autoteste do braço robótico. Sequên­cia de inicialização.

        • Quinta, 05.02.2015 19:41
        • Adalberto Oliveira

          O carro mon­tado, uti­lizando pla­cas de acrílico nas lat­erais. O braço está desmon­tado na pâté superior.

          • Quinta, 05.02.2015 19:39
          • Adalberto Oliveira

            Detalhe das engrena­gens respon­sáveis pelo movi­mento de torção do braço, uti­lizando um cubo de bici­cleta e um par de engrena­gens e uma cor­rente de comado de motor de motocicleta.

            • Quinta, 05.02.2015 19:36
            • Adalberto Oliveira

              Detalhe do sis­tema de torção do braço.

              • Quinta, 05.02.2015 19:34
              • Adalberto Oliveira

                Ver­são 3 do braço, com a primeira ver­são da garra.

                • Quinta, 05.02.2015 19:28
                • Adalberto Oliveira

                  Rodas uti­lizadas no projeto.

                  • Quinta, 05.02.2015 19:26
                  • Adalberto Oliveira

                    Ver­são 2 do braço mon­tado na plataforma.

                    • Quinta, 05.02.2015 19:24
                    • Adalberto Oliveira

                      Ver­são 2 do braço mecânico.

                      • Quinta, 05.02.2015 19:23