Liste der Anhänge anzeigen (Anzahl: 1)
Hallo mic,
ganz so einfach funktioniert es nicht mit den Maussensor. Dazu muß man sich schon durch das Datenblatt des Maussensors quälen. Das ist ja ein komplettes Protokoll mit Befehlen zum Abfragen und Schreiben von Config Registern zur Initialisierung. Die Befehle sind zudem noch von Sensor zu Sensor verschieden.
Zudem wird der SDA Pin als Eingang zum Lesen und als Ausgang zum Schreiben benutzt. Mit einem kleinen Fehler im Programm killt man sich schnell den Maussensor (ist mir auch einmal passiert), wenn der Maussensor und der Controller beide den SDA Pin als Ausgang betreiben. Für erste Versuche sollte man hier einen Reihenwiderstand in die Leitung hängen.
Für den ADNS2610 findet man hier ein komplettes Datenblatt:
http://www.avagotech.com/docs/AV02-1184EN
Für den ADNS2620:
http://www.avagotech.com/docs/AV02-1115EN
Für den ADNS2051:
http://bdml.stanford.edu/twiki/pub/M...r/ADNS2051.pdf
Man kann mit dem Maussensor über kleine Strecken recht genaue Informationen über die zurückgelegte Wegstrecke erhalten. Auf langen Strecken summieren sich die Fehler allerdings zu recht deutlichen Fehlern.
Als kleines Schmankerl ohne größeren Nutzwert: es lässt sich auch das gerade aufgenommene Bild der Kamera auslesen.
Das sieht dann z.B. so aus:
Liste der Anhänge anzeigen (Anzahl: 1)
Hallo
Ich habe mal grob die Timeings der 26xx mit meinem 2051 verglichen. Bis auf die unterschiedlichen Verzögerungen scheint das gleich. Vor allem das Zusammenspiel von Takt und Daten ist gleich. Hier nun mein erster funktionierender Versuch:
Code:
// RP6 liest optischen Maussensor aus (nur x/y)(Maussensor: ADNS-2051) 22.1.09 mic
#include "RP6RobotBaseLib.h"
#define clk_h DDRC |= 1; PORTC |= 1 // Für Anschluss an SDA/CLK am XBUS
#define clk_l DDRC |= 1; PORTC &= ~1 // clk - Pin 10
// data= Pin 12
#define data_h DDRC |= 2; PORTC |= 2 // Vcc - Pin 3
#define data_l DDRC |= 2; PORTC &= ~2 // GND - Pin 1
#define data_z DDRC &= ~2; PORTC &= ~2
#define data_in (PINC & 2)
/*
#define clk_h DDRA |= 1; PORTA |= 1 // Für Anschluss an ADC0/1
#define clk_l DDRA |= 1; PORTA &= ~1 // clk - ADC0
// data- ADC1
#define data_h DDRA |= 2; PORTA |= 2
#define data_l DDRA |= 2; PORTA &= ~2
#define data_z DDRA &= ~2; PORTA &= ~2
#define data_in (PINA & 2)
*/
void init( void)
{
data_z;
clk_h;
sleep(5);
clk_l;
mSleep(2000); //timeout adnr2051 erzwingen => reset
}
void write_data(uint16_t data)
{
uint8_t bit=16;
while(bit--)
{
if(data & (1<<bit)) {data_h;} else {data_l;} // Klammern sind hier muss!
sleep(5);
clk_h;
sleep(5);
clk_l;
sleep(5);
}
data_z;
sleep(20);
}
uint8_t read_data(uint8_t adr)
{
uint8_t bit, data;
bit=8;
while(bit--)
{
if(adr & (1<<bit)) {data_h;} else {data_l;}
sleep(5);
clk_h;
sleep(5);
clk_l;
sleep(5);
}
clk_l;
data_z;
sleep(20);
bit=8;
data=0;
while(bit--)
{
clk_h;
if(data_in) {data |= (1<<bit);}
sleep(5);
clk_l;
sleep(5);
}
sleep(20);
return(data);
}
int main(void)
{
uint8_t status;
initRobotBase();
init();
writeString_P("Produkt-ID: ");
writeInteger(read_data(0), 16);
writeString_P("\n\n\r");
while(1)
{
status=read_data(2);
if(status & 128) // Bewegung erkannt?
{
writeString_P("Status: "); // wenn Bit7 gesetzt ist
writeInteger(status, 16);
writeString_P(" x: ");
writeInteger(read_data(3), 10); // können die eingefrorenen Deltawerte
writeString_P(" y: "); // für x und y ausgelesen werden.
writeInteger(read_data(4), 10);
writeString_P("\n\r");
}
sleep(255);
}
while(0) // Testansteuerung
{
clk_h;
data_h;
mSleep(1000);
clk_l;
mSleep(1000);
clk_h;
data_l;
mSleep(1000);
clk_l;
mSleep(1000);
clk_h;
data_z;
mSleep(1000);
clk_l;
mSleep(1000);
}
return(0);
}
wenn man die Maus bewegt werden die Daten zum RP6Loader gesendet :)
Das Programm verwendet zwei Funktionen:
write_data() sendet 16 Bits zur Maus. Bit15-8 sind dabei die Adresse, Bit7-0 die Daten. Bit15 für Schreibzugriff muss man selbst setzen!
read_data(adresse) liest Daten von der angegebenen Adresse. Dazu wird zuerst die Adresse gesendet, kurz gewartet und dann werden die Daten eingelesen.
Das Timeing ist noch nicht optimiert, Wartezeiten von 5 sleep()s dürften aber reichlich zuviel sein.
Der Chip in meiner Maus wurde mit digitalen Ausgängen genutzt, die Takt- und Datenpins waren mit GND verbunden. Ich habe sie einfach abgezwickt und das Kabel direkt auf die Pins gelötet. Vcc und GND sind geblieben:
Bild hier Bild hier
Das USB-Kabel steckt dann direkt im XBUS.
Ich glaube nicht das man die Maus sinnvoll zur Wegmessung/-berechnung nutzen kann, lasse mich aber gerne vom Gegenteil überzeugen.
Viel Spaß beim Nachbau.
[Edit]Noch ein kleines Update:
Bevor man mit dem Maussensor ein Foto machen kann sollte man die LED einschalten:
Bild hier
http://www.youtube.com/watch?v=Lhg-QdRft-A
Das funzt ja schon prima:
Code:
//RP6 schaltet die LED einer optischen Maus (Maussensor: ADNS-2051) 22.1.09 mic
#include "RP6RobotBaseLib.h"
#define clk_h DDRC |= 1; PORTC |= 1 // Für Anschluss an SDA/CLK am XBUS
#define clk_l DDRC |= 1; PORTC &= ~1 // clk - Pin 10
// data= Pin 12
#define data_h DDRC |= 2; PORTC |= 2 // Vcc - Pin 3
#define data_l DDRC |= 2; PORTC &= ~2 // GND - Pin 1
#define data_z DDRC &= ~2; PORTC &= ~2
#define data_in (PINC & 2)
/*
#define clk_h DDRA |= 1; PORTA |= 1 // Für Anschluss an ADC0/1
#define clk_l DDRA |= 1; PORTA &= ~1 // clk - ADC0
// data- ADC1
#define data_h DDRA |= 2; PORTA |= 2
#define data_l DDRA |= 2; PORTA &= ~2
#define data_z DDRA &= ~2; PORTA &= ~2
#define data_in (PINA & 2)
*/
void init( void)
{
data_z;
clk_h;
sleep(5);
clk_l;
mSleep(1500); // timeout adnr2051 erzwingen zur Syncronisation
// kein Takt seit mehr als 0,9sec => reset
}
void write_data(uint16_t data)
{
uint8_t bit=16;
while(bit--)
{
if(data & (1<<bit)) {data_h;} else {data_l;} // Klammern sind hier muss!
sleep(5);
clk_h;
sleep(5);
clk_l;
sleep(5);
}
data_z;
sleep(20);
}
uint8_t read_data(uint8_t adr)
{
uint8_t bit, data;
bit=8;
while(bit--)
{
if(adr & (1<<bit)) {data_h;} else {data_l;}
sleep(5);
clk_h;
sleep(5);
clk_l;
sleep(5);
}
clk_l;
data_z;
sleep(20);
bit=8;
data=0;
while(bit--)
{
clk_h;
if(data_in) {data |= (1<<bit);}
sleep(5);
clk_l;
sleep(5);
}
sleep(20);
return(data);
}
int main(void)
{
uint8_t adresse, daten;
initRobotBase();
init();
writeString_P("Produkt-ID: ");
writeInteger(read_data(0), 16);
writeString_P("\n\n\r");
adresse=0x8a; // Registernr. + Bit7 gesetzt weil Kommando!
daten=0b00000001; // Bit0 gesetzt ist Sleep-Mode aus
//76543210
while(1)
{
write_data(256*adresse+daten); // Lampe an
mSleep(500);
write_data(256*adresse); // Lampe aus
init(); // Timeout erzwingen um PowerDown-Zeit zu umgehen
}
return(0);
}
[NocheinEdit]
Ist doch nicht sooo schwierig:
Code:
[READY]
Produkt-ID: 2
Bilddaten des Maussensors:
0123456789abcdef
0 |#¤¤¤¤¤¤¤x××××××·|
1 |¤¤¤¤¤#¤¤¤x××××··|
2 |¤¤¤¤¤##¤¤xx×××··|
3 |¤¤¤¤¤##¤¤¤x×××··|
4 |x¤¤¤¤###¤¤¤x××··|
5 |x¤¤¤¤###¤¤¤x×××·|
6 |xx¤¤¤##¤#¤¤x××·×|
7 |xxx¤¤¤#¤¤¤¤x××·×|
8 |xxx¤¤#¤¤¤¤¤x××··|
9 |¤x×x¤¤¤¤¤¤¤x×···|
a |¤x×x¤¤¤¤¤xxx×···|
b |xx××x¤¤¤xxxx××··|
c |xx×××x¤xxxx××···|
d |×xx××xxxxx××····|
e |××××××xx××××····|
f |×××·×××××××·····|
[READY]
Produkt-ID: 2
Bilddaten des Maussensors:
0123456789abcdef
0 |#¤¤¤¤¤¤¤x××××××·|
1 |¤¤¤¤¤#¤¤¤x××××··|
2 |¤¤¤¤¤##¤¤x××××··|
3 |¤¤¤¤¤#¤¤¤¤x×××··|
4 |x¤¤¤¤###¤¤¤×××··|
5 |x¤¤¤¤¤##¤¤¤x×××·|
6 |xx¤¤¤##¤#¤¤x××·×|
7 |xxx¤¤¤#¤¤¤¤x××·×|
8 |¤xx¤¤¤¤¤¤¤xx××··|
9 |¤××x¤¤¤¤¤¤xx×···|
a |¤x×x¤¤¤¤¤xxx×···|
b |xx××x¤¤¤xxxx××··|
c |xxx××x¤xxxx××···|
d |××x××xxxxxx×····|
e |××××××xx××××····|
f |×××·×××××××·····|
[READY]
Produkt-ID: 2
Bilddaten des Maussensors:
0123456789abcdef
0 |×······×××······|
1 |×···············|
2 |x×··············|
3 |¤¤x·············|
4 |¤¤¤¤x×··········|
5 |¤¤¤#¤xx××·×·×××·|
6 |¤¤¤¤#¤¤¤xxx×××××|
7 |¤¤¤¤#¤¤¤¤xxx××××|
8 |¤¤¤¤¤¤¤¤xxx×××·×|
9 |¤¤###¤¤¤xxx×××××|
a |¤¤##¤¤¤¤xx×××××·|
b |¤¤¤¤¤¤xxxx××××··|
c |xxx¤¤¤xxxx×××···|
d |xxxx¤xxxxx×××···|
e |xxxxxxxxx×××××··|
f |xxxxxxxx×××××···|
Zweimal der Scan einer Steuermarke auf einer Zigarettenschachtel, Maus wurde nicht bewegt. Das Dritte ist ein Scan aus einer Zeitschrift(Text).
Code:
// RP6 liest ein 16x16 Pixelbild vom Maussensor ein (63 Helligkeitswerte) 22.1.09 mic
// Maussensor: ADNS-2051
#include "RP6RobotBaseLib.h"
#define clk_h DDRC |= 1; PORTC |= 1 // Für Anschluss an SDA/CLK am XBUS
#define clk_l DDRC |= 1; PORTC &= ~1 // clk - Pin 10
// data= Pin 12
#define data_h DDRC |= 2; PORTC |= 2 // Vcc - Pin 3
#define data_l DDRC |= 2; PORTC &= ~2 // GND - Pin 1
#define data_z DDRC &= ~2; PORTC &= ~2
#define data_in (PINC & 2)
/*
#define clk_h DDRA |= 1; PORTA |= 1 // Für Anschluss an ADC0/1
#define clk_l DDRA |= 1; PORTA &= ~1 // clk - ADC0
// data- ADC1
#define data_h DDRA |= 2; PORTA |= 2
#define data_l DDRA |= 2; PORTA &= ~2
#define data_z DDRA &= ~2; PORTA &= ~2
#define data_in (PINA & 2)
*/
void init( void)
{
data_z;
clk_h;
sleep(5);
clk_l;
mSleep(1500); // timeout adnr2051 erzwingen zur Syncronisation
// kein Takt seit mehr als 0,9sec => reset
}
void write_data(uint16_t data)
{
uint8_t bit=16;
while(bit--)
{
if(data & (1<<bit)) {data_h;} else {data_l;} // Klammern sind hier muss!
sleep(2);
clk_h;
sleep(2);
clk_l;
sleep(2);
}
data_z;
sleep(20);
}
uint8_t read_data(uint8_t adr)
{
uint8_t bit, data;
bit=8;
while(bit--)
{
if(adr & (1<<bit)) {data_h;} else {data_l;}
sleep(2);
clk_h;
sleep(2);
clk_l;
sleep(2);
}
clk_l;
data_z;
sleep(20);
bit=8;
data=0;
while(bit--)
{
clk_h;
if(data_in) {data |= (1<<bit);}
sleep(2);
clk_l;
sleep(2);
}
sleep(20);
return(data);
}
int main(void)
{
uint8_t adresse, daten, zeile, spalte;
uint8_t graustufen[6]={32, 184, 216, 120, 165, 35}; // " ·×x¤#"
initRobotBase();
init();
writeString_P("Produkt-ID: ");
writeInteger(read_data(0), 16);
writeString_P("\n\n\r");
adresse=0x8a; // Registernr. + Bit7 gesetzt weil Kommando!
daten=0b00000001; // Bit0 gesetzt ist Sleep-Mode aus
//76543210
write_data(256*adresse+daten); // Lampe an
mSleep(500);
daten=0b00001001; // Bit3 gesetzt startet PixelDump
//76543210
write_data(256*adresse+daten); // Pixeldump anfordern
writeString_P("Bilddaten des Maussensors:\n\r");
writeString_P(" 0123456789abcdef\n\r");
for(zeile=0; zeile<16; zeile++) // 16x16=256 Pixel lesen
{
writeInteger(zeile, 16);
writeString_P(" |");
for(spalte=0; spalte<16; spalte++)
{
read_data(0x0d);
//do daten=read_data(0x0c); while(!(daten & 128);
daten=read_data(0x0c);
writeChar(graustufen[daten/10]); // 63 ist maxwert, 6 graustufen
}
writeString_P("|\n\r");
}
adresse=0x8a; // Lampe aus, PixelDump fertig
write_data(256*adresse);
while(1); // Kunstwerk betrachten
return(0);
}