Trabalho Prático 4
Introdução
Neste trabalho o robô foi preparado para as diversas tarefas a serem realizadas na competição de final de curso. Após diversas mudanças estruturais completas, feitas em decorrência da alteração constante das regras da competição, estabeleceu-se uma estrutura composta por: shaft encoders, sensores de luz ambiente, sensores de luz polarizada, sensores de luz de partida, desligamento após 60 segundos, leitores de cor do bloco, uma garra e uma catapulta dupla. A estratégia adotada para a competição consistiu em, após feita a calibração inicial, que armazena o valor da luz ambiente e orienta o robô em relação à luz polarizada oposta à sua posição, andar em linha reta até se chegar à base da ponte, para em seguida disparar a dupla catapulta, num total de quatro bolas.
Mudanças estruturais
A maior parte das funções do robô já havia sido implementada em outros trabalhos, as adições para este trabalho consistindo na montagem da garra e da catapulta dupla.
Catapulta dupla
Uma vez que o mecanismo de localização da fonte de luz polarizada já foi criado e implementado com sucesso no trabalho passado, bastou criar a catapulta e o algoritmo para fazer o lançamento das bolas na direção correta. O mecanismo é simples: o motor gira uma alavanca que faz com que, através de três reduções, toda a estrutura da catapulta gire, de modo a fazê-la arremessar as bolas armazenadas em suas pás, sendo duas bolas por pá. O rearmamento da catapulta é manual, através do puxar de uma corda que prende a catapulta. Como resultado, obteve-se uma catapulta dupla que conseguia atirar a bola com força e precisão razoáveis, fazendo com que esta alcançasse uma boa distância.
Deslocamento orientado por Shaft Encoder
Conforme explicado na documentação dos trabalhos práticos anteriores, o Shaft Encoder é um sensor que, ao ser colocado adjacente à roda do robô, conta o número de rotações realizadas por ela. Se for considerada a margem de erro decorrente de rotações sem deslocamento que a roda realizar, em virtude da ausência de atrito com o piso, pode-se assim determinar, com razoável precisão, a distância deslocada pelo robô.
Neste caso, o robô foi programado para, em momentos distintos, girar em torno de si mesmo e andar em linha reta.
Garra
Um motor separado faz com que a estrutura da garra gire em torno de um eixo, num movimento pré estabelecido que vai até quase o piso. O bloco, já previamente detectado e posicionado em frente ao robô, é preso na garra entre duas borrachas flexíveis, que permitem a entrada do cubo na garra mas não sua saída. Elásticos presos à garra fazem com que ela volte, em seguida, à posição inicial.
Software do projeto
#include sencdr6.icb #include sencdr0.icb #define MOTOR_R 3 #define MOTOR_L 0 #define MOTOR_C 2 #define MOTOR_T 1 //#define SENS_OPT_B 10 #define SENS_OPT_L 11 #define SENS_OPT_R 13 #define SENS_OPT_X 15 #define SENS_DIF 5 #define SENS_CDR 2 #define SENS_COL 3 #define SENS_BRE 14 #define SEN_START 9 #define RED 0 #define GREEN 1 #define BLUE 2 #define YELLOW 3 #define BLACK 4 #define TODOS 5 #define LED_R 0b00100000 #define LED_G 0b00000100 #define LED_B 0b00001000 #define LED_SENS 0b00010000 #use "cmucamlib.ic" char buff[11]; int vermelho, verde, azul, amarelo, preto,tempoEmp; char menu_principal[3][30]={"Menu: Orientar","Menu: Seguir Linha", "Menu: Invadir e Capturar"}; char menu_seguir_luz[2][30]={"Menu: Vertical","Menu: Horizontal"}; char menu_seguir_linha[6][30]={"Vermelho", "Verde", "Azul", "Amarelo", "Preto", "Todos"}; char menu_algoritmo[2][30]={"1","2"}; int rei = -10; int soldado = -20; int main(){ int sel, th,algo; vermelho = 3; verde = 2; azul = 0; amarelo = 1; preto = 3; printf("Parallel Mind - Press START\n"); while(!start_button()); poke(0x1009, 0x3c); bit_clear(0x1008, LED_R); bit_clear(0x1008, LED_G); bit_clear(0x1008, LED_B); bit_clear(0x1008, LED_SENS); bit_set(0x1008, LED_SENS); sel = select_string(menu_principal, 3); if(sel==0){ bit_clear(0x1008, LED_R); bit_clear(0x1008, LED_G); bit_clear(0x1008, LED_B); bit_clear(0x1008, LED_SENS); sel = select_string(menu_seguir_luz, 2); while(!digital(SEN_START)); if(sel==0){ th = start_process(orienta_vertical()); sleep(60.0); kill_process(th); ao(); } else if(sel==1){ th = start_process(orienta_horizontal()); sleep(60.0); kill_process(th); ao(); } } else if(sel==1){ sel = select_string(menu_seguir_linha, 6); // vermelho, verde, azul, amarelo, preto, todos; th = start_process(segue_linha(sel)); sleep(60.0); kill_process(th); ao(); bit_clear(0x1008, LED_R); bit_clear(0x1008, LED_G); bit_clear(0x1008, LED_B); bit_clear(0x1008, LED_SENS); bit_set(0x1008, LED_SENS); } else if(sel==2){ sel = select_string(menu_seguir_luz, 2); algo = select_string(menu_algoritmo,2); while(!digital(SEN_START)); th = start_process(executa_tarefa(sel, algo)); sleep(60.0); kill_process(th); ao(); } printf("I See You! Good Night!\n"); } void executa_tarefa(int luz, int algoritmo){ if(luz == 0){ orienta_vertical(); soldado = -10; rei = -10; } else { orienta_horizontal(); soldado = -10; rei = -10; } andaPraFrente(900); ao(); msleep(10L); motor(MOTOR_T, 100); msleep(1000L); ao(); msleep(10L); if(algoritmo == 0){ } else if(algoritmo == 1){ motor(MOTOR_L,-50); motor(MOTOR_R,-50); msleep(2000L); ao(); } else if(algoritmo == 2){ } } void pega_bloco(){ motor(MOTOR_C, 100); msleep(2000L); off(MOTOR_C); motor(MOTOR_C, -100); msleep(1500L); off(MOTOR_C); } int detecta_cor(){ int i, red, green, blue; int color_limit[5][3][2]; color_limit[RED][RED][0]= 135; color_limit[RED][RED][1]= 203; color_limit[RED][GREEN][0]= 199; color_limit[RED][GREEN][1]= 240; color_limit[RED][BLUE][0]= 165; color_limit[RED][BLUE][1]= 235; color_limit[GREEN][RED][0]= 195; color_limit[GREEN][RED][1]= 235; color_limit[GREEN][GREEN][0]= 118; color_limit[GREEN][GREEN][1]= 189; color_limit[GREEN][BLUE][0]= 155; color_limit[GREEN][BLUE][1]= 215; color_limit[BLUE][RED][0]= 220; color_limit[BLUE][RED][1]= 255; color_limit[BLUE][GREEN][0]= 185; color_limit[BLUE][GREEN][1]= 220; color_limit[BLUE][BLUE][0]= 95; color_limit[BLUE][BLUE][1]= 185; color_limit[YELLOW][RED][0]= 120; color_limit[YELLOW][RED][1]= 170; color_limit[YELLOW][GREEN][0]= 120; color_limit[YELLOW][GREEN][1]= 184; color_limit[YELLOW][BLUE][0]= 145; color_limit[YELLOW][BLUE][1]= 215; color_limit[BLACK][RED][0]= 204; color_limit[BLACK][RED][1]= 250; color_limit[BLACK][GREEN][0]= 190; color_limit[BLACK][GREEN][1]= 228; color_limit[BLACK][BLUE][0]= 185; color_limit[BLACK][BLUE][1]= 215; analog(SENS_COL); i = 0; bit_clear(0x1008, LED_R); bit_clear(0x1008, LED_G); bit_clear(0x1008, LED_B); msleep(10L); bit_set(0x1008, LED_R); red = 0; while(i < 50){ red += analog(SENS_COL); msleep(5L); i++; } i = 0; bit_clear(0x1008, LED_R); bit_clear(0x1008, LED_G); bit_clear(0x1008, LED_B); msleep(10L); bit_set(0x1008, LED_G); green = 0; while(i < 50){ green += analog(SENS_COL); msleep(5L); i++; } i = 0; bit_clear(0x1008, LED_R); bit_clear(0x1008, LED_G); bit_clear(0x1008, LED_B); msleep(10L); bit_set(0x1008, LED_B); blue = 0; while(i < 50){ blue += analog(SENS_COL); msleep(5L); i++; } red = red/50; green = green/50; blue = blue/50; printf("\n"); printf("r:%d g:%d b:%d", red, green, blue); bit_clear(0x1008, LED_R); bit_clear(0x1008, LED_G); bit_clear(0x1008, LED_B); if(color_limit[RED][RED][0] < red && color_limit[RED][RED][1] > red && color_limit[RED][GREEN][0] < green && color_limit[RED][GREEN][1] > green && color_limit[RED][BLUE][0] < blue && color_limit[RED][BLUE][1] > blue){ printf("red\n"); return RED; }else if(color_limit[GREEN][RED][0] < red && color_limit[GREEN][RED][1] > red && color_limit[GREEN][GREEN][0] < green && color_limit[GREEN][GREEN][1] > green && color_limit[GREEN][BLUE][0] < blue && color_limit[GREEN][BLUE][1] > blue){ printf("green\n"); return GREEN; }else if(color_limit[BLUE][RED][0] < red && color_limit[BLUE][RED][1] > red && color_limit[BLUE][GREEN][0] < green && color_limit[BLUE][GREEN][1] > green && color_limit[BLUE][BLUE][0] < blue && color_limit[BLUE][BLUE][1] > blue){ printf("blue\n"); return BLUE; }else if(color_limit[YELLOW][RED][0] < red && color_limit[YELLOW][RED][1] > red && color_limit[YELLOW][GREEN][0] < green && color_limit[YELLOW][GREEN][1] > green && color_limit[YELLOW][BLUE][0] < blue && color_limit[YELLOW][BLUE][1] > blue){ printf("yellow\n"); return YELLOW; }else if(color_limit[BLACK][RED][0] < red && color_limit[BLACK][RED][1] > red && color_limit[BLACK][GREEN][0] < green && color_limit[BLACK][GREEN][1] > green && color_limit[BLACK][BLUE][0] < blue && color_limit[BLACK][BLUE][1] > blue){ printf("black\n"); return BLACK; }else{ printf("fuuuu\n"); return -1; } return 0; } void andaReto(int dist){ int rodou = 0; motor(MOTOR_L, 80); motor(MOTOR_R, 80); while(rodou<dist){ rodou++; msleep(1L); } off(MOTOR_L); off(MOTOR_R); } void andaPraFrente(int counts){ int cor; int i, j; int rodou0; int rodou1; int app=0; int furos; int speed; int VMOTOR_0; int VMOTOR_1; int inv0; int inv1; int bloquinho; inv0 = 0; inv1 = 0; rodou0 = 0; rodou1 = 0; furos = 6; speed = 80; encoder0_counts = 0; encoder6_counts = 0; VMOTOR_0 = speed; VMOTOR_1 = speed; i = 0; if (inv0) VMOTOR_0 = -speed; if (inv1) VMOTOR_1 = -speed; while(rodou0<counts){ i++; rodou0 += encoder6_counts; rodou1 += encoder0_counts; if (encoder0_counts < furos){ if(inv0) VMOTOR_0 -= 4; else VMOTOR_0 += 4; } else if (encoder0_counts > furos){ if(inv0)VMOTOR_0 += 4; else VMOTOR_0 -= 4; } if (encoder6_counts < furos){ if(inv1) VMOTOR_1 -= 4; else VMOTOR_1 += 4; } else if (encoder6_counts > furos){ if(inv1)VMOTOR_1 += 4; else VMOTOR_1 -= 4; } encoder0_counts = 0; encoder6_counts = 0; motor(MOTOR_L,VMOTOR_0); motor(MOTOR_R,VMOTOR_1); msleep(50L); } off(MOTOR_L); off(MOTOR_R); msleep(200L); } void andaPraFrenteCor(int counts){ int cor; int i, j; int rodou0; int rodou1; int app=0; int furos; int speed; int VMOTOR_0; int VMOTOR_1; int inv0; int inv1; int bloquinho; inv0 = 0; inv1 = 0; rodou0 = 0; rodou1 = 0; furos = 6; speed = 80; encoder0_counts = 0; encoder6_counts = 0; VMOTOR_0 = speed; VMOTOR_1 = speed; i = 0; if (inv0) VMOTOR_0 = -speed; if (inv1) VMOTOR_1 = -speed; while(rodou0<counts){ i++; rodou0 += encoder6_counts; rodou1 += encoder0_counts; bloquinho = detectacor(); if(cor == rei || cor == soldado){ pega_bloco(); ao(); } else if(cor != -1){ } if (encoder0_counts < furos){ if(inv0) VMOTOR_0 -= 4; else VMOTOR_0 += 4; } else if (encoder0_counts > furos){ if(inv0)VMOTOR_0 += 4; else VMOTOR_0 -= 4; } if (encoder6_counts < furos){ if(inv1) VMOTOR_1 -= 4; else VMOTOR_1 += 4; } else if (encoder6_counts > furos){ if(inv1)VMOTOR_1 += 4; else VMOTOR_1 -= 4; } encoder0_counts = 0; encoder6_counts = 0; motor(MOTOR_L,VMOTOR_0); motor(MOTOR_R,VMOTOR_1); msleep(50L); } off(MOTOR_L); off(MOTOR_R); msleep(200L); } void giraRobo(int direction, int counts){ int i, j; int rodou0; int rodou1; int app=0; int furos; int speed; int VMOTOR_0; int VMOTOR_1; int inv0; int inv1; inv0 = 0; inv1 = 0; rodou0 = 0; rodou1 = 0; furos = 3; speed = 50; encoder0_counts = 0; encoder6_counts = 0; VMOTOR_0 = speed; VMOTOR_1 = speed; i = 0; if(direction){ inv1=1; } else { inv0=1; } if (inv0) VMOTOR_0 = -speed; if (inv1) VMOTOR_1 = -speed; while(rodou0 < counts ){ i++; motor(MOTOR_L,VMOTOR_0); motor(MOTOR_R,VMOTOR_1); rodou0 += encoder0_counts; rodou1 += encoder6_counts; if (encoder0_counts < furos){ if(inv0) VMOTOR_0 -= 15; else VMOTOR_0 += 15; } else if (encoder0_counts > furos){ if(inv0)VMOTOR_0 += 15; else VMOTOR_0 -= 15; } if (encoder6_counts < furos){ if(inv1) VMOTOR_1 -= 15; else VMOTOR_1 += 15; } else if (encoder6_counts > furos){ if(inv1)VMOTOR_1 += 15; else VMOTOR_1 -= 15; } encoder0_counts = 0; encoder6_counts = 0; msleep(25L); } off(MOTOR_L); off(MOTOR_R); msleep(200L); } void orienta_vertical(){ int light, polarizada, max=1000, value,valuec, count; motor(MOTOR_R, -70); motor(MOTOR_L, 70); count = 0; while(count < 300){ value = analog(SENS_DIF); valuec = analog(SENS_CDR); if(max > value+valuec){ max = value+valuec; } msleep(20L); count++; //printf("%d %d\n",max,count); printf("%d %d\n",value,valuec); } printf("saiiiii\n"); count = 0; max = max + 10; while(1){ value=analog(SENS_DIF); valuec=analog(SENS_CDR); //printf("%d %d\n",max,value); printf("%d %d\n",value,valuec); if( value+valuec< max){ //andaReto(10000); ao(); msleep(10L); break; } msleep(50L); } return; } void orienta_horizontal(){ int light, polarizada, min=0, value, valuec, count; motor(MOTOR_R, -70); motor(MOTOR_L, 70); count = 0; while(count < 300){ value = analog(SENS_DIF); valuec = analog(SENS_CDR); if(min < 1000 + value - valuec){ min = 1000 + value - valuec; } msleep(20L); count++; //printf("%d %d\n",min,count); printf("%d %d\n",value,valuec); } printf("saiiiii\n"); count = 0; min = min - 10; while(1){ value=analog(SENS_DIF); valuec = analog(SENS_CDR); //printf("%d %d\n",min,value); printf("%d %d\n",value,valuec); if(1000 + value - valuec > min){ //andaReto(10000); ao(); msleep(10L); break; } msleep(50L); } return; } int detectacor(){ int cor; bit_clear(0x1008, LED_R); bit_clear(0x1008, LED_G); bit_clear(0x1008, LED_B); bit_clear(0x1008, LED_SENS); bit_set(0x1008, LED_SENS); if(digital(SENS_BRE) == 0){ motor(MOTOR_R ,0); motor(MOTOR_L ,0); bit_clear(0x1008, LED_R); bit_clear(0x1008, LED_G); bit_clear(0x1008, LED_B); bit_clear(0x1008, LED_SENS); cor=detecta_cor(); while(cor==-1){ cor=detecta_cor(); } } else{ cor=-1; } //mateus pitoco bit_clear(0x1008, LED_R); bit_clear(0x1008, LED_G); bit_clear(0x1008, LED_B); bit_clear(0x1008, LED_SENS); bit_set(0x1008, LED_SENS); return(cor); } void battlefield(){ while(1){ andaPraFrente(800); msleep(100L); } } void segue_linha(int rei){ int rodou0, rodou1, VMOTOR_0, VMOTOR_1, furos, speed, i, slow, threshold, newOptB; int antOptL, antOptR, newOptX; //int antOptB; int newOptL, newOptR; int state, fora, dentro,cor=0,acao=0; antOptL = digital(SENS_OPT_L); antOptR = digital(SENS_OPT_R); //antOptB = digital(SENS_OPT_B); furos = 45; speed = 80; slow = 0; threshold = 80; state = 0; fora = 1; dentro = 0; while(1){ newOptL = digital(SENS_OPT_L); newOptR = digital(SENS_OPT_R); newOptX = digital(SENS_OPT_X); if (newOptX == 0){ msleep(10L); newOptX = digital(SENS_OPT_X); if (newOptX == 0){ ao(); break; } } if (antOptL == dentro && antOptR == dentro){ if (newOptL == fora && newOptR == dentro /*&&(newOptB == dentro || (antOptB == fora && newOptB == fora))*/){ state = 2; printf("direita | %d | %d \n", newOptL, newOptR); } else if (newOptL == dentro && newOptR == fora /*&& (newOptB == dentro || (antOptB == fora && newOptB == fora))*/){ state = 1; printf("esquerda | %d | %d \n", newOptL, newOptR); } else if (newOptL == dentro && newOptR == dentro){ state = 0; printf("adiante | %d | %d \n", newOptL, newOptR); } } else if(antOptL == dentro && antOptR == fora){ if (newOptL == fora && newOptR == fora){ state=1; } }else if(antOptL == fora && antOptR == dentro){ if (newOptL == fora && newOptR == fora){ state=2; } }else printf("ignorar | %d | %d \n", newOptL, newOptR); switch(state){ case 0: //continua reto encoder0_counts = 0; encoder6_counts = 0; VMOTOR_0 = speed; VMOTOR_1 = speed; if (encoder0_counts < furos){ VMOTOR_0 += 4; } else if (encoder0_counts > furos){ VMOTOR_0 -= 4; } if (encoder6_counts < furos){ VMOTOR_1 += 4; } else if (encoder6_counts > furos){ VMOTOR_1 -= 4; } encoder0_counts = 0; encoder6_counts = 0; motor(MOTOR_R ,VMOTOR_0); motor(MOTOR_L ,VMOTOR_1); case 1: //desvia para esquerda motor(MOTOR_L, slow); motor(MOTOR_R, speed); break; case 2: //desvia para direita motor(MOTOR_L, speed); motor(MOTOR_R, slow); break; case 3: break; } antOptL = newOptL; antOptR = newOptR; } } /****************************** hbmenu.c ********************************/ /* Menu functions which also allow variables to be set via the knob and selection buttons Version 1.0 Written for MIT 6.270 contest by Anne Wright 11/14/1991 Version 2.0 Converted for Handy Board for Botball by Anne Wright 1/13/2001 */ /* abstractions for chosen_button */ #define NEITHER_B 0 #define START_B 1 #define STOP_B 2 /* abstractions for wait_button */ #define UP_B 3 #define DOWN_B 4 #define CYCLE_B 5 /*****************************button routines*************************/ /* Return minimum of two integers */ /* defined in cmucam3.ic which is loaded by this file -dpm 1/03 int min(int a,int b) { if(a<b) return(a); else return(b); } */ /* Return minimum of two floats */ float fmin(float a,float b) { if(a<b) return(a); else return(b); } /* Returns which button is depressed using definitions above. If both are pressed, start has precedence */ int chosen_button() { if(start_button()) return START_B; else if(stop_button()) return STOP_B; else return NEITHER_B; } /* wait until button is depressed(DOWN_B), released(UP_B), or both(CYCLE_B) and return which button if any activated the sequence */ int wait_button(int i) { if(i==DOWN_B){ while(!(start_button() || stop_button())); return chosen_button(); } else if (i==UP_B) { int b; b=chosen_button(); while(start_button() || stop_button()); return b; } else { int b; while(!(start_button() || stop_button())); b=chosen_button(); while(start_button() || stop_button()); return b; } } /********************* Knob to Number routines*****************************/ /* Returns an integer value from min_val to max_val based on the current position of the knob */ int knob_int_value(int min_val,int max_val) { int val, coarseness=(255)/(max_val-min_val),selection; val=min((knob())/coarseness+min_val,max_val); return min(val,max_val); } /* Returns an float value from min_val to max_val based on the current position of the knob */ float knob_float_value(float min_val,float max_val) { float val, coarseness=(255.)/(max_val-min_val),selection; val=fmin(((float)knob())/coarseness+min_val,max_val); return fmin(val,max_val); } /******************** Menu selection routines ****************************/ /* While waiting for a button press, display the string passed in and the val, the integer value betwen min_val and max_val for the knob. If the button pressed is the start button, returns the final value of val. If the button pressed is the stop button, returns -1. */ int select_int_value(char s[],int min_val,int max_val) { int val, button; printf("%s %d to %d\n",s,min_val, max_val); sleep(0.8); /* Wait until no button is pressed */ wait_button(UP_B); /* While no button is pressed, display the string passed in and the current value of val */ while((button = chosen_button())==NEITHER_B) { val=knob_int_value(min_val,max_val); printf("%s %d\n",s,val); msleep(100L); } /* Wait until no button is pressed */ wait_button(UP_B); if(button==STOP_B) return(-1); /** -1 means stop pressed -- do not reset value **/ else return(val); /* Stop not pressed, return val */ } /* While waiting for a button press, display the string passed in and the val, the float value betwen min_val and max_val for the knob. If the button pressed is the start button, returns the final value of val. If the button pressed is the stop button, returns -1. */ float select_float_value(char s[],float min_val,float max_val) { float val; int button; printf("%s %f to %f\n",s,min_val, max_val); sleep(0.8); /* Wait until no button is pressed */ wait_button(UP_B); /* While no button is pressed, display the string passed in and the current value of val */ while((button = chosen_button())==NEITHER_B) { val=knob_float_value(min_val,max_val); printf("%s %f\n",s,val); msleep(100L); } /* Wait until no button is pressed */ wait_button(UP_B); if(button==STOP_B) return(-1.0); /** -1 means stop pressed -- do not reset value **/ else return(val); /* Stop not pressed, return val */ } /* While waiting for a button press, display the string from the array of strings passed in which corresponds to the current position of the knob (see select_int_value). If the button pressed is the start button, returns the index of the string selected (0 to n-1). If the button pressed is the stop button, returns -1. */ int select_string(char choices[][],int n) { int selection,last_selection=-1,button; if(n>_array_size(choices)) n=_array_size(choices); /* Wait until no button is pressed */ wait_button(UP_B); /* While no button is pressed, display the string from the array of strings passed in which corresponds to the current position of the knob */ while((button = chosen_button())==NEITHER_B) { selection=knob_int_value(0,n-1); if(selection!=last_selection) { printf("%s\n",choices[selection]); msleep(150L); last_selection=selection; } } /* Wait until no button is pressed */ wait_button(UP_B); if(button==STOP_B) return(-1); /** -1 means stop pressed -- do not reset value **/ else return(selection); /* Stop not pressed, return val */ } /* * Local variables: * comment-column: 40 * c-indent-level: 4 * c-basic-offset: 4 * End: */
Conclusão
Neste trabalho o robô, após diversas montagens e remontagens, acabou por possuir, em sua versão final, uma estrutura apenas levemente diferente das dos trabalhos anteriores. Alguns algoritmos foram removidos e ele obteve uma catapulta dupla e e uma garra de pegar blocos.
Referências
MARTIN, Fred G. Interactive C User's Guide MIT Media Laboratory. Manual Edition 0.9. 1997.
MARTIN, Fred G. Robotic Explorations: An Introduction to Engineering Through Design. Prentice Hall; ISBN: 0-130-89568-7.
MARTIN, Fred G. The Handy Board Technical Reference. at
http://handyboard.com/oldhb/techdocs/hbmanual.pdf
MARTIN, Fred G. The Art of LEGO Design. Journal for Robot Builders,
volume 1, number 2. March 15, 1995