Aus RN-Wissen.de
Wechseln zu: Navigation, Suche
Rasenmaehroboter fuer schwierige und grosse Gaerten im Test

K (3,3V-I2C-Bus)
K (Autoren)
 
(104 dazwischenliegende Versionen desselben Benutzers werden nicht angezeigt)
Zeile 1: Zeile 1:
 
=RP6v2 Orientierung: Hardware=
 
=RP6v2 Orientierung: Hardware=
  
In diesem Projekt soll eine "Exp" ([[RP6#Experimentierplatine]], CONRAD [http://www.conrad.de/ce/de/product/191537/RP6-EXPERIMENTIERPLATINE 191537]) für den [[RP6v2]] (natürlich auch für den [[RP6]]) "gebaut" werden, mit der sich der RP6v2 besser im Raum orientieren kann.
+
In diesem Projekt soll eine "Exp" ([[RP6#Experimentierplatine|Experimentierplatine]], CONRAD [http://www.conrad.de/ce/de/product/191537/RP6-EXPERIMENTIERPLATINE 191537]) für den [[RP6v2]] (natürlich auch für den [[RP6]]) "gebaut" werden, mit der sich der RP6v2 besser im Raum orientieren kann.
  
 
Die Sensoren des RP6v2 (Odometrie, ACS, Helligkeitssensoren, Bumper) helfen ihm zwar schon dabei, sich im Raum zu orientieren, aber das geht noch besser:
 
Die Sensoren des RP6v2 (Odometrie, ACS, Helligkeitssensoren, Bumper) helfen ihm zwar schon dabei, sich im Raum zu orientieren, aber das geht noch besser:
Zeile 29: Zeile 29:
  
 
  '''Teileliste:'''
 
  '''Teileliste:'''
  C1  Elko 10µF, 16V
+
  C1  Elko 47µF, 16V
 
  C2  Keram. Kondensator 0,1µF
 
  C2  Keram. Kondensator 0,1µF
 
  C3  Keram. Kondensator 0,1µF
 
  C3  Keram. Kondensator 0,1µF
Zeile 46: Zeile 46:
 
   
 
   
 
  3,3V Spannungsregler  ST L78L33A
 
  3,3V Spannungsregler  ST L78L33A
 +
 +
So könnte die Experimentierplatine (noch ohne PROG/UART Stecker) aussehen:
 +
 +
[[bild:RP6_Orientierung_B5.JPG]]
  
 
Viel Erfolg beim Aufbau!
 
Viel Erfolg beim Aufbau!
  
 
  Natürlich muss man nicht alle drei Sensoren aufbauen!
 
  Natürlich muss man nicht alle drei Sensoren aufbauen!
  Man kann einfach den/die Sensor/en weglassen, die man nicht nutzen will!
+
  Man kann einfach den/die Sensor/en weglassen, den/die man nicht nutzen will!
  
 
==Schaltungsbeschreibung==
 
==Schaltungsbeschreibung==
 
Die Schaltung ist primär ausgelegt für den Aufbau auf einer RP6 Experimentierplatine. Über den '''XBUS''' (rechte Steckverbindung) erfolgt der Anschluß der Schaltung an den I2C-Bus eines µCs und die Stromversorgung mit 5V.
 
Die Schaltung ist primär ausgelegt für den Aufbau auf einer RP6 Experimentierplatine. Über den '''XBUS''' (rechte Steckverbindung) erfolgt der Anschluß der Schaltung an den I2C-Bus eines µCs und die Stromversorgung mit 5V.
  
Die vom XBUS nach links führenden Leiterbahnen stellen (von oben nach unten) die wesentlichen Verbindungen dar:
+
Die vom '''XBUS''' nach links führenden Leiterbahnen stellen (von oben nach unten) die wesentlichen Verbindungen dar:
 
* VDD  (+5V)
 
* VDD  (+5V)
 
* GND  (Masse, Minuspol des Akkus)
 
* GND  (Masse, Minuspol des Akkus)
Zeile 62: Zeile 66:
 
* SDA  (5V-I2C-Bus: SDA)
 
* SDA  (5V-I2C-Bus: SDA)
  
Im RP6-System ist die '''XBUS-INT1-Leitung''' mit unterschiedlichen Portpins verbunden,- siehe: [[RP6#Interrupt-Zuordnung_.C3.A4ndern]]. Auf der RP6v2 Base liegt diese Leitung über einen 10kOhm Pulldown-Widerstand (R34) an GND. Wenn ein Pullup-Widerstand an INT1 benötigt wird, kann dieser (R7; 2,2kOhm) mit JP14 eingeschaltet werden.
+
Im RP6-System ist die '''XBUS-INT1-Leitung''' mit unterschiedlichen Portpins verbunden,- siehe: [[RP6#Interrupt-Zuordnung_.C3.A4ndern|Interrupt-Zuordnung ändern]]. Auf der RP6v2 Base liegt diese Leitung über einen 10kOhm Pulldown-Widerstand (R34) an GND. Wenn ein Pullup-Widerstand an INT1 benötigt wird, kann dieser (R7; 2,2kOhm) mit JP14 eingeschaltet werden. Über INT1 kann ein angeschlossener Sensor z.B. mitteilen, ob Daten vom Master (über den I2C-Bus) zu lesen sind.
  
 
Links im Schaltplan ist der '''USRBUS''' zu erkennen. Er dient hier nur zur Verbindung des GPS-Moduls mit dem UART eines µCs.
 
Links im Schaltplan ist der '''USRBUS''' zu erkennen. Er dient hier nur zur Verbindung des GPS-Moduls mit dem UART eines µCs.
Zeile 68: Zeile 72:
 
===Kompassmodul HDMM01===
 
===Kompassmodul HDMM01===
 
Das Kompassmodul kann mit den Jumpern JP1..3 komplett deaktiviert werden. Die Verschaltung weist sonst keinerlei Besonderheiten auf.
 
Das Kompassmodul kann mit den Jumpern JP1..3 komplett deaktiviert werden. Die Verschaltung weist sonst keinerlei Besonderheiten auf.
 +
 +
Eine wichtige Entscheidung ist, WO man den Sensor anbringt. Er sollte möglichst weit weg von Magnetfeldern (z.B. den Motoren des RP6!) montiert sein. Ich habe ihn etwas erhöht auf der Exp ganz vorn rechts angebracht, wobei diese Exp "Orientierung" sowieso als oberste Platine auf den vorderen Stapel gehört.
  
 
===Beschleunigungssensor 3D-BS===
 
===Beschleunigungssensor 3D-BS===
 
Auch dieser Sensor kann komplett deaktiviert werden (JP4..7). Er ist wie das Kompassmodul mit dem I2C-Bus (SCL, SDA) verbunden. Sein INT-Anschluß kann über JP6 mit der XBUS-INT1-Leitung verbunden werden. Zur Nutzung des INT-Anschlusses siehe das Datenblatt zum BMA020!
 
Auch dieser Sensor kann komplett deaktiviert werden (JP4..7). Er ist wie das Kompassmodul mit dem I2C-Bus (SCL, SDA) verbunden. Sein INT-Anschluß kann über JP6 mit der XBUS-INT1-Leitung verbunden werden. Zur Nutzung des INT-Anschlusses siehe das Datenblatt zum BMA020!
 +
 +
Ich habe den 3D-BS etwas erhöht rechts hinten auf der Exp montiert.
  
 
===GPS-Modul NL-552ETTL===
 
===GPS-Modul NL-552ETTL===
Das GPS-Modul kann deaktiviert werden, indem die 5-polige Steckverbindung zwischen Modul und ST1 gelöst wird. Alternativ kann auch JP8 geöffnet werden (Modul ohne Versorgungsspannung!). Das GPS-Modul sendet permanent serielle Daten im NMEA 0183 Standard. Sein TX-Ausgang (3,3V-TTL-Logik) wird daher mit einem RX-Eingang eines µCs verbunden. Die Verbindung kann über den USRBUS (Y6) oder ST2 (Pin 2) erfolgen.
+
Das GPS-Modul kann deaktiviert werden, indem die 5-polige Steckverbindung zwischen Modul und ST1 gelöst wird. Alternativ kann auch JP8 geöffnet werden (Modul ohne Versorgungsspannung!). Das GPS-Modul sendet permanent serielle Daten im NMEA 0183 Format. Sein TX-Ausgang (3,3V-TTL-Logik) wird daher mit einem RX-Eingang eines µCs verbunden. Die Verbindung kann über den USRBUS (Y6) oder ST2 (Pin 2) erfolgen.
 +
 
 +
Der TX-Ausgang des GPS-Moduls liegt zusätzlich (über JP18) an Pin 3 des PROG/UART Steckers auf dieser Exp. Hier kann z.B. über das USB-Interface des RP6v2 oder über den [http://www.rn-wissen.de/index.php/RP6v2_USB-RS232-Adapter hier] beschriebenen RP6v2 USB-RS232-Adapter eine Verbindung zum PC hergestellt werden. Mit dem Navilock '''u-blox-7.0 Center für Windows''' ([http://www.navilock.de/files/17366.download Download]) kann das GPS-Modul dann komfortabel gesteuert und konfiguriert werden. Hierzu ist auch die RX-Verbindung erforderlich (s.u.!).
 +
 
 +
Für die Konfiguration des GPS-Moduls müssen auch serielle Daten an das Modul (RX-Eingang) gesendet werden. Dies kann mit 5V-TTL-Pegel über den USRBUS (Y8) erfolgen (JP9 geschlossen!) oder über ST2 (Pin 3). ''Normalerweise wird man diese Verbindung nicht benötigen, kann also JP9 offen lassen und an Pin 3 von ST2 nichts anschliessen.''
 +
 
 +
Über JP17 kann der RX-Eingang des GPS-Moduls zusätzlich mit dem PROG/UART Stecker auf dieser Exp verbunden werden (5V-TTL-Pegel). Damit ist eine Verbindung zum PC (s.o.!) möglich,- auch mit Konfiguration des Moduls. ''Normalerweise wird man diese Verbindung nicht benötigen, kann also JP17 offen lassen.''
  
Für die Konfiguration des GPS-Moduls müssen auch serielle Daten an das Modul gesendet werden. Dies kann mit 5V-TTL-Pegel über den USRBUS (Y8) erfolgen (JP9 geschlossen!) oder über ST2 (Pin 3). Normalerweise wird man diese Verbindung nicht benötigen.
+
Das GPS-Modul sitzt bei mir vorn direkt an der Einbuchtung der Exp. Ich habe es mit Klett-Klebepads 25x25mm befestigt. An das Anschlußkabel des NL-552ETTL habe ich eine 5-polige Buchsenleiste angelötet, die auf ST1 gesteckt wird.
  
 
===3,3V-I2C-Bus===
 
===3,3V-I2C-Bus===
Zeile 83: Zeile 97:
 
* [http://www.pollin.de/shop/dt/MDg4OTgxOTk-/Bausaetze_Module/Module/Luftdruck_Modul_HP03S.html Luftdruck Modul HP03S]
 
* [http://www.pollin.de/shop/dt/MDg4OTgxOTk-/Bausaetze_Module/Module/Luftdruck_Modul_HP03S.html Luftdruck Modul HP03S]
 
* [http://www.pollin.de/shop/dt/OTc4OTgxOTk-/Bausaetze_Module/Module/Luftfeuchtigkeits_Modul_HH10D.html Luftfeuchtigkeits Modul HH10D]
 
* [http://www.pollin.de/shop/dt/OTc4OTgxOTk-/Bausaetze_Module/Module/Luftfeuchtigkeits_Modul_HH10D.html Luftfeuchtigkeits Modul HH10D]
* [http://www.watterott.com/de/Tri-Axis-Gyro-Breakout-L3G4200D 3-Achsen-GYRO ITG-3200] (Merkwürdig: '''Da passt sogar der Stecker ST3 perfekt!!! Warum wohl?''')
+
* [http://www.watterott.com/de/Gyro-ITG-3200-Breakout 3-Achsen-GYRO ITG-3200] (Merkwürdig: ''Da passt sogar die ST3-Belegung perfekt!!! Warum wohl? Absicht...?'')
 
* ...
 
* ...
  
Zeile 131: Zeile 145:
 
|}
 
|}
  
Ein µC kann auf zwei Arten Daten vom GPS-Modul empfangen:
+
Ein µC/PC kann auf drei Arten die NMEA 0183 Datensätze vom GPS-Modul empfangen:
 
* 1. Über diesen Stecker ST2: In der Regel braucht man nur eine 2-adrige Verbindung von Pins 1 und 2 zum µC. Dabei wird Pin 2 mit dem UART-Eingang RX des µCs verbunden. Den 3,3V-TTL-Ausgangspegel des GPS-Moduls sollte eigentlich jeder AVR-µC verstehen, auch wenn er mit 5V betrieben wird. '''VORSICHT: Diesen Pin 2 nie mit einem AUSGANG eines µCs verbinden!'''
 
* 1. Über diesen Stecker ST2: In der Regel braucht man nur eine 2-adrige Verbindung von Pins 1 und 2 zum µC. Dabei wird Pin 2 mit dem UART-Eingang RX des µCs verbunden. Den 3,3V-TTL-Ausgangspegel des GPS-Moduls sollte eigentlich jeder AVR-µC verstehen, auch wenn er mit 5V betrieben wird. '''VORSICHT: Diesen Pin 2 nie mit einem AUSGANG eines µCs verbinden!'''
* 2. Über den USRBUS: Der Ausgang TX des GPS-Moduls ist mit Pin Y6 (µC RX) des USRBUS verbunden. Auf der auswertenden Platine (Base, M32, M128, M256 WiFi) muss dann Y6 des USRBUS mit UART-Eingang RX des µCs verbunden werden.
+
* 2. Über den USRBUS: Der Ausgang TX des GPS-Moduls ist mit Pin Y6 (µC RX) des USRBUS verbunden. Auf der auswertenden Platine (Base, M32, M128) muss dann Y6 des USRBUS mit UART-Eingang RX des µCs verbunden werden.
 +
* 3. Über den PROG/UART Stecker: Der Ausgang TX des GPS-Moduls ist über JP18 mit Pin 3 des PROG/UART Steckers verbunden. Damit können die Daten des GPS-Moduls über das USB-Interface des RP6v2 z.B. zu einem PC übertragen werden.
  
Soll ein µC auch Daten zum GPS-Modul senden (nur nötig zur Konfiguration des Moduls!), gelingt das auch auf zwei Arten:
+
Soll ein µC/PC auch Daten zum GPS-Modul senden (nur nötig zur Konfiguration des Moduls!), gelingt das auch auf drei Arten:
* 1. Über diesen Stecker ST2: Der UART-Ausgang TX eines µCs wird mit Pin 3 dieses Steckers verbunden.
+
* 1. Über diesen Stecker ST2: Der UART-Ausgang TX eines µCs wird mit Pin 3 dieses Steckers verbunden (dieser liegt über einen Spannungsteiler R1/R2 am Eingang RX des GPS-Moduls).
* 2. Über den USRBUS: Der Eingang RX des GPS-Moduls ist über einen Spannungsteiler R1/R2 mit Pin Y8 (µC TX) des USRBUS verbunden, wenn JP9 geschlossen (ON) ist. Auf der steuernden Platine (Base, M32, M128, M256 WiFi) muss dann Y8 des USRBUS mit UART-Ausgang TX des µCs verbunden werden.
+
* 2. Über den USRBUS: Der Eingang RX des GPS-Moduls ist über einen Spannungsteiler R1/R2 mit Pin Y8 (µC TX) des USRBUS verbunden, wenn JP9 geschlossen (ON) ist. Auf der steuernden Platine (Base, M32, M128) muss dann Y8 des USRBUS mit UART-Ausgang TX des µCs verbunden werden.
 +
* 3. Über den PROG/UART Stecker: Der Eingang RX des GPS-Moduls ist über einen Spannungsteiler R1/R2 mit Pin 2 des PROG/UART Steckers verbunden, wenn JP17 geschlossen (ON) ist. Damit kann z.B. ein PC über das USB-Interface des RP6v2 Konfigurations-Daten zum GPS-Modul übertragen.
  
 
====ST3====
 
====ST3====
Zeile 228: Zeile 244:
 
| JP13 || ON (S) || 3,3V-I2C-Bus Power AN
 
| JP13 || ON (S) || 3,3V-I2C-Bus Power AN
 
|-
 
|-
| JP14 || OFF (S)|| INT 5V Pullup AUS
+
| JP14 || OFF (S) || INT 5V Pullup AUS
 
|-
 
|-
 
| JP14 || ON || INT 5V Pullup AN **
 
| JP14 || ON || INT 5V Pullup AN **
Zeile 236: Zeile 252:
 
| JP15 || ON (S) || SDA 3,3V Pullup AN ***
 
| JP15 || ON (S) || SDA 3,3V Pullup AN ***
 
|-
 
|-
| JP16 || OFF || INT 3,3V Pullup AUS
+
| JP16 || OFF (S) || INT 3,3V Pullup AUS
 
|-
 
|-
| JP16 || ON (S) || INT 3,3V Pullup AN
+
| JP16 || ON || INT 3,3V Pullup AN
 +
|-
 +
| JP17 || OFF (S) || NL-552ETTL RX getrennt von PROG/UART
 +
|-
 +
| JP17 || ON || NL-552ETTL RX verbunden mit PROG/UART
 +
|-
 +
| JP18 || OFF (S) || NL-552ETTL TX getrennt von PROG/UART
 +
|-
 +
| JP18 || ON || NL-552ETTL TX verbunden mit PROG/UART
 +
|-
 +
| JP19 || OFF (S) || GND getrennt von PROG/UART
 +
|-
 +
| JP19 || ON || GND verbunden mit PROG/UART
 
|}
 
|}
  
Zeile 252: Zeile 280:
 
=RP6v2 Orientierung: Software=
 
=RP6v2 Orientierung: Software=
  
... KANN DAUERN ...
+
Die Funktionen in diesem Abschnitt sind noch stark verbesserungs-fähig!
 +
Daher bitte nur als Anregung und als Startpunkt für eigene Entwicklungen verstehen!
 +
 
 +
===Kompassmodul HDMM01===
 +
Hier drei Funktionen (RP6 Library) zum Lesen der Roh-Daten des HDMM01 und zur Berechnung der Himmelsrichtung:
 +
<pre>// The I2C slave address of the HDMM01:
 +
#define HDMM01_ADR 0x60
 +
 
 +
// Internal registers:
 +
#define INTERNAL_REGISTER 0x00
 +
#define MSB_X_AXIS 0x01
 +
#define LSB_X_AXIS 0x02
 +
#define MSB_Y_AXIS 0x03
 +
#define LSB_Y_AXIS 0x04
 +
 
 +
// Commands:
 +
#define CMD_TM 0b00000001
 +
#define CMD_SET 0b00000010
 +
#define CMD_RESET 0b00000100
 +
 
 +
// Axis centre points:
 +
#define X_CENTRE 1945.0 // Default: 2048.0
 +
#define Y_CENTRE 2029.5 // Default: 2048.0
 +
 
 +
/*****************************************************************************/
 +
// Variables:
 +
 
 +
uint16_t x_axis, y_axis;
 +
 
 +
/*****************************************************************************/
 +
// HDMM01 functions:
 +
 
 +
/**
 +
* This function sets and resets the internal coil of the sensor.
 +
*/
 +
void resetCoilHDMM01(void)
 +
{
 +
I2CTWI_transmit2Bytes(HDMM01_ADR, INTERNAL_REGISTER, CMD_SET);
 +
mSleep(1);
 +
I2CTWI_transmit2Bytes(HDMM01_ADR, INTERNAL_REGISTER, CMD_RESET);
 +
mSleep(5);
 +
}
 +
 
 +
/**
 +
* This function reads the X-axis and Y-axis values from the HDMM01 and
 +
* stores them in the global variables x_axis and y_axis.
 +
* It returns the Internal register of the HDMM01.
 +
*/
 +
uint8_t readHDMM01(void)
 +
{
 +
uint8_t readBuf[5];
 +
I2CTWI_transmit2Bytes(HDMM01_ADR, INTERNAL_REGISTER, CMD_TM); // Measure
 +
mSleep(5);
 +
I2CTWI_transmitByte(HDMM01_ADR, INTERNAL_REGISTER);
 +
I2CTWI_readBytes(HDMM01_ADR, readBuf, 5); // Read Int. reg. & X-/Y-axis
 +
x_axis = ((readBuf[MSB_X_AXIS] & 0x0f) << 8) + readBuf[LSB_X_AXIS];
 +
y_axis = ((readBuf[MSB_Y_AXIS] & 0x0f) << 8) + readBuf[LSB_Y_AXIS];
 +
return readBuf[INTERNAL_REGISTER];
 +
}
 +
 
 +
/**
 +
* This function calculates the heading. The heading is a value from
 +
* 0° to 359°. If the robot's front (and the sensor's SDA/SCL pin side)
 +
* points to ...
 +
*  north -> heading is 0°,
 +
*  east  -> heading is 90°,
 +
*  south -> heading is 180°,
 +
*  west  -> heading is 270°.
 +
*
 +
* The heading (HDG) is calculated by:  HDG = ATAN2(Y, X) * 180 / PI
 +
*/
 +
uint16_t headingHDMM01(void)
 +
{
 +
double x, y, heading;
 +
x = x_axis - X_CENTRE;
 +
y = y_axis - Y_CENTRE;
 +
heading = atan2(y, x) * 180 / M_PI - 90;
 +
if(heading < 0) heading += 360.0;
 +
return ((uint16_t) heading);
 +
}
 +
</pre>
 +
Die Werte für X_CENTRE und Y_CENTRE hängen vom Sensor und vom aktuellen Standort ab. Man kann sie für den eigenen Standort ermitteln, indem man den RP6 (bzw. den Sensor) auf einer genau waagerechten Fläche langsam um 360° dreht und dabei die Maximal- und Minimalwerte für die X- und Y-Achse notiert. Dann errechnet man die beiden Mittelwerte. Diese trägt man als Werte für X_CENTRE und Y_CENTRE ein.
 +
Für erste Versuche mit dem Sensor kann man für beide Konstanten den Wert 2048 (Zero Field) einsetzen.
 +
 
 +
===Beschleunigungssensor 3D-BS===
 +
Diese Funktionen (RP6 Library) können nützlich sein zur Ansteuerung des 3D-BS Beschleunigungssensors:
 +
<pre>// The I2C slave address of the 3D-BS:
 +
#define I2C_3D_BS_ADR 0x70
 +
 
 +
// Register start addresses:
 +
#define OP_REG_14H_ADR 0x14
 +
#define LSB_X_ADR 0x02
 +
 
 +
// Data register offsets:
 +
#define LSB_X 0
 +
#define MSB_X 1
 +
#define LSB_Y 2
 +
#define MSB_Y 3
 +
#define LSB_Z 4
 +
#define MSB_Z 5
 +
 
 +
/*****************************************************************************/
 +
// Variables:
 +
 
 +
int16_t x_val, y_val, z_val;
 +
double x_acc, y_acc, z_acc;
 +
uint8_t accrange = 0; // Acceleration range +/-2g (default)
 +
double adc2g = (double) 2 / 512; // Factor for acceleration [g]
 +
double pitch, roll;
 +
 
 +
/*****************************************************************************/
 +
// 3D-BS functions:
 +
 
 +
/**
 +
* This function sets the BMA020 Range.
 +
*  range = 0 -> +/-2g (default)
 +
*  range = 1 -> +/-4g
 +
*  range = 2 -> +/-8g
 +
* It returns true, if the Range could be set successfully,
 +
* else it returns false.
 +
* If the result is true, the function calculates the variable adc2g and
 +
* sets accrange to range.
 +
*
 +
* ==> Normally you should leave the Range at default setting!!!
 +
*/
 +
uint8_t set3D_BSaccrange(uint8_t range)
 +
{
 +
uint8_t opreg14h, temp;
 +
if(range > 2) range = 0;
 +
I2CTWI_transmitByte(I2C_3D_BS_ADR, OP_REG_14H_ADR);
 +
opreg14h = I2CTWI_readByte(I2C_3D_BS_ADR); // Read Op. Register 14h
 +
opreg14h &= 0b11100111; // Clear BMA020 Range bits 3, 4
 +
opreg14h |= (range << 3); // Set new Range
 +
I2CTWI_transmit2Bytes(I2C_3D_BS_ADR, OP_REG_14H_ADR, opreg14h);
 +
I2CTWI_transmitByte(I2C_3D_BS_ADR, OP_REG_14H_ADR);
 +
temp = I2CTWI_readByte(I2C_3D_BS_ADR); // Read Op. Reg. 14h again
 +
if(opreg14h == temp) {
 +
adc2g = 1 << range;
 +
adc2g *= 2;
 +
adc2g /= 512;
 +
accrange = range;
 +
return true;
 +
}
 +
else
 +
return false;
 +
}
 +
 
 +
/**
 +
* This function reads the X-/Y-/Z-acceleration values from the 3D-BS and
 +
* stores them in the global int variables x_val, y_val and z_val.
 +
*
 +
* The Z-axis is inverted, because positive Z-axis values are agreed as
 +
* downward acceleration of a vehicle.
 +
*/
 +
void read3D_BS(void)
 +
{
 +
uint8_t readBuf[6];
 +
I2CTWI_transmitByte(I2C_3D_BS_ADR, LSB_X_ADR); // Adress 1st data register
 +
I2CTWI_readBytes(I2C_3D_BS_ADR, readBuf, 6); // Read X-/Y-/Z-acceleration
 +
x_val = (readBuf[MSB_X] << 8) + (readBuf[LSB_X] & 0xc0);
 +
x_val /= 64;
 +
y_val = (readBuf[MSB_Y] << 8) + (readBuf[LSB_Y] & 0xc0);
 +
y_val /= 64;
 +
z_val = (readBuf[MSB_Z] << 8) + (readBuf[LSB_Z] & 0xc0);
 +
z_val /= -64; // Invert Z-axis!
 +
}
 +
 
 +
/**
 +
* This function calculates the acceleration [g] values and stores them
 +
* in the global double variables x_acc, y_acc and z_acc.
 +
*/
 +
void acceleration3D_BS(void)
 +
{
 +
x_acc = x_val * adc2g;
 +
y_acc = y_val * adc2g;
 +
z_acc = z_val * adc2g;
 +
}
 +
 
 +
/**
 +
* This function calculates the tilt angles (pitch, roll) and stores them
 +
* in the global double variables pitch and roll.
 +
*/
 +
void tiltAngles3D_BS(void)
 +
{
 +
double x, y, z;
 +
x = (double) x_val;
 +
y = (double) y_val;
 +
z = (double) z_val;
 +
pitch = atan(x / sqrt(y * y + z * z)) * -180 / M_PI;
 +
roll = atan(y / sqrt(z * z + z * z)) * 180 / M_PI;
 +
}
 +
</pre>
 +
 
 +
===GPS-Modul NL-552ETTL===
 +
Hier ein kurzes Beispiel für die RP6v2 M256 WiFi zur fortlaufenden Ausgabe aller Daten des GPS-Moduls auf dem WIFI-Terminal. Der NL-552ETTL wird dazu mit seinem TX-Ausgang (ST2 Pin 2 bzw. Modul Pin 4) mit RXD1 der M256 WiFi (Stecker UART_SPI1/T5 Pin 8) verbunden:
 +
<pre>/*
 +
* ****************************************************************************
 +
* RP6 ROBOT SYSTEM - RP6 CONTROL M256 Examples
 +
* ****************************************************************************
 +
* Example: NL-552ETTL
 +
* Author(s): Dirk
 +
* ****************************************************************************
 +
* Description:
 +
* Now we will use UART1 to read data from the NL-552ETTL GPS module
 +
* (ELV No. 94241) with the u-blox5 UBX-G5000-BT GPS chipset
 +
* and display the data permanently on the WIFI terminal.
 +
*
 +
* The NL-552ETTL TX pin (4) has to be connected to RP6 M256 pin RXD1
 +
* (UART_SPI1/T5: 8). The internal pullup resistor of RXD1 should be
 +
* deactivated!
 +
*
 +
* ****************************************************************************
 +
* NMEA 0183 short description:
 +
* 1. GPRMC:
 +
* $GPRMC,213938.000,A,5108.3356,N,00951.0774,E,0.00,79.64,061012,,,A*53
 +
* Index: 1          2 3        4 5          6 7    8    9        12CS
 +
*  1    = UTC of position [hhmmss.sss]
 +
*  2    = Data status (A=ok, V=void)
 +
*  3    = Latitude of fix [ddmm.mmmm]
 +
*  4    = N or S
 +
*  5    = Longitude of fix [dddmm.mmmm]
 +
*  6    = E or W
 +
*  7    = Speed over ground in knots
 +
*  8    = Track made good, degrees true
 +
*  9    = UT date [ddmmyy]
 +
*  10  = Magnetic variation degrees (Easterly var. subtracts from true course)
 +
*  11  = E or W
 +
*  12  = Mode indicator (NMEA V2.3):
 +
*          A=Autonomous mode
 +
*          D=Differential mode
 +
*          E=Estimated (dead-reckoning) mode
 +
*          M=Manual input mode
 +
*          S=Simulated mode
 +
*          N=Data not valid
 +
*  CS  = Checksum
 +
*
 +
* 2. GPVTG:
 +
* $GPVTG,79.64,T,,M,0.00,N,0.0,K,A*31
 +
* Index: 1    2  4 5    6 7  8 9 CS
 +
*  1    = Track made good
 +
*  2    = Fixed text 'T' indicates that track made good is relative to true north
 +
*  3    = Track degrees
 +
*  4    = M=Magnetic
 +
*  5    = Speed over ground in knots
 +
*  6    = Fixed text 'N' indicates that speed over ground is in knots
 +
*  7    = Speed over ground in kilometers/hour
 +
*  8    = Fixed text 'K' indicates that speed over ground is in kilometers/hour
 +
*  9    = Mode indicator (A,D,E,M,S,N)
 +
*  CS  = Checksum
 +
*
 +
* 3. GPGGA:
 +
* $GPGGA,213938.000,5108.3356,N,00951.0774,E,1,04,5.3,158.5,M,46.2,M,,0000*52
 +
* Index: 1          2        3 4          5 6 7  8  9      11  12 14  CS
 +
*  1    = UTC of position
 +
*  2    = Latitude of fix
 +
*  3    = N or S
 +
*  4    = Longitude of fix
 +
*  5    = E or W
 +
*  6    = GPS quality indicator:
 +
*          0=invalid
 +
*          1=GPS fix (SPS)
 +
*          2=DGPS fix
 +
*          3=PPS fix
 +
*          4=Real Time Kinematic
 +
*          5=Float RTK
 +
*          6=estimated (dead reckoning) (NMEA V2.3)
 +
*          7=Manual input mode
 +
*          8=Simulation mode
 +
*  7    = Number of satellites in use [not those in view]
 +
*  8    = Horizontal dilution of position (HDOP)
 +
*  9    = Antenna altitude above/below mean sea level (geoid)
 +
*  10  = Meters  (Antenna height unit)
 +
*  11  = Geoidal separation (Diff. between WGS-84 earth ellipsoid and
 +
*          mean sea level.  -=geoid is below WGS-84 ellipsoid)
 +
*  12  = Meters  (Units of geoidal separation)
 +
*  13  = Age in seconds since last update from diff. reference station
 +
*  14  = Differential reference station ID#
 +
*  CS  = Checksum
 +
*
 +
* 4. GPGSA:
 +
* $GPGSA,A,3,02,04,10,07,,,,,,,,,7.4,5.3,5.1*33
 +
* Index: 1 2 3  4  5  6          15  16  17  CS
 +
*  1    = Selection mode:
 +
*          M=Manual, forced to operate in 2D or 3D
 +
*          A=Automatic 2D/3D
 +
*  2    = Mode:
 +
*          1=no fix
 +
*          2=2D
 +
*          3=3D
 +
*  3-14 = IDs of SVs used in position fix (null for unused fields)
 +
*  15  = PDOP
 +
*  16  = HDOP
 +
*  17  = VDOP
 +
*  CS  = Checksum
 +
*
 +
* 5. GPGSV:
 +
* $GPGSV,3,1,12,02,36,301,37,04,53,235,21,05,03,294,,07,35,170,29*79
 +
* $GPGSV,3,2,12,08,04,187,28,10,56,290,36,13,88,106,20,16,12,076,*7D
 +
* $GPGSV,3,3,12,20,23,118,11,23,50,067,,29,03,351,12,30,16,048,22*70
 +
* Index: 1 2 3  4  5  6  7  8  9  10  12 13 14  15 16 17 18  19 CS
 +
*  1    = Total number of messages of this type in this cycle
 +
*  2    = Message number
 +
*  3    = Total number of SVs in view
 +
*  4    = SV PRN number
 +
*  5    = Elevation in degrees, 90 maximum
 +
*  6    = Azimuth, degrees from true north, 000 to 359
 +
*  7    = SNR, 00-99 dB (null when not tracking)
 +
*  8-11 = Information about second SV, same as field 4-7
 +
*  12-15= Information about third SV, same as field 4-7
 +
*  16-19= Information about fourth SV, same as field 4-7
 +
*  CS  = Checksum
 +
*
 +
* 6. GPGLL:
 +
* $GPGLL,5108.3356,N,00951.0774,E,213938.000,A,A*5C
 +
* Index: 1        2 3          4 5          6 7 CS
 +
*  1    = Latitude of fix
 +
*  2    = N or S
 +
*  3    = Longitude of fix
 +
*  4    = E or W
 +
*  5    = UTC of position
 +
*  6    = Data status (A=ok, V=void)
 +
*  7    = Mode indicator (A,D,E,M,S,N)
 +
*  CS  = Checksum
 +
*
 +
* COMMENTS:
 +
* a) Each sentence (line) begins with '$'.
 +
* b) Each sentence (line) ends with '*', followed by the checksum (two
 +
*    chars building an 8-bit HEX number) and terminated by <CR><LF>.
 +
* c) The checksum (CS) is calculated by XOR of all chars between '$' and '*'.
 +
* d) The max. sentence (line) length is 82 chars (including <CR><LF>).
 +
* e) Further infos:
 +
*    -> http://www.nmea.org/
 +
*    -> http://www.kowoma.de/gps/zusatzerklaerungen/NMEA.htm
 +
*    -> http://de.wikipedia.org/wiki/NMEA_0183
 +
*    -> http://aprs.gids.nl/nmea/
 +
*
 +
* ############################################################################
 +
* The Robot does NOT move in this example! You can simply put it on a table
 +
* next to your PC and you should connect it to the PC via the USB Interface!
 +
* You should also connect to it via WIFI.
 +
* ############################################################################
 +
* ****************************************************************************
 +
*/
 +
 
 +
/*****************************************************************************/
 +
// Includes:
 +
 
 +
#include "RP6M256Lib.h"
 +
#include "RP6M256uart1.h"
 +
 
 +
/*****************************************************************************/
 +
// Variables:
 +
 
 +
uint8_t ch;
 +
 
 +
 
 +
/*****************************************************************************/
 +
// Main function - The program starts here:
 +
 
 +
int main(void)
 +
{
 +
initRP6M256();
 +
PORTD &= ~RXD1; // No pullup at RXD1!
 +
initLCD();
 +
 
 +
writeString_P_WIFI("\n\nRP6 CONTROL M256 NL-552ETTL Example Program!\n");
 +
 
 +
cli();
 +
UBRR1H = UBRR_BAUD_LOW >> 8; // Setup UART1: 38.4 kBaud
 +
UBRR1L = (uint8_t) UBRR_BAUD_LOW;
 +
UCSR1A = 0x00;
 +
UCSR1C = (0<<UMSEL10) | (0<<UMSEL11) | (1<<UCSZ11) | (1<<UCSZ10);
 +
UCSR1B = (1 << TXEN1) | (1 << RXEN1) | (1 << RXCIE1);
 +
clearReceptionBuffer1();
 +
sei();
 +
 
 +
setLEDs(0b1111);
 +
 
 +
showScreenLCD("################", "################");
 +
mSleep(500);
 +
showScreenLCD("  NL-552ETTL", "Example Program");
 +
mSleep(1000);
 +
 
 +
setLEDs(0b0000);
 +
 
 +
while (true) {
 +
ch = readChar1();
 +
if(ch) writeChar_WIFI(ch);
 +
}
 +
return 0;
 +
}
 +
</pre>
 +
Übrigens: Die RP6M256uart1 Library findet ihr [http://www.rn-wissen.de/index.php/RP6v2_USB-RS232-Adapter#RP6M256uart1_Library hier]!
 +
 
 +
===3,3V-I2C-Bus===
 +
Naja, was soll hier an Software-Beispielen stehen? Das hängt natürlich ab von der angeschlossenen Hardware.
  
  
Zeile 259: Zeile 682:
 
* [[RP6 - Programmierung]]
 
* [[RP6 - Programmierung]]
 
* [[RP6v2]]
 
* [[RP6v2]]
 +
* [[RP6 Sensor Board und Xtra Module]]
 
* [[RP6 Kamera - Mitmach-Projekt]]
 
* [[RP6 Kamera - Mitmach-Projekt]]
 +
* [[RP6 - Morse-Code]]
 
* [[RP6v2 I2C-Portexpander]]
 
* [[RP6v2 I2C-Portexpander]]
 
* [[RP6v2 USB-RS232-Adapter]]
 
* [[RP6v2 USB-RS232-Adapter]]
 +
* [[RP6 Multi IO Projekt]]
 +
* [[RP6 Multi IO Projekt - Software]]
 +
* [[RP6 ArduIO]]
 +
* [[RP6 ArduIO - Software]]
 
* [[CCRP5]]
 
* [[CCRP5]]
 
* [[Yeti]]
 
* [[Yeti]]
 
* [[Asuro]]
 
* [[Asuro]]
  
 +
<br/>
  
 
=Quellen=
 
=Quellen=
Zeile 271: Zeile 701:
 
* [http://www.pollin.de/shop/dt/NTM4OTgxOTk-/Bausaetze_Module/Module/Kompassmodul_HDMM01.html Kompassmodul HDMM01]
 
* [http://www.pollin.de/shop/dt/NTM4OTgxOTk-/Bausaetze_Module/Module/Kompassmodul_HDMM01.html Kompassmodul HDMM01]
 
** [http://www.jm.pl/karty/MMC212XM.pdf MEMSIC MMC2120MG Datasheet]
 
** [http://www.jm.pl/karty/MMC212XM.pdf MEMSIC MMC2120MG Datasheet]
* [http://www.elv.de/3-achsen-beschleunigungssensor-3d-bs-komplettbausatz.html 3-Achsen-Beschleunigungssensor-Modul]
+
* [http://www.elv.de/3-achsen-beschleunigungssensor-3d-bs-komplettbausatz.html 3-Achsen-Beschleunigungssensor-Modul 3D-BS]
 
** [http://www.elv-downloads.de/Assets/Produkte/9/915/91521/Downloads/91521_bma020_data.pdf Bosch Sensortec BMA020 Datasheet]
 
** [http://www.elv-downloads.de/Assets/Produkte/9/915/91521/Downloads/91521_bma020_data.pdf Bosch Sensortec BMA020 Datasheet]
 
* [http://www.elv.de/navilock-nl-552ettl-engine-modul.html Navilock NL-552ETTL GPS-Modul]
 
* [http://www.elv.de/navilock-nl-552ettl-engine-modul.html Navilock NL-552ETTL GPS-Modul]
** [http://www.texim-europe.com/promotion/560/ubx-g5010%20datasheet_te.pdf UBX-G5000-BT Datasheet]
+
** [http://www.texim-europe.com/promotion/560/ubx-g5010%20datasheet_te.pdf u-blox5 UBX-G5000-BT Datasheet]
 
* [http://www.st.com/internet/com/TECHNICAL_RESOURCES/TECHNICAL_LITERATURE/DATASHEET/CD00000446.pdf ST L78L33A Datasheet]
 
* [http://www.st.com/internet/com/TECHNICAL_RESOURCES/TECHNICAL_LITERATURE/DATASHEET/CD00000446.pdf ST L78L33A Datasheet]
 
* [http://www.produktinfo.conrad.com/datenblaetter/150000-174999/159204-da-01-en-BSN10_BSN10A.pdf BSN10A Datasheet]
 
* [http://www.produktinfo.conrad.com/datenblaetter/150000-174999/159204-da-01-en-BSN10_BSN10A.pdf BSN10A Datasheet]
 +
 +
 +
* GPS - NMEA Informationen:
 +
** [http://www.nmea.org/ NMEA.org]
 +
** [http://www.kowoma.de/gps/zusatzerklaerungen/NMEA.htm kowoma.de - NMEA]
 +
** [http://de.wikipedia.org/wiki/NMEA_0183 Wikipedia - NMEA 0183]
 +
** [http://aprs.gids.nl/nmea/ GPS - NMEA sentence information]
 +
 +
 +
* Neigungskorrektur (tilt compensation) für 2-Achsen Kompassmodule:
 +
** [http://etrij.etri.re.kr/Cyber/servlet/BrowseAbstract?vol=27&num=3&pg=280 ETRI Journal, vol.27, no.3, June 2005, pp.280-288]
 +
** [http://www.google.com/patents/US6836971 United States Patent No.: 6836971 B1]
  
 
[[Kategorie:Elektronik]]
 
[[Kategorie:Elektronik]]
Zeile 283: Zeile 725:
  
 
=Autoren=
 
=Autoren=
--[[Benutzer:Dirk|Dirk]] 17:22, 2. Okt 2012 (CET)
+
--[http://www.roboternetz.de/community/members/1972-Dirk Dirk] 15:28, 11. Jan 2015 (CET)

Aktuelle Version vom 11. Januar 2015, 15:28 Uhr

RP6v2 Orientierung: Hardware

In diesem Projekt soll eine "Exp" (Experimentierplatine, CONRAD 191537) für den RP6v2 (natürlich auch für den RP6) "gebaut" werden, mit der sich der RP6v2 besser im Raum orientieren kann.

Die Sensoren des RP6v2 (Odometrie, ACS, Helligkeitssensoren, Bumper) helfen ihm zwar schon dabei, sich im Raum zu orientieren, aber das geht noch besser:

  • Wenn er einen Kompass bekommen würde, könnte er eine bestimmte Richtung einhalten oder genauere Kurven fahren. Ein einfach zu verwendendes Kompassmodul auf Basis des MMC2120MG von MEMSIC ist das HDMM01 (Pollin Best.-Nr. 810164). Es kann über den I2C-Bus ausgelesen und an 5V betrieben werden. Zudem ist es recht preisgünstig.
  • Wenn er auch noch einen Beschleunigungssensor bekommen würde, könnte er Bewegungen und Beschleunigungen messen. ELV bietet ein 3-Achsen-Beschleunigungssensor-Modul (ELV Best.-Nr. 91521) auf Basis des BMA020 von Bosch Sensortec an. Auch dieses Modul kann an 5V betrieben werden und verfügt über I2C-Pegelwandler, um es an einen I2C-Bus mit 5V-Pegeln anschliessen zu können.
  • Wenn er sogar noch ein GPS-Modul bekäme, könnte er seine eigene Position bestimmen. Geeignet für unsere Zwecke ist das GPS-Modul NL-552ETTL von Navilock auf Basis des u-blox5 GPS-Chipsets UBX-G5000-BT (auch z.B. bei ELV erhältlich: Artikel-Nr. 68-094241. Bitte unbedingt auch das Anschlusskabel: Artikel-Nr. 68-081846 mit bestellen!). Das Modul kann ebenfalls mit 5V betrieben werden,- leider arbeitet seine serielle Schnittstelle mit 3,3V-Pegeln. Dies ist aber kein wesentliches Problem, weil nur TX des Moduls mit einem UART-Eingangspin (RX) des Microcontrollers (µC) verbunden werden muss, und der versteht die 3,3V-TTL-Logik in der Regel ohne Probleme. Ob ein GPS-Modul für einen Roboter, der eigentlich nur in Innenräumen fahren kann, sinnvoll ist, muss jeder selbst eintscheiden. Das verwendete GPS-Modul soll allerdings mit seiner sog. SuperSense Technik auch in schwierigen Empfangssituationen noch Ergebnisse bringen.
  • Da wir schon dabei sind, können wir auch noch eine 3,3V-Pegel-Anpassung des I2C-Busses des RP6v2 auf der Exp vorsehen: Man kann dann auch I2C-Slave-Bausteine, die nur an einem 3,3V-I2C-Bus arbeiten, an den RP6v2 anschließen.

Was braucht man allgemein für den Aufbau einer Schaltung auf der Exp:

  • Seitenschneider, Schere, Zange
  • Lötkolben 25..30 Watt, Lötzinn
  • Plastik 70 Schutzlack (CONRAD 813621)
  • Isolierter Schaltdraht YV 0,20 mm² (CONRAD 606065)
  • Versilberter CU-Draht 0,6 mm (CONRAD 605581)

Mit dem versilberten CU-Draht stellt man auf der Unterseite (= Lötseite) der Exp Verbindungen zwischen den Bauteilen her; mit dem isolierten Schaltdraht werden Drahtbrücken auf der Oberseite (= Bestückungsseite) der Exp eingesetzt.

Aufbau

Hier der Schaltplan:

RP6v2 Orientierung SP.JPG

Teileliste:
C1  Elko 47µF, 16V
C2  Keram. Kondensator 0,1µF
C3  Keram. Kondensator 0,1µF
C4  Keram. Kondensator 0,1µF

R1  Kohleschicht-Widerstand 4,7 kOhm, 1/4 Watt
R2  Kohleschicht-Widerstand 10 kOhm, 1/4 Watt
R3  Kohleschicht-Widerstand 4,7 kOhm, 1/4 Watt
R4  Kohleschicht-Widerstand 10 kOhm, 1/4 Watt
R5  Kohleschicht-Widerstand 4,7 kOhm, 1/4 Watt
R6  Kohleschicht-Widerstand 4,7 kOhm, 1/4 Watt
R7  Kohleschicht-Widerstand 2,2 kOhm, 1/4 Watt

Q1  MOSFET BSN10A
Q2  MOSFET BSN10A

3,3V Spannungsregler  ST L78L33A

So könnte die Experimentierplatine (noch ohne PROG/UART Stecker) aussehen:

RP6 Orientierung B5.JPG

Viel Erfolg beim Aufbau!

Natürlich muss man nicht alle drei Sensoren aufbauen!
Man kann einfach den/die Sensor/en weglassen, den/die man nicht nutzen will!

Schaltungsbeschreibung

Die Schaltung ist primär ausgelegt für den Aufbau auf einer RP6 Experimentierplatine. Über den XBUS (rechte Steckverbindung) erfolgt der Anschluß der Schaltung an den I2C-Bus eines µCs und die Stromversorgung mit 5V.

Die vom XBUS nach links führenden Leiterbahnen stellen (von oben nach unten) die wesentlichen Verbindungen dar:

  • VDD (+5V)
  • GND (Masse, Minuspol des Akkus)
  • INT1 (Interrupt-Leitung)
  • SCL (5V-I2C-Bus: SCL)
  • SDA (5V-I2C-Bus: SDA)

Im RP6-System ist die XBUS-INT1-Leitung mit unterschiedlichen Portpins verbunden,- siehe: Interrupt-Zuordnung ändern. Auf der RP6v2 Base liegt diese Leitung über einen 10kOhm Pulldown-Widerstand (R34) an GND. Wenn ein Pullup-Widerstand an INT1 benötigt wird, kann dieser (R7; 2,2kOhm) mit JP14 eingeschaltet werden. Über INT1 kann ein angeschlossener Sensor z.B. mitteilen, ob Daten vom Master (über den I2C-Bus) zu lesen sind.

Links im Schaltplan ist der USRBUS zu erkennen. Er dient hier nur zur Verbindung des GPS-Moduls mit dem UART eines µCs.

Kompassmodul HDMM01

Das Kompassmodul kann mit den Jumpern JP1..3 komplett deaktiviert werden. Die Verschaltung weist sonst keinerlei Besonderheiten auf.

Eine wichtige Entscheidung ist, WO man den Sensor anbringt. Er sollte möglichst weit weg von Magnetfeldern (z.B. den Motoren des RP6!) montiert sein. Ich habe ihn etwas erhöht auf der Exp ganz vorn rechts angebracht, wobei diese Exp "Orientierung" sowieso als oberste Platine auf den vorderen Stapel gehört.

Beschleunigungssensor 3D-BS

Auch dieser Sensor kann komplett deaktiviert werden (JP4..7). Er ist wie das Kompassmodul mit dem I2C-Bus (SCL, SDA) verbunden. Sein INT-Anschluß kann über JP6 mit der XBUS-INT1-Leitung verbunden werden. Zur Nutzung des INT-Anschlusses siehe das Datenblatt zum BMA020!

Ich habe den 3D-BS etwas erhöht rechts hinten auf der Exp montiert.

GPS-Modul NL-552ETTL

Das GPS-Modul kann deaktiviert werden, indem die 5-polige Steckverbindung zwischen Modul und ST1 gelöst wird. Alternativ kann auch JP8 geöffnet werden (Modul ohne Versorgungsspannung!). Das GPS-Modul sendet permanent serielle Daten im NMEA 0183 Format. Sein TX-Ausgang (3,3V-TTL-Logik) wird daher mit einem RX-Eingang eines µCs verbunden. Die Verbindung kann über den USRBUS (Y6) oder ST2 (Pin 2) erfolgen.

Der TX-Ausgang des GPS-Moduls liegt zusätzlich (über JP18) an Pin 3 des PROG/UART Steckers auf dieser Exp. Hier kann z.B. über das USB-Interface des RP6v2 oder über den hier beschriebenen RP6v2 USB-RS232-Adapter eine Verbindung zum PC hergestellt werden. Mit dem Navilock u-blox-7.0 Center für Windows (Download) kann das GPS-Modul dann komfortabel gesteuert und konfiguriert werden. Hierzu ist auch die RX-Verbindung erforderlich (s.u.!).

Für die Konfiguration des GPS-Moduls müssen auch serielle Daten an das Modul (RX-Eingang) gesendet werden. Dies kann mit 5V-TTL-Pegel über den USRBUS (Y8) erfolgen (JP9 geschlossen!) oder über ST2 (Pin 3). Normalerweise wird man diese Verbindung nicht benötigen, kann also JP9 offen lassen und an Pin 3 von ST2 nichts anschliessen.

Über JP17 kann der RX-Eingang des GPS-Moduls zusätzlich mit dem PROG/UART Stecker auf dieser Exp verbunden werden (5V-TTL-Pegel). Damit ist eine Verbindung zum PC (s.o.!) möglich,- auch mit Konfiguration des Moduls. Normalerweise wird man diese Verbindung nicht benötigen, kann also JP17 offen lassen.

Das GPS-Modul sitzt bei mir vorn direkt an der Einbuchtung der Exp. Ich habe es mit Klett-Klebepads 25x25mm befestigt. An das Anschlußkabel des NL-552ETTL habe ich eine 5-polige Buchsenleiste angelötet, die auf ST1 gesteckt wird.

3,3V-I2C-Bus

Der 3,3V-I2C-Bus kann mit den Jumpern JP10..13 komplett deaktiviert werden. Er dient zum Anschluß von I2C-Slave-Bausteinen, die einen 3,3V-Pegel benötigen. Über ST3 (Pins 1, 2) können solche Slaves auch mit 3,3V (max. 100mA) versorgt werden. Wenn der Slave nicht über eigene Pullup-Widerstände am I2C-Bus verfügt, kann für SDA mit JP15 ein Pullup aktiviert werden. Mit JP16 ist das auch möglich für die INT-Leitung an ST3 (Pin 4).

Beispiele von Sensoren, die an ST3 anschließbar sind:

Allgemeine Daten und Tabellen

Stecker

Stecker Pins Bedeutung
ST1 5 Anschluß GPS-Modul
ST2 3 µC-Anschluß für GPS-Modul
ST3 7 3,3V-I2C-Bus Anschluß

ST1

Pin Funktion E/A Bedeutung
1 VCC NL-552ETTL +5V *
2 GND NL-552ETTL GND
3 Abschirmung NL-552ETTL Abschirmung
4 TX A NL-552ETTL TX (3,3V)
5 RX E NL-552ETTL RX (3,3V)

Zu *) Falls JP8 = ON!

An diesen Stecker ST1 wird das GPS-Modul NL-552ETTL mit seinem 5-poligen Verbindungskabel angeschlossen. Die schwarze Ader des Kabels gehört an Pin 1 von ST1! Soll das GPS-Modul nicht benutzt werden, sollte das Modul nicht mit ST1 verbunden sein (Steckverbindung!).

ST2

Pin Funktion E/A Bedeutung
1 GND NL-552ETTL GND
2 TX A NL-552ETTL TX (3,3V)
3 RX E NL-552ETTL RX (5V)

Ein µC/PC kann auf drei Arten die NMEA 0183 Datensätze vom GPS-Modul empfangen:

  • 1. Über diesen Stecker ST2: In der Regel braucht man nur eine 2-adrige Verbindung von Pins 1 und 2 zum µC. Dabei wird Pin 2 mit dem UART-Eingang RX des µCs verbunden. Den 3,3V-TTL-Ausgangspegel des GPS-Moduls sollte eigentlich jeder AVR-µC verstehen, auch wenn er mit 5V betrieben wird. VORSICHT: Diesen Pin 2 nie mit einem AUSGANG eines µCs verbinden!
  • 2. Über den USRBUS: Der Ausgang TX des GPS-Moduls ist mit Pin Y6 (µC RX) des USRBUS verbunden. Auf der auswertenden Platine (Base, M32, M128) muss dann Y6 des USRBUS mit UART-Eingang RX des µCs verbunden werden.
  • 3. Über den PROG/UART Stecker: Der Ausgang TX des GPS-Moduls ist über JP18 mit Pin 3 des PROG/UART Steckers verbunden. Damit können die Daten des GPS-Moduls über das USB-Interface des RP6v2 z.B. zu einem PC übertragen werden.

Soll ein µC/PC auch Daten zum GPS-Modul senden (nur nötig zur Konfiguration des Moduls!), gelingt das auch auf drei Arten:

  • 1. Über diesen Stecker ST2: Der UART-Ausgang TX eines µCs wird mit Pin 3 dieses Steckers verbunden (dieser liegt über einen Spannungsteiler R1/R2 am Eingang RX des GPS-Moduls).
  • 2. Über den USRBUS: Der Eingang RX des GPS-Moduls ist über einen Spannungsteiler R1/R2 mit Pin Y8 (µC TX) des USRBUS verbunden, wenn JP9 geschlossen (ON) ist. Auf der steuernden Platine (Base, M32, M128) muss dann Y8 des USRBUS mit UART-Ausgang TX des µCs verbunden werden.
  • 3. Über den PROG/UART Stecker: Der Eingang RX des GPS-Moduls ist über einen Spannungsteiler R1/R2 mit Pin 2 des PROG/UART Steckers verbunden, wenn JP17 geschlossen (ON) ist. Damit kann z.B. ein PC über das USB-Interface des RP6v2 Konfigurations-Daten zum GPS-Modul übertragen.

ST3

Pin Funktion E/A Bedeutung
1 VCC A VCC 3,3V max. 100mA *
2 VCC A VCC 3,3V max. 100mA *
3 GND 3,3V-I2C-Bus GND
4 INT E 3,3V-I2C-Bus INT Eingang
5 GND 3,3V-I2C-Bus GND
6 SDA E/A 3,3V-I2C-Bus SDA
7 SCL A 3,3V-I2C-Bus SCL Ausgang

Zu *) Falls JP13 = ON!

An diesen Stecker ST3 können 3,3V-I2C-Slave-Devices angeschlossen werden. Wenn diese über eine eigene 3,3V-Spannungsversorgung verfügen, braucht man zum Anschluß nur die Pins 5..7 von ST3 (GND, SDA, SCL). ST3 kann aber auch externe I2C-Slaves über Pins 1 und 2 mit 3,3V versorgen (JP13 geschlossen!). Bitte beide Pins zusammen mit nicht mehr als 100mA belasten!

An Pin 4 von ST3 befindet sich noch der Eingang INT. Über ihn kann ein Slave mitteilen, dass z.B. Daten bereit liegen.

Jumper

Zeichenerklärung:

  • Zweipolige Jumper:
    • Stellung ON = Jumper aufgesteckt (Kontakt geschlossen)
    • Stellung OFF = Jumper abgezogen (Kontakt offen)
Jumper Stellung Bedeutung
JP1 OFF HDMM01 SDA getrennt
JP1 ON (S) HDMM01 SDA verbunden
JP2 OFF HDMM01 SCL getrennt
JP2 ON (S) HDMM01 SCL verbunden
JP3 OFF HDMM01 Power AUS
JP3 ON (S) HDMM01 Power AN
JP4 OFF 3D-BS SDA getrennt
JP4 ON (S) 3D-BS SDA verbunden
JP5 OFF 3D-BS SCL getrennt
JP5 ON (S) 3D-BS SCL verbunden
JP6 OFF (S) 3D-BS INT getrennt
JP6 ON 3D-BS INT verbunden *
JP7 OFF 3D-BS Power AUS
JP7 ON (S) 3D-BS Power AN
JP8 OFF NL-552ETTL Power AUS
JP8 ON (S) NL-552ETTL Power AN
JP9 OFF (S) NL-552ETTL RX getrennt von USRBUS
JP9 ON NL-552ETTL RX verbunden mit USRBUS
JP10 OFF 3,3V-I2C-Bus SDA getrennt
JP10 ON (S) 3,3V-I2C-Bus SDA verbunden
JP11 OFF 3,3V-I2C-Bus SCL getrennt
JP11 ON (S) 3,3V-I2C-Bus SCL verbunden
JP12 OFF (S) 3,3V-I2C-Bus INT getrennt
JP12 ON 3,3V-I2C-Bus INT verbunden *
JP13 OFF 3,3V-I2C-Bus Power AUS
JP13 ON (S) 3,3V-I2C-Bus Power AN
JP14 OFF (S) INT 5V Pullup AUS
JP14 ON INT 5V Pullup AN **
JP15 OFF SDA 3,3V Pullup AUS
JP15 ON (S) SDA 3,3V Pullup AN ***
JP16 OFF (S) INT 3,3V Pullup AUS
JP16 ON INT 3,3V Pullup AN
JP17 OFF (S) NL-552ETTL RX getrennt von PROG/UART
JP17 ON NL-552ETTL RX verbunden mit PROG/UART
JP18 OFF (S) NL-552ETTL TX getrennt von PROG/UART
JP18 ON NL-552ETTL TX verbunden mit PROG/UART
JP19 OFF (S) GND getrennt von PROG/UART
JP19 ON GND verbunden mit PROG/UART

Zu (S) Standard-Stellung der Jumper!

Zu *) Am XBUS steht in dieser Schaltung nur EINE Interrupt-Leitung (INT1) zur Verfügung. Es kann also nur die Interrupt-Auswertung von EINEM Sensor auf dieser Platine erfolgen. JP6 und JP12 sollten also nicht gleichzeitig ON sein!

Zu **) Da INT1 auf der RP6v2 Base mit einem 10kOhm Pulldown-Widerstand (R34) verbunden ist, muss man auf dieser Platine ggf. den Pullup-Widerstand 2,2kOhm (R7) einschalten (JP14 = ON!).

Zu ***) Wenn der an ST3 angeschlossene I2C-Slave keinen Pullup-Widerstand an SDA hat, muss R5 eingeschaltet werden (JP15 = ON!).


RP6v2 Orientierung: Software

Die Funktionen in diesem Abschnitt sind noch stark verbesserungs-fähig!
Daher bitte nur als Anregung und als Startpunkt für eigene Entwicklungen verstehen!

Kompassmodul HDMM01

Hier drei Funktionen (RP6 Library) zum Lesen der Roh-Daten des HDMM01 und zur Berechnung der Himmelsrichtung:

// The I2C slave address of the HDMM01:
#define HDMM01_ADR		 	0x60

// Internal registers:
#define INTERNAL_REGISTER	0x00
#define MSB_X_AXIS			0x01
#define LSB_X_AXIS			0x02
#define MSB_Y_AXIS			0x03
#define LSB_Y_AXIS			0x04

// Commands:
#define CMD_TM				0b00000001
#define CMD_SET				0b00000010
#define CMD_RESET			0b00000100

// Axis centre points:
#define X_CENTRE			1945.0	// Default: 2048.0
#define Y_CENTRE			2029.5	// Default: 2048.0

/*****************************************************************************/
// Variables:

uint16_t x_axis, y_axis;

/*****************************************************************************/
// HDMM01 functions:

/**
 * This function sets and resets the internal coil of the sensor.
 */
void resetCoilHDMM01(void)
{
	I2CTWI_transmit2Bytes(HDMM01_ADR, INTERNAL_REGISTER, CMD_SET);
	mSleep(1);
	I2CTWI_transmit2Bytes(HDMM01_ADR, INTERNAL_REGISTER, CMD_RESET);
	mSleep(5);
}

/**
 * This function reads the X-axis and Y-axis values from the HDMM01 and
 * stores them in the global variables x_axis and y_axis.
 * It returns the Internal register of the HDMM01.
 */
uint8_t readHDMM01(void)
{
	uint8_t readBuf[5];
	I2CTWI_transmit2Bytes(HDMM01_ADR, INTERNAL_REGISTER, CMD_TM); // Measure
	mSleep(5);
	I2CTWI_transmitByte(HDMM01_ADR, INTERNAL_REGISTER);
	I2CTWI_readBytes(HDMM01_ADR, readBuf, 5); // Read Int. reg. & X-/Y-axis
	x_axis = ((readBuf[MSB_X_AXIS] & 0x0f) << 8) + readBuf[LSB_X_AXIS];
	y_axis = ((readBuf[MSB_Y_AXIS] & 0x0f) << 8) + readBuf[LSB_Y_AXIS];
	return readBuf[INTERNAL_REGISTER];
}

/**
 * This function calculates the heading. The heading is a value from
 * 0° to 359°. If the robot's front (and the sensor's SDA/SCL pin side)
 * points to ...
 *   north -> heading is 0°,
 *   east  -> heading is 90°,
 *   south -> heading is 180°,
 *   west  -> heading is 270°.
 *
 * The heading (HDG) is calculated by:  HDG = ATAN2(Y, X) * 180 / PI
 */
uint16_t headingHDMM01(void)
{
	double x, y, heading;
	x = x_axis - X_CENTRE;
	y = y_axis - Y_CENTRE;
	heading = atan2(y, x) * 180 / M_PI - 90;
	if(heading < 0) heading += 360.0;
	return ((uint16_t) heading);
}

Die Werte für X_CENTRE und Y_CENTRE hängen vom Sensor und vom aktuellen Standort ab. Man kann sie für den eigenen Standort ermitteln, indem man den RP6 (bzw. den Sensor) auf einer genau waagerechten Fläche langsam um 360° dreht und dabei die Maximal- und Minimalwerte für die X- und Y-Achse notiert. Dann errechnet man die beiden Mittelwerte. Diese trägt man als Werte für X_CENTRE und Y_CENTRE ein.

Für erste Versuche mit dem Sensor kann man für beide Konstanten den Wert 2048 (Zero Field) einsetzen.

Beschleunigungssensor 3D-BS

Diese Funktionen (RP6 Library) können nützlich sein zur Ansteuerung des 3D-BS Beschleunigungssensors:

// The I2C slave address of the 3D-BS:
#define I2C_3D_BS_ADR		0x70

// Register start addresses:
#define OP_REG_14H_ADR		0x14
#define LSB_X_ADR			0x02

// Data register offsets:
#define LSB_X				0
#define MSB_X				1
#define LSB_Y				2
#define MSB_Y				3
#define LSB_Z				4
#define MSB_Z				5

/*****************************************************************************/
// Variables:

int16_t x_val, y_val, z_val;
double x_acc, y_acc, z_acc;
uint8_t accrange = 0;					// Acceleration range +/-2g (default)
double adc2g = (double) 2 / 512;			// Factor for acceleration [g]
double pitch, roll;

/*****************************************************************************/
// 3D-BS functions:

/**
 * This function sets the BMA020 Range.
 *   range = 0 -> +/-2g (default)
 *   range = 1 -> +/-4g
 *   range = 2 -> +/-8g
 * It returns true, if the Range could be set successfully,
 * else it returns false.
 * If the result is true, the function calculates the variable adc2g and
 * sets accrange to range.
 *
 * ==> Normally you should leave the Range at default setting!!!
 */
uint8_t set3D_BSaccrange(uint8_t range)
{
	uint8_t opreg14h, temp;
	if(range > 2) range = 0;
	I2CTWI_transmitByte(I2C_3D_BS_ADR, OP_REG_14H_ADR);
	opreg14h = I2CTWI_readByte(I2C_3D_BS_ADR); // Read Op. Register 14h
	opreg14h &= 0b11100111;				// Clear BMA020 Range bits 3, 4
	opreg14h |= (range << 3);			// Set new Range
	I2CTWI_transmit2Bytes(I2C_3D_BS_ADR, OP_REG_14H_ADR, opreg14h);
	I2CTWI_transmitByte(I2C_3D_BS_ADR, OP_REG_14H_ADR);
	temp = I2CTWI_readByte(I2C_3D_BS_ADR); // Read Op. Reg. 14h again
	if(opreg14h == temp) {
		adc2g = 1 << range;
		adc2g *= 2;
		adc2g /= 512;
		accrange = range;
		return true;
	}
	else
		return false;
}

/**
 * This function reads the X-/Y-/Z-acceleration values from the 3D-BS and
 * stores them in the global int variables x_val, y_val and z_val.
 *
 * The Z-axis is inverted, because positive Z-axis values are agreed as
 * downward acceleration of a vehicle.
 */
void read3D_BS(void)
{
	uint8_t readBuf[6];
	I2CTWI_transmitByte(I2C_3D_BS_ADR, LSB_X_ADR); // Adress 1st data register
	I2CTWI_readBytes(I2C_3D_BS_ADR, readBuf, 6); // Read X-/Y-/Z-acceleration
	x_val = (readBuf[MSB_X] << 8) + (readBuf[LSB_X] & 0xc0);
	x_val /= 64;
	y_val = (readBuf[MSB_Y] << 8) + (readBuf[LSB_Y] & 0xc0);
	y_val /= 64;
	z_val = (readBuf[MSB_Z] << 8) + (readBuf[LSB_Z] & 0xc0);
	z_val /= -64;						// Invert Z-axis!
}

/**
 * This function calculates the acceleration [g] values and stores them
 * in the global double variables x_acc, y_acc and z_acc.
 */
void acceleration3D_BS(void)
{
	x_acc = x_val * adc2g;
	y_acc = y_val * adc2g;
	z_acc = z_val * adc2g;
}

/**
 * This function calculates the tilt angles (pitch, roll) and stores them
 * in the global double variables pitch and roll.
 */
void tiltAngles3D_BS(void)
{
	double x, y, z;
	x = (double) x_val;
	y = (double) y_val;
	z = (double) z_val;
	pitch = atan(x / sqrt(y * y + z * z)) * -180 / M_PI; 
	roll = atan(y / sqrt(z * z + z * z)) * 180 / M_PI;
}

GPS-Modul NL-552ETTL

Hier ein kurzes Beispiel für die RP6v2 M256 WiFi zur fortlaufenden Ausgabe aller Daten des GPS-Moduls auf dem WIFI-Terminal. Der NL-552ETTL wird dazu mit seinem TX-Ausgang (ST2 Pin 2 bzw. Modul Pin 4) mit RXD1 der M256 WiFi (Stecker UART_SPI1/T5 Pin 8) verbunden:

/* 
 * ****************************************************************************
 * RP6 ROBOT SYSTEM - RP6 CONTROL M256 Examples
 * ****************************************************************************
 * Example: NL-552ETTL
 * Author(s): Dirk
 * ****************************************************************************
 * Description:
 * Now we will use UART1 to read data from the NL-552ETTL GPS module
 * (ELV No. 94241) with the u-blox5 UBX-G5000-BT GPS chipset
 * and display the data permanently on the WIFI terminal.
 *
 * The NL-552ETTL TX pin (4) has to be connected to RP6 M256 pin RXD1
 * (UART_SPI1/T5: 8). The internal pullup resistor of RXD1 should be
 * deactivated!
 *
 * ****************************************************************************
 * NMEA 0183 short description:
 * 1. GPRMC:
 * $GPRMC,213938.000,A,5108.3356,N,00951.0774,E,0.00,79.64,061012,,,A*53
 * Index: 1          2 3         4 5          6 7    8     9        12CS
 *   1    = UTC of position [hhmmss.sss]
 *   2    = Data status (A=ok, V=void)
 *   3    = Latitude of fix [ddmm.mmmm]
 *   4    = N or S
 *   5    = Longitude of fix [dddmm.mmmm]
 *   6    = E or W
 *   7    = Speed over ground in knots
 *   8    = Track made good, degrees true
 *   9    = UT date [ddmmyy]
 *   10   = Magnetic variation degrees (Easterly var. subtracts from true course)
 *   11   = E or W
 *   12   = Mode indicator (NMEA V2.3):
 *          A=Autonomous mode
 *          D=Differential mode
 *          E=Estimated (dead-reckoning) mode
 *          M=Manual input mode
 *          S=Simulated mode
 *          N=Data not valid
 *   CS   = Checksum
 *
 * 2. GPVTG:
 * $GPVTG,79.64,T,,M,0.00,N,0.0,K,A*31
 * Index: 1     2  4 5    6 7   8 9 CS
 *   1    = Track made good
 *   2    = Fixed text 'T' indicates that track made good is relative to true north
 *   3    = Track degrees
 *   4    = M=Magnetic
 *   5    = Speed over ground in knots
 *   6    = Fixed text 'N' indicates that speed over ground is in knots
 *   7    = Speed over ground in kilometers/hour
 *   8    = Fixed text 'K' indicates that speed over ground is in kilometers/hour
 *   9    = Mode indicator (A,D,E,M,S,N)
 *   CS   = Checksum
 *
 * 3. GPGGA:
 * $GPGGA,213938.000,5108.3356,N,00951.0774,E,1,04,5.3,158.5,M,46.2,M,,0000*52
 * Index: 1          2         3 4          5 6 7  8   9       11   12 14   CS
 *   1    = UTC of position
 *   2    = Latitude of fix
 *   3    = N or S
 *   4    = Longitude of fix
 *   5    = E or W
 *   6    = GPS quality indicator:
 *          0=invalid
 *          1=GPS fix (SPS)
 *          2=DGPS fix
 *          3=PPS fix
 *          4=Real Time Kinematic
 *          5=Float RTK
 *          6=estimated (dead reckoning) (NMEA V2.3)
 *          7=Manual input mode
 *          8=Simulation mode
 *   7    = Number of satellites in use [not those in view]
 *   8    = Horizontal dilution of position (HDOP)
 *   9    = Antenna altitude above/below mean sea level (geoid)
 *   10   = Meters  (Antenna height unit)
 *   11   = Geoidal separation (Diff. between WGS-84 earth ellipsoid and
 *          mean sea level.  -=geoid is below WGS-84 ellipsoid)
 *   12   = Meters  (Units of geoidal separation)
 *   13   = Age in seconds since last update from diff. reference station
 *   14   = Differential reference station ID#
 *   CS   = Checksum
 *
 * 4. GPGSA:
 * $GPGSA,A,3,02,04,10,07,,,,,,,,,7.4,5.3,5.1*33
 * Index: 1 2 3  4  5  6          15  16  17  CS
 *   1    = Selection mode:
 *          M=Manual, forced to operate in 2D or 3D
 *          A=Automatic 2D/3D
 *   2    = Mode:
 *          1=no fix
 *          2=2D
 *          3=3D
 *   3-14 = IDs of SVs used in position fix (null for unused fields)
 *   15   = PDOP
 *   16   = HDOP
 *   17   = VDOP
 *   CS   = Checksum
 *
 * 5. GPGSV:
 * $GPGSV,3,1,12,02,36,301,37,04,53,235,21,05,03,294,,07,35,170,29*79
 * $GPGSV,3,2,12,08,04,187,28,10,56,290,36,13,88,106,20,16,12,076,*7D
 * $GPGSV,3,3,12,20,23,118,11,23,50,067,,29,03,351,12,30,16,048,22*70
 * Index: 1 2 3  4  5  6   7  8  9  10   12 13 14  15 16 17 18  19 CS
 *   1    = Total number of messages of this type in this cycle 
 *   2    = Message number 
 *   3    = Total number of SVs in view 
 *   4    = SV PRN number
 *   5    = Elevation in degrees, 90 maximum 
 *   6    = Azimuth, degrees from true north, 000 to 359 
 *   7    = SNR, 00-99 dB (null when not tracking) 
 *   8-11 = Information about second SV, same as field 4-7 
 *   12-15= Information about third SV, same as field 4-7 
 *   16-19= Information about fourth SV, same as field 4-7
 *   CS   = Checksum
 *
 * 6. GPGLL:
 * $GPGLL,5108.3356,N,00951.0774,E,213938.000,A,A*5C
 * Index: 1         2 3          4 5          6 7 CS
 *   1    = Latitude of fix
 *   2    = N or S
 *   3    = Longitude of fix
 *   4    = E or W
 *   5    = UTC of position
 *   6    = Data status (A=ok, V=void)
 *   7    = Mode indicator (A,D,E,M,S,N)
 *   CS   = Checksum
 *
 * COMMENTS:
 * a) Each sentence (line) begins with '$'.
 * b) Each sentence (line) ends with '*', followed by the checksum (two
 *    chars building an 8-bit HEX number) and terminated by <CR><LF>.
 * c) The checksum (CS) is calculated by XOR of all chars between '$' and '*'.
 * d) The max. sentence (line) length is 82 chars (including <CR><LF>).
 * e) Further infos:
 *    -> http://www.nmea.org/
 *    -> http://www.kowoma.de/gps/zusatzerklaerungen/NMEA.htm
 *    -> http://de.wikipedia.org/wiki/NMEA_0183
 *    -> http://aprs.gids.nl/nmea/
 *
 * ############################################################################
 * The Robot does NOT move in this example! You can simply put it on a table
 * next to your PC and you should connect it to the PC via the USB Interface!
 * You should also connect to it via WIFI.
 * ############################################################################
 * ****************************************************************************
 */

/*****************************************************************************/
// Includes:

#include "RP6M256Lib.h"
#include "RP6M256uart1.h"

/*****************************************************************************/
// Variables:

uint8_t ch;


/*****************************************************************************/
// Main function - The program starts here:

int main(void)
{
	initRP6M256();
	PORTD &= ~RXD1;						// No pullup at RXD1!
	initLCD(); 

	writeString_P_WIFI("\n\nRP6 CONTROL M256 NL-552ETTL Example Program!\n"); 

	cli();
	UBRR1H = UBRR_BAUD_LOW >> 8;	// Setup UART1: 38.4 kBaud
	UBRR1L = (uint8_t) UBRR_BAUD_LOW;
	UCSR1A = 0x00;
	UCSR1C = (0<<UMSEL10) | (0<<UMSEL11) | (1<<UCSZ11) | (1<<UCSZ10);
	UCSR1B = (1 << TXEN1) | (1 << RXEN1) | (1 << RXCIE1);
	clearReceptionBuffer1();
	sei();

	setLEDs(0b1111);

	showScreenLCD("################", "################");
	mSleep(500);
	showScreenLCD("   NL-552ETTL", "Example Program");
	mSleep(1000);

	setLEDs(0b0000);

	while (true) {
		ch = readChar1();
		if(ch) writeChar_WIFI(ch);
	}
	return 0;
}

Übrigens: Die RP6M256uart1 Library findet ihr hier!

3,3V-I2C-Bus

Naja, was soll hier an Software-Beispielen stehen? Das hängt natürlich ab von der angeschlossenen Hardware.


Siehe auch


Quellen




Autoren

--Dirk 15:28, 11. Jan 2015 (CET)


LiFePO4 Speicher Test