Como um dos vencedores do concurso “Robotics 2016” do Instructables, recebi como prêmio da empresa iRobot, um robô aspirador Roomba Create2. Neste post, vou contar um pouco de minhas primeiras aventuras com o garoto!
O Create 2 é uma robusta e relativamente acessível plataforma para o desenvolvimento de projetos na área da robótica (pelo menos nos EUA, onde custa cerca de US $ 200). O Create2 é na verdade um Robô Aspirador de pó “Roomba” da série 660 restaurado que permite uma variedade de métodos de programação. No Brasil, mais e mais se torna comum este tipo de eletrodomésticos ( então é só esperar a mãe sair de casa e fazer alguma experiências com o rapaz ;-)
Para começar, usei um Arduino e um aplicativo Android para poder mover o robô por aí. Neste primeiro tutorial, explorarei como conectar o Arduino com o Roomba via porta serial e como comandar seus motores, LEDs e som. Em projectos futuros, explorarei seus sensores e usarei um Raspberry Pi para conectar o Roomba com a internet.
Abaixo, um rápido vídeo mostrando os meus primeiros resultados programando o Roomba:
PASSO 1: LISTA DE MATERIAIS
- iRobot “Roomba”Create2
- Arduino UNO
- módulo Bluetooth HC-06
- Botão (“Push0Button”)
- Protobard e cabos de conecção.
PASSO 2: O ROOMBA CREATE2
O Roomba é um robô do tipo diferencial, com 2 rodas e um “caster”
Sua velocidade vai até 500 mm/s e pode ser comandado para ir tanto para a frente como para trás.
Para sinalização, podemos contar com 4 displays de sete segmentos e 5 LEDs:
- Limpar (Clean)
- Local (Spot)
- Doca (Dock)
- Aviso (Warning)
- Sugeira (Dirt / Debris)
Como sensores internos, temos entre outros:
- Detector de degrau (Cliff) (4 à frente)
- Detectores de colisão (2 na frente)
- Codificadores de giro das rodas
Para a programação, deve ser usado o documento de referencia: iRobot® Create® 2 Open Interface (OI) .
O Roomba possui 3 modos de programação:
- Modo de segurança (Safe):
Libera o controle total do Roomba, com a excepção das seguintes condições de segurança:- Carregador de batería conectado e ligado.
- A detecção de uma queda de roda (ocorre quando se “levanta o Roomba do chão”).
- A detecção de um degrau de escada por exemplo, enquanto se move para a frente (ou movendo-se para trás com um raio de giro pequeno).
Se uma das condições de segurança acima ocorrem enquanto o Roomba está em modo de segurança, Roomba para todos os motores e reverte para o modo passivo.
- Modo passivo (Passive):
Ao enviar o comando Iniciar (“Start”) ou qualquer um dos comandos do modo de limpeza (por exemplo, “Spot”, “Clean”, “Seek Dock”), o Roomba entra em modo passivo. Quando o Roomba está em modo passivo, você pode solicitar e receber dados utilizando qualquer um dos comandos de sensores, mas você não pode mudar os parâmetros de comando dos atuadores (motores, som, luzes, saídas digitais, etc.) .
- Modo completo (Full):
Libera o controle completo do Roomba, a todos os seus atuadores e a todas as condições de segurança que são restritos quando o robô está em modo de segurança descritas no modo Safe.
PASSO 3: A COMUNICAÇÃO SERIAL
Para a comunicação entre o Roomba e o Arduino, será utilizada a porta serial de ambos. Por padrão, o Roomba se comunica a 115.200 bauds, mas para uma melhor comunicação com o Arduino, vamos modificar-lo para 19.200 bauds.
Existem 2 maneiras de se definir a taxa de transmissão do Roomba :
- Durante o desligamento do Roomba, continue a manter pressionado o botão central POWER/CLEAN, mesmo após a luz se apagar. Após cerca de 10 segundos, o Roomba tocará uma música com tons descendentes. A partir daí, o Roomba irá comunicar-se a 19.200 bauds até que o processador perda a energia da bateria ou a taxa de transmissão seja explicitamente alterada através de programação.
- Usar o pino 5 no conector Mini-DIN (Baud Rate Change pin) para alterar a taxa de transmissão do Roomba. Depois de ligar o Roomba, espere 2 segundos; em seguida, aplique um pulso de nivel baixo no pin5 três vezes. Cada pulso deve durar entre 50 e 500 milissegundos. O Roomba irá comunicar-se a 19200 bauds até que o processador perca a energia da bateria ou a taxa de transmissão seja explicitamente alterada por SW.
O diagrama abaixo mostra como o Arduino deve ser conectado ao conector Mini-DIN do Roomba:
Par se ter acesso ao Mini-DIN se deve remover a parte superior do Create 2 (capa verde), ou simplesmente fazer um furo na mesma.
PASSO 4: INICIALIZANDO O ROMBA
O primeiro passo a ser feito na programação de um Roomba é:
- “Acordar” o robô
- Iniciar e definir o modo de operação (Safe ou Full)
Para acordar o Roomba, devemos enviar um pulso baixo para o pino 5 do Mini-DIN (detectar dispositivo de entrada), como mostrado n
a função abaixo (ddPin é o pin 5 do Arduino conectado ao pin% do Roomba):
void wakeUp (void)
{
digitalWrite(ddPin, HIGH);
delay(100);
digitalWrite(ddPin, LOW);
delay(500);
digitalWrite(ddPin, HIGH);
delay(2000);
}
Para iniciar o Roomba, sempre devem ser enviados 2 códigos :
“START” [128] e o modo, no nosso caso “modo de segurança” [131]. Se você quizer o “modo completo”, deve enviar o código [132].
void startSafe()
{
Roomba.write(128); //Start
Roomba.write(131); //Safe mode
delay(1000);
}
PASSO 5: ACIONAR OS LEDS E DISPLAY
Ligando os LEDs
Conforme descrito na introdução, o Roomba possui 5 LEDs:
- POWER/CLEAN (bicolor vermelho / verde e intensidade controlada)
- SPOT (Verde, intensidade fixa)
- DOVK (verde, a intensidade fixa)
- WARNING / Check (Laranja, intensidade fixa)
- DIRT (azul, intensidade fixa)
Todos os LEDs podem ser comandados usando o código [139]
Para controlar o LED POWER/CLEAN, você deve enviar dois bytes de dados para o Roomba: “cor” e “intensidade”.
- Cor:
- Verde = 0
- Laranja = 128
- vermelho = 255
- Intensidade:
- Min = 0
- Max = 255
A função setPowerLED (byte setColor, byte setIntensity) faz isso automaticamente:
void setPowerLED(byte setColor, byte setIntensity)
{
color = setColor;
intensity = setIntensity;
Roomba.write(139);
Roomba.write((byte)0x00);
Roomba.write((byte)color);
Roomba.write((byte)intensity);
}
Por exemplo, para acender o LED POWER com cor de laranja e na metade de sua intensidade maxima, você pode chamar a função como abaixo:
setPowerLED (128, 128);
Para acender os restantes 4 LEDs, devem ser utilizadas as funções:
setDebrisLED (ON);
setDockLED (ON);
setSpotLED (ON);
setWarningLED (ON);
Todas as funções acima tem um código semelhante a este:
void setDebrisLED(bool enable)
{
debrisLED = enable;
Roomba.write(139);
Roomba.write((debrisLED ? 1 : 0) + (spotLED ? 2 : 0) + (dockLED ? 4 : 0) + (warningLED ? 8 : 0));
Roomba.write((byte)color);
Roomba.write((byte)intensity);
}
Basicamente, a diferença estará na linha:
debrisLED = enable;
a qual deverá ser alterada permitindo (“enabling”) que cada um dos outros LEDs (spotLED, dockLED, warningLED) acenda.
Envio de mensagens a serem mostradas
O Roomba possui quatro Displays de 7 Segmentos que você podem ser usados para enviar mensagens de duas maneiras diferentes:
- Código [163]: LEDs com dígitos numéricos (“Raw”)
- Código [164]: LEDs com dígitos ASCII (aproximação de letras e códigos especiais)
Para exibir números é muito facil. Você apenas deve enviar o código [163], seguido dos 4 dígitos a serem exibidos. A função:
setDigitLEDs (digit1 byte, digit2 byte, digit3 byte, byte digit4)
faz isso para você:
void setDigitLEDs(byte digit1, byte digit2, byte digit3, byte digit4)
{
Roomba.write(163);
Roomba.write(digit1);
Roomba.write(digit2);
Roomba.write(digit3);
Roomba.write(digit4);
}
Por exemplo, para exibir “1, 2, 3, 4”, basta chamar a função:
setDigitLEDs (1, 2, 3, 4);
Com o código [164], é possível aproximação de envio de ASCII.
A função: setDigitLEDFromASCII(byte digit, char letter) faz isso para nós:
void setDigitLEDFromASCII(byte digit, char letter)
{
switch (digit)
{
case 1:
digit1 = letter;
break;
case 2:
digit2 = letter;
break;
case 3:
digit3 = letter;
break;
case 4:
digit4 = letter;
break;
}
Roomba.write(164);
Roomba.write(digit1);
Roomba.write(digit2);
Roomba.write(digit3);
Roomba.write(digit4);
}
Para simplificar, criei uma nova função que pode ser utilizada para enviar os 4 dígitos ao mesmo tempo:
void writeLEDs (char a, char b, char c, char d)
{
setDigitLEDFromASCII(1, a);
setDigitLEDFromASCII(2, b);
setDigitLEDFromASCII(3, c);
setDigitLEDFromASCII(4, d);
}
Por exemplo, para exibir “STOP”, você deve chamar a função:
writeLEDs ( 's', 't', 'o', 'p');
PASSO 6: PILOTANDO O ROOMBA PELA CASA
Para sua mobilidade, o Roomba possui 2 motores DC independentes que podem ser programados para rodar a uma velocidade de até 500 mm/s. Existem vários comandos que podem ser usados para dirigir o robô. Os principais são:
- Código [137]: Drive ==> devem ser enviados: +/- velocidade em mm/s e +/- Radius em mm
- Código [145]: Direct Drive ==> deve ser enviado velocidade à Esquerda/Direita em mm/s (+ para a frente e – para trás)
- Código [146]: Drive PWM ==> devem ser enviados +/- dados PWM individualmente para as rodas esquerda e direita.
Abaixo o código para essas 3 opções descritas anteriormente:
void drive(int velocity, int radius)
{
clamp(velocity, -500, 500); //def max and min velocity in mm/s
clamp(radius, -2000, 2000); //def max and min radius in mm
Roomba.write(137);
Roomba.write(velocity >> 8);
Roomba.write(velocity);
Roomba.write(radius >> 8);
Roomba.write(radius);
}
//---------------------------------------------------------------
void driveWheels(int right, int left)
{
clamp(right, -500, 500);
clamp(left, -500, 500);
Roomba.write(145);
Roomba.write(right >> 8);
Roomba.write(right);
Roomba.write(left >> 8);
Roomba.write(left);
}
//---------------------------------------------------------------
void driveWheelsPWM(int rightPWM, int leftPWM)
{
clamp(rightPWM, -255, 255);
clamp(leftPWM, -255, 255);
Roomba.write(146);
Roomba.write(rightPWM >> 8);
Roomba.write(rightPWM);
Roomba.write(leftPWM >> 8);
Roomba.write(leftPWM);
}
Note que a função “clamp” define os valores máximos e mínimos que são permitidos para como entrada. Essa função é definida no arquivorombaDefines.h :
#define clamp(value, min, max) (value < min ? min : value > max ? max : value)
Usando os códigos descritos acima, funções mais simples podem ser criadas para mover o Roomba:
void turnCW(unsigned short velocity, unsigned short degrees)
{
drive(velocity, -1);
clamp(velocity, 0, 500);
delay(6600);
drive(0,0);
}
//---------------------------------------------------------------
void turnCCW(unsigned short velocity, unsigned short degrees)
{
drive(velocity, 1);
clamp(velocity, 0, 500);
delay(6600);
drive(0,0);
}
//---------------------------------------------------------------
void driveStop(void)
{
drive(0,0);
}
//---------------------------------------------------------------
void driveLeft(int left)
{
driveWheels(left, 0);
}
//---------------------------------------------------------------
void driveRight(int right)
{
driveWheels(0, right);
}
Note-se que para se obter um valor de ângulo correto, o argumento da função “delay” deve ser calculada especificamente para uma dada velocidade (o método de tentativa e erro é a melhor opção aqui).
Abaixo alguns exemplos que podem ser utilizados para testar os motores:
turnCW (40, 180); // spin clockwise 180 degrees and stop
driveWheels(20, -20); // spin
driveLeft(20); // turning left
Para testar os motores, é bom adicionar um botão externo (no meu caso ligado ao Arduino pino 12), de modo a que você possa baixar o código para o Arduino, iniciando o Roomba, mas parando a execução até que o botão seja é pressionado.
Abaixo, simples exemplo de um código de testes para os motores utilizando-se Arduino (observe que para o codigo ser executado, funções e definições discutidas nos steps anteriores deverão ser utilizadas):
Você precisa ser um membro de Laboratorio de Garagem (arduino, eletrônica, robotica, hacking) para adicionar comentários!
Entrar em Laboratorio de Garagem (arduino, eletrônica, robotica, hacking)