czech english

ATmega8 board

dokumentace k desce, uživatelský manuál a další revize

Čip ATmega8 se ukázal jako vhodný pro první experimenty s robotikou i jako interface pro složitější zařízení. Z tohoto důvodu vznikla deska s označením ATMEGA8_BOARD, kterou již několik robotů obsahuje. Nic není nikdy dokonalé, a tak se zde pokusíme shrnout základní problémy a plány do budoucna.

Popis

Deska v zásadě plní dvě funkce: umožňuje přístup ke všem pinům čipu ATmega8 a zajišťuje spolehlivou komunikaci s ostatními zařízeními pomocí RS-232 (to má na starosti část obvodu s čipem MAX232 a několika kondenzátory).
DIP (Dual-inline package) verze čipu ATmega8 má 28 pinů, vlastní oscilátor a očekává napájení 5V. K základnímu provozu tedy stačí připojit zem a 5V (buď regulované přes 7805, nebo pomocí např. čtyř tužkových baterií). Je také možné použít L-verzi, která má nižší spotřebu a běží i na nižších napětích (2.7-5.5V). V nejtriviálnější verzi tedy stačí čip napájet a už je schopen akce.

Vstupy a výstupy

Z 28mi pinů je 5 pro napájení a referenci pro analogové vstupy. Zbývá tedy 23 univerzálních I/O pinů, které jsou všechny na desce dostupné. Pokud budeme postupovat podle čísel jednotlivých pinů (tj. proti směru hodinových ručiček od U-značky na čipu), tak nejprve máme 5 digiálních vstupů (PD0-PD4) [na fotografii jsou dole uprostřed]. Vstupy PD0 a PD1 ale nedoporučujeme používat, protože plní funci vysílání a příjmu na RS-232. Další zapojení je ve dvojici vždy se zemí, kde signál je blíže k čipu a na obvodu desky je zem.
Následuje blok pro řízení serv [vpravo dole]. Každé servo potřebuje napájení, zem a signál. Společné externí napájení serv je řešeno pomocí dvojpinu v pravém dolním rohu. Opět signál je nejblíže k čipu, externích 5V uprostřed a zem na obvodu desky. I u tohoto bloku je ale „malá zrada”. Zaprvé jednotlivé konektory odpovídají pinům z obou stran čipu a to v pořadí: PB6, PB7, PD5, PD6, PB2, PD7, PB1, PB0. Dále je na pin PB0 připojena červená LEDka, vhodná jako indikace fungujícího programu, a proto není rozumné na první pozici nic jiného zapojovat.
Postupujeme-li proti směru hodinových ručiček, tak další blok je 2x3 konektor na programování čipu pomocí paralelního kabelu [vpravo nahoře]. Zde jsou vyvedeny piny PC6/RESET, PB3/MOSI, PB4/MISO, PB5/SCK společně se zemí a 5V. Opět nedoporučujeme používat tyto piny k ničemu jinému, než programování čipu.
Poslední blok [uprostřed nahoře] obsahuje všech 6 analogových vstupů, které jsou vyvedeny společně s napájením a zemí (signál je vždy nejblíže k čipu, 5V je uprostřed a zem na obvodu desky). Zde snad jenom poznámka, že vstupy PC4 a PC5 lze použít také pro I2C komunikaci mezi čipy (TWI—two wire interface).

Použití desky

Deska zatím byla použita na několika robotech. Popis robotů lze najít na odpovídajících odkazech — zde se zaměříme pouze na zapojení jednotlivých senzorů/efektorů a připadné zkušenosti ve vztahu k první verzi desky.

Faethon

Faethon je dálkově ovládaný robot pomocí standardního modelářského vysílače. Zde bylo třeba převést signály z přijímače na robotovi do čipu a podle aktuálních hodnot upravit rychlost a směr chůze.
Jako vstupy byly použity/zneužity PB6 a PB7 z bloku pro řízení serv. Bylo totiž zároveň třeba napájet přijímač a sledovat signál. Čip pak řídil tři serva zapojená na PB1, PD7 a PB2.
Pro ladění programu se hodně vyplatilo užití RS-232. Pro samotnou „autonomní” funkci však už konektor s čipem MAX232, diodami a kondenzátory byl zbytečnou extra váhou. Výhodnější by tedy bylo nějaké kompaktnější řešení, kde by část s RS-232 byla zcela oddělitelná.
Další problém bylo oddělené napájení serv — řešeno pomocí dvou sad baterií.

Ferda

Ferda je autonomní robot na soutěž Eurobot 2005. Pro pohyb používá dvě serva: jedno pro zatáčení a jedno pro pohon. Dva digitální vstupy byly použity pro startovní kabel a nárazník. Dva analogové vstupy sloužily pro detekci příkopu a barev podlahy a další dva na enkodéry, či přesněji na detekci pohybu robota.
Asi největší nedostatek byly chybějící indikátory v zcela autonomním režimu (pokud byl robot řízen z notebooku, byly všechny vstupy a výstupy logované, takže ladění nebylo až tak problémové).
Další detail bylo napájení z jednoho zdroje (4x 1.5V baterie). Ideální by byl jeden konektor (jedna verze desky má přímo propojené 5V pro serva se zbytkem desky).

Fatima

I robot Fatima byl stavěn na soutěž Eurobot 2005, ale na rozdíl od Ferdy prošel mnoha dramatickými přestavbami. Nakonec Fatima skončila jako pásák hnaný dvěma servy s jediným vstupem pro detekci vytažení startovního kabelu.
Jelikož se jednalo o celkem nenáročnou aplikaci, tak jsme nenarazili na žádné extra nové potřeby/nedostatky desky. Asi platí to samé, co u Ferdy, tj. dovolit možnost propojit obě napájení a případně nějak lépe indikovat stav, než jedinou blikající LEDkou.

Gerda

Gerda byl manipulátor pro genetické experimenty (PCR — polymerase chain reaction). Pro pohyb byla použita dvě modifikovaná serva a všechny vstupy byly digitální (microswitche na detekci dorazů resp. poloh jednotlivých nádob).
Zde asi největší plus byla spolehlivost komunikace (celé zařízení bylo řízeno z počítače), s tím, že dosud používaný program byl modifikovat tak, aby vypršení watchodog timeru automaticky vypínalo všechna serva.
Snad jediným problémem byl nedostatek digitálních vstupů (jsou 3, ale potřeba byly 4), který bylo možno obejít pomocí analogových vstupů a pull-up odporu (ano, řešení by bylo i přeprogramovat desku, to by však zanášelo zbytečnou nekompatibilitu s ostatními verzemi).

Software

Software, na rozdíl od hardware, lze snadno měnit a upravovat. To je jedna z jeho velkých předností, která má však i stinnou stránku: pokud máte více desek/robotů/aplikací tak je třeba nějak sjednotit alespoň základní rozhraní, jinak je údržba nemožná. Jednou z motivací je stále větší množství uživatelů desky (včetně studentů na cvičení), kterým bychom chtěli usnadnit první krůčky. To je poměrně netriviální, protože každý se chce hned vydat jiným směrem .
Naším cílem je sjednotit komunikační protokol, který by bylo možné snadno rozšiřovat a přitom by každý nemusel znát detaily všech možných přenášených zpráv. Dále je třeba vytvořit základní program pro ATmega8, aby úplný začátečník nemusel řešit problémy s nastavováním timerů pro řízení serv, komunikace a A/D převodníků. Z tohoto důvodu vznikne pravděpodobně více revizi software, který jsme nazvali RoboBIOS (Robotic Basic Input Output System).

Komunikační protokol

Jádro řídícího software je ve všech dříve zmíněných robotech podobné, tj. není stejné. Co je však u všech robotů stejné je komunikační protokol, tj. způsob jak se posílají a kódují jednotlivé zprávy. Základ pochází z robota Daisy a jisté podobnosti by bylo možné vystopovat až k robotovi Guido firmy Haptica.
Komunikace mezi PC a deskou je zcela synchronní: počítač pošle příkazy a deska, až příkazy vykoná, odpoví s informací o aktuálním stavu všech senzorů. Deska je tedy v podřízené (slave) pozici a všechny zprávy vysílá pouze na vyžádání počítače (master).
U Daisy byla situace jednoduchá, protože bylo třeba posílat pouze jeden typ zprávy a pouze jeden typ zprávy přijímat. Tuto zprávu dále používali i všichni zmínění roboti, přestože neměli k dispozici např. enkodéry a PWM pro řízení motorů. Tato varianta je však do budoucna neúnosná a tak zavádíme více druhů (a velikostí) zpráv.
Každá zpráva začína start bajtem (0xAB), následuje délka zprávy a příkazový bajt. Délka zprávy tedy může být maximálně 255 bajtů s tím, že hodnota 0 je rezerovaná a vždy očekáváme alespoň jeden bajt (odpovídající příkazovému bajtu). Za příkazovým bajtem mohou následovat další parametry a data. Posledním posílaným bajtem je kontrolní součet (check sum), což je pro jednoduchost pouze doplněk k součtu všech bajtů za start bajtem. Pokud sečtete všechny bajty správně přenesené zprávy (bez start bajtu), tak dostanete 0.
Zpráva od desky má stejný formát s výjimkou příkazového bajtu, který má navíc nastaven nejvyšší bit. Pokud příkaz z PC byl 0x10 tak odpověď desky na tento příkaz bude 0x90. Motivací je snaží párování příkaz—odpověď v případě posílání více druhů zpráv a řešení složitějších variant, kdy např. na jednu zprávu může být generováno více odpovědí.
Ještě jednu poznámku k analyzování zpráv na jednočipu: pokud už došlo k poslání začátku zprávy a zbytek se ztratil, tak jednočip tuto situaci nepozná dokud nedostane očekávaný počet bajtů (nejsou použity žádné timeouts) a kontrolní součet bude špatně. Při příjmu další zprávy hledá start bajt a ten považuje za začátek. Pokud by se bajt 0xAB vyskytoval i někde uvnitř pokažené zprávy, tak by mohl čip špatně určit začatek a tak dokola. Čip má dva režimy:
  • probíhá příjem zprávy (start bajt detekován, ale nebyly přijaty ještě všechny bajty)
  • čekání na start bajt
Při čekání na start bajt tedy může provádět i jiné akce, než zahazovat všechny bajty různé od 0xAB. Zatím jedinou implementovanou akcí je posílání 'D' při příjmu 'D' (D od slova Daisy). Pokud dojde k porušení komunikace, tak PC může posílat písmeno 'D' dokud mu čip neodpoví. Má pak 100% jistotu, že je čip správně nastaven na příjem start bajtu.
Do budoucna v tomto mezirežimu hodláme implementovat textové příkazy pro snadnou diagnostiku pomocí ručního zadávání příkazů např. z hyperterminálu.

Příklad

Počítač pošle osmibajtovou zprávu desce:
AB 08 10 E1 FF 00 00 00 B4 00 54
a dostane devítibajtovou odpověď:
AB 09 90 E1 00 AF AD AC B4 B3 B0 67
Pro kontrolu 08+10+E1+FF+00+00+00+B4+00+54 = 0x300 … tj. spodní bajt je 0 a stejně tak odpověď 09+90+E1+00+AF+AD+AC+B4+B3+B0+67=0x600. Zprávy tedy byly přeneseny v pořádku. Pozn. že ten kdo zprávy posílá/přijímá potřebuje pouze znát jak je kódován start bajt a jak je zpráva dlouhá (tj. první dva bajty). Co přesně přenáší je mu už jedno.
Pokud Vás zajímá, co zpráva znamená , tak příkaz zněl: ,,Servobote (10), v čase E1 s nastavením watchdogu na 0.5s (FF) pohni pouze se čtvrtým servem do polohy B4.''
Odpověď desky byla: ,,Pane, Váš příkaz (90) jsem úspěšně realizoval v čase E1. Při té příležitosti jsem zjistil, že nejsou stisknuta žádná tlačítka (00) a na šesti analogových vstupech jsou hodnoty AF AD AC B4 B3 B0.''
Více se významu zpráv dozvíte v následující části.

RoboBIOS rev. 1.2

Základem jsou dvě komunikační struktury: HWWrite pro zápis příkazů a HWRead pro čtení aktuálního stavu. Aktuální verze vypadá takto:
struct HWRead
{
  uint8_t R_timer; //! ~500Hz
  uint8_t R_digitalInputs;
  uint8_t R_analog[6];
};
struct HWWrite
{
  uint8_t W_executeAt;
  uint8_t W_watchDog;
  uint8_t W_servo[4];
  uint8_t W_digitalOutputs;
};
Jak již bylo řečeno, tyto struktury byly převzaty z robota Daisy (až na pár drobností — přibylo W_executeAt a jedna struktura se rozpadla na dvě … W_ a R_ prefix ale stále zůstal, byly odstraněny enkodéry a PWM a redukován počet analogových vstupů).

HWRead

Struktura HWRead popisuje aktualní stav čipu. R_timer je absolutní čas, který ale přeteče zhruba 2x za sekundu. Hodnota 500Hz je pouze přibližná, přesně je to 1000000/(8*256)=488.28125Hz (pro 8MHz je použit prescale 64, takže časování je stejné).
Aktuální digitální vstupy jsou kódovány v R_digitalInputs. Odpovídají stavu PIND - piny (PD2, PD3 a PD4). Výsledná hodnota je invertována, posunuta o oříznuta maskou 0x7. Stisku tlačítka tedy odpovídá hodnota 1, 2 nebo 4.
Pole analogových vstupů R_analog[6] pak obsahuje aktuální hodnoty všech A/D převodníků.

HWWrite

Pomocí struktury HWWrite se robot řídí. Příkaz bude proveden až v nějakou konkrétní dobu a to podle nastavení W_executeAt. Provádí se znamínkový rozdíl s aktuální hodnotou timeru, takže pokud zbývá záporný čas (příkaz měl být před chvilkou proveden), tak se provede okamžitě. Chcete-li tedy okamžité provedení, tak nastavte W_executeAt=R_timer, běžně se však používá pravidelné opakování např. W_executeAt=R_timer+20, tj. 25Hz. Ještě poznámka, že pro správné chování by maximální doba čekání měla být W_executeAt=R_timer+127, což si vynucuje minimální rychlost zaslání příkazů na zhruba 5krát za sekundu.
Další řídící bajt je W_watchDog, který má zaručit správné chování robota v případě přerušení komunikace. Pokud je hodnota „hlídacího psa” větší než nula, tak se v každém cyklu (změna timeru o jedničku) sníží. V okamžiku, kdy je tato hodnota nulová se všechny motory (v našem případě serva) vypnou.
Řízení serv se realizuje pomocí pole W_servo[4]. Poloha serva se určuje hodnotami 1-254 (u většiny serv je však tento interval užší, např. 20-230). Hodnoty 0 a 255 jsou rezervované s tím, že 0 odpovídá zastavení vysílání sigálu a v budoucnu výstupu 0V. Pro hodnotu 255 je pak plánovaný výstup 5V.
Zbývající W_digitalOutputs odpovídají pinům PB6, PB7 a PD5.

Revize — seznam změn

Přechod od verze 1.1 k 1.2:
  • odstraněny nepoužité proměnné ze struktury HWRead a HWWrite. Konkrétně se jedná o R_encoder0, R_encoder1, W_pwm0 a W_pwm1. Počet analogových vstupů byl snížen na 6, tj. maximum co je na desce dostupné.
  • odděleny tři digitální výstupy (piny PB6, PB7 a PD5).
  • tři digitální vstupy jsou invertovány, posunuty a oříznuty na tři bity (AND 0x7). Jelikož jsou použity pull-up odpory, tak pro nezapojené vstupy je hodnota 0. Stisk tlačítka (spojení se zemí) pak odpovídá jedničce.
  • rozšíření komunikačního paketu: start bajt 0xAB je následován délkou dat. Data vedle struktur HWRead a HWWrite navíc obsahují příkazový bajt 0x10 (v odpovědi HWRead je to 0x90).
  • inverze bajtu checksum — pokud se nyní sečtou všechny datové bajty, délka zprávy a checksum tak výsledek správně poslané zprávy je roven 0.
  • implementováno čtvrté servo (W_servo[3])
  • hodnoty 0 a 255 jsou pro serva rezervovaná (další verze bude mít pro 0 na výstupu 0V a pro 255 výstup 5V). Hodnotě 0 nyní odpovídá stav no signal.

Rychlost komunikace

Čip je prodávan se zapnutým interním oscilátorem na 1MHz. Pro toto časování je však rychlost komunikace limitována na 9600bps a to je pro náročnější aplikace již nedostačující. Nastavní rychlejšího oscilátoru vyžaduje několik netriviálních kroků, které zde popíšeme:
Nejprve zjištění, jak má čip nastaveny pojistky (fuses). To lze realizovat i pomocí uicp programu, který je použit pro programování čipu:
fuse8MHz:
	uisp -dlpt=0x378 -dprog=fbprg -@-wr_fuse_l=0xe4

fuse1MHz:
	uisp -dlpt=0x378 -dprog=fbprg -@-wr_fuse_l=0xe1

info:
	uisp -dlpt=0x378 -dprog=fbprg -@-rd_fuses
s tím, že např. na většině linuxů odpadá parametr -dlpt a jako programátor budete mít -dprog=stk200.
Výsledek pro make info s přiloženým Makefile soborem může vypadat takto:
uisp -dlpt=0x378 -dprog=fbprg -@-rd_fuses
Atmel AVR ATmega8 is found.

Fuse Low Byte      = 0xe1
Fuse High Byte     = 0xd9
Fuse Extended Byte = 0xff
Calibration Byte   = 0xae  -@-  Read Only
Lock Bits          = 0xff
    BLB12 -> 1
    BLB11 -> 1
    BLB02 -> 1
    BLB01 -> 1
      LB2 -> 1
      LB1 -> 1
Fuse Low Byte (spodní bajt pojistky) odpovídá rychlosti 1MHz — první krok je tedy změnit tuto rychlost na 8MHz (--wr_fuse_l=0xe4).
Další krok je zjištění kalibračních bajtů pro jiné rychlosti (pro 1MHz je přímo nastaven z továrny a v našem příkladě odpovídá 0xae). K tomu je třeba použít např. dalšího programu dodávaného s WinAVR balíkem: avrdude.
Postup od Pavla Jiroutka je následující:
Příkazem avrdude -p m8 -c funcard -t uvedu program do interaktivního textoveho módu pro atmega8 a funcard. V kalibračních bajtech mám: a9 ab a0 a2 (příkaz "dump calibration"). Ta poslední hodnota by měla být pro 8MHz. Přímo v kódu mám napsáno outp(0xA2, OSCCAL); Pozn. špatná kalibrace se projevovala tím, že se občas kazily bitíky při uart komunikaci.
Před použitím avrdude je třeba spustit install_giveio.bat. Většinou se nachází v c:\Program Files\WinAVR\bin\. Možná je v něm potřeba nastavit cesty. Občas (nevím proč) mi avrdude ze začátku stejně nefunguje (nenaváže spojeni s avr). Vyřeší se to po spuštění a vypnutí icprog.

Implementační otázky a plány do budoucna

Jedním z implementačních problémů je nastavování kalibračního bajtu pro vyšší rychlosti vnitřního oscilátoru (konkrétně na 8MHz). Tato hodnota je po každý čip jiná a vedle toho, že je jí třeba zjistit, tak buď musí být nastavena z kódu nebo z EEPROM (ta se ale při každém přeprogramování také mění, takže to vyjde nastejno).
Další otázka do budoucna je I2C (resp. TWI) komunikace. Má smysl jí nějak vyčlenit? Jak přecházet ze stavu desky s šesti analogovými vstupy na komunikující desku? (jedná se o změnu konfigurace, kterou není uplně dobré dělat za běžného provozu). Jak by měly vypadat posílané pakety z PC a pak po I2C sběrnici?

Komentáře a názory
  • schovat některé piny (RXD, TXD, PB0)?
  • rozdělit serva na dva bloky, tj. serva a digitální výstupy?
  • udělat verzi s oddělenou RS-232?
  • jumper na napájení?
  • kompaktnější verze?
  • více LEDek?
  • více digitálních I/O?
  • lepší implementace servo-výstupů, kdy extrémní hodnoty znamenají 255=AlwaysOn a 0=Off?

  • používat L verzi procesoru (se čtyřmi nabíjecími tužkovými bateriemi (4 x 1.2V) není snadné udržet napájení nad 4.5V)
  • stále používat oddělené napájení pro serva a zbytek desky (problémy při programování, kdy serva cukají) s možností napájecí rozdvojky
  • zvážit přidání vypínače
  • vyvrtat díry v rozích desky (ideálně s násobkem 1cm)
Zbyněk:
  • digitální výstupy opravdu řešit přes 0=Off, 1-254 poloha serva a 255=AlwaysOn
  • jumper na externí zdroj
  • máme-li standardní bios, tak odstranit rezervované piny (červená LEDka, RXD a TXD)
Pavel:
  • zachovat RS-232 na desce
  • více LEDek zdražuje, zvětšuje a zesložiťuje desku
Martin:
  • nepřesunout červenou LEDku jinam, aby byl k dispozici ICP1 - Input Caputre Pin, pro přesné měření pulzů?

Source code rev. 1.2

AVR

PC

Testování

Pro přímé testování pod linuxem je možné použít program minicom -o ttyS0 a ověřit, že deska vysílá úvodní zprávu a reaguje na 'D'.