Aus RN-Wissen.de
Version vom 22. April 2012, 16:42 Uhr von Dirk (Diskussion | Beiträge) (Morse-Funkstrecke)

Wechseln zu: Navigation, Suche
Rasenmaehroboter fuer schwierige und grosse Gaerten im Test

Allgemein

In diesem Artikel geht es um die Programmierung des RP6 und seiner Erweiterungsplatinen RP6 CONTROL M32 und RP6 CCPRO M128 am konkreten Beispiel eines Morse-Decoders (Empfänger), eines Morse-Encoders (Sender) und einer Morse-Station (Transceiver).

Zu den Grundlagen des RP6 gibt es eine eigene Seite: RP6. Ebenso zur Programmierung des RP6 im Allgemeinen: RP6 - Programmierung


Geschichte

Nachdem Samuel Morse 1833 den ersten brauchbaren elektromagnetischen Schreibtelegrafen gebaut hatte, fand der erste Testbetrieb 1837 statt. Der verwendete Code umfasste damals nur die zehn Ziffern; die übertragenen Zahlen mussten mit Hilfe einer Tabelle in Buchstaben und Wörter übersetzt werden. Alfred Lewis Vail, ein Mitarbeiter Morses, entwickelte ab 1838 den ersten Code, der auch Buchstaben umfasste. Er bestand aus Zeichen von drei verschiedenen Längen und unterschiedlich langen Pausen. Dieser Code wurde ab 1844 betrieblich eingesetzt (als Morse Landline Code oder American Morse Code bei amerikanischen Eisenbahnen und den Telegrafenunternehmen bis in die 1960er Jahre). Die unterschiedlich langen Pausen stellten eine Unzulänglichkeit des Codes dar, so dass Friedrich Clemens Gerke ihn 1848 zur Inbetriebnahme der elektromagnetischen Telegrafenverbindung zwischen Hamburg und Cuxhaven umschrieb. Dieser Code wurde nach einigen weiteren kleinen Änderungen 1865 auf dem Internationalen Telegraphenkongress in Paris standardisiert und später mit der Einführung der drahtlosen Telegrafie als Internationaler Morsecode von der Internationalen Fernmeldeunion (ITU) genormt. Im Mai 2004 wurde der Morse Code ein zweites Mal anläßlich des 160-jährigen Bestehens der ITU ergänzt, in dem das @ (. - - . - .) offiziell hinzugefügt wurde. Die erste Änderung war ca. 1960 mit der Unterscheidung zwischen Klammer-auf (- . - - .) und Klammer-zu (- . - - . -) erfolgt. Der Morse Code hat in den letzten 10 Jahren immer mehr an Bedeutung verloren. Im Amateurfunk und zu Unterrichtszwecken wird er jedoch noch eingesetzt, auch weiterhin als (Buchstaben-) Kennung von Funknavigationsanlagen (Leuchttürme, Funkfeuer, Radarantwortbaken ...) und bei der Steuerung von Computern durch Menschen mit körperlichen Behinderungen. (Quelle: Wikipedia)


Grundlagen

Der Morse-Code verwendet drei Symbole, die Punkt (.), Strich (-) und Pause ( ) genannt werden.

  • Ein Strich (Dah) ist dreimal so lang wie ein Punkt (Dit).
  • Die Pause zwischen 2 Symbolen ist ein Dit lang.
  • Zwischen den Buchstaben eines Worts gilt eine Pause von einer Dah-Länge (= 3 Dits).
  • Die Pause zwischen Wörtern beträgt 7 Dits.

Die Übertragungsrate beim Morsen wird in Buchstaben pro Minute (BpM, englisch: CpM) oder in Wörtern pro Minute (WpM) gemessen, wobei ein Wort 5 Buchstaben entspricht. Als Referenz für die Geschwindigkeitsmessung wurde das Wort „PARIS“ ausgewählt. Gibt ein Funker dieses Wort mit seinen 5 Buchstaben 12-mal pro Minute, so beträgt die Morse-Geschwindigkeit 60 BpM. Das Wort „PARIS“ besteht aus 50 Dits (d.h. Punkt- plus Strich- plus Pausenlängen). Ein WpM sind 50 Dits pro Minute.

WpM BpM Punktlänge [ms] Strichlänge [ms]
1 5 1200 3600
3 15 400 1200
5 25 240 720
10 50 120 360
20 100 60 180
50 250 24 72
100 500 12 36
150 750 8 24

Anfänger leisten bis zu 5 WpM, die Prüfgeschwindigkeit für Funkamateure liegt bei 12 WpM. Sehr gute Funker schaffen 50 WpM. Weltrekorde: Mehr als 75 WpM!

Morse-Alphabet

Das hier aufgeführte Morse-Alphabet umfasst die englischen Buchstaben und die nicht-englischen Ergänzungen zum Morse-Alphabet. Darüber hinaus gibt es Morse-Codes in vielen Sprachen, die nicht lateinische Buchstaben verwenden: Griechisch, Kyrillisch, Hebräisch, Arabisch, Persisch, Japanisch, Chinesisch, Koreanisch …

RP6 Morse-Tabelle


Morse-Baum

Mit den "Morse-Bäumen" kann man den Morse-Code lernen oder sehr langsam gesendete Morse-Zeichen direkt decodieren. Im Morse-Baum steht ein Kreis für einen Punkt und ein Rechteck mit abgerundeten Kanten für einen Strich. Beginnt das empfangene Morse-Zeichen mit einem Punkt, folgt man im Morse-Baum "E" den Pfeilen abhängig von den folgenden Punkten/Strichen bis zum Ende des Zeichens. Dort kann man dann das decodierte Zeichen ablesen. Genauso verfährt man im Morse-Baum "T" mit Morse-Zeichen, die mit einem Strich beginnen.

RP6 Morse-Baum E RP6 Morse-Baum T


Projekt

Das Empfangen und Senden von Morse-Zeichen ist für einen uC (Microcontroller) eigentlich kein Problem. Die drei Plattformen (Base, M32, M128) des RP6-Systems haben den Vorteil, dass sie aus drei unabhängigen uCs bestehen, die man zum Testen einer Datenübertragung gut benutzen kann. Dazu brauchen die M32 und M128 nur auf dem RP6 montiert zu sein. Als Verbindungen, über die die Morse-Zeichen gesendet werden, kann man die I/O-Pins benutzen, durch die die drei uCs über den XBUS schon verbunden sind (SCL, SDA, EINT1).

Natürlich kann man auch eine "echte" drahtgebundene Morse-Verbindung erreichen, indem man eine der Zusatzplatinen stand-alone betreibt und durch ein Kabel z.B. mit der Base verbindet.

Am reizvollsten ist aber eine Funkverbindung: Der HF-Sender wird z.B. mit einem Ton moduliert, wenn der Ausgangs-Pin des steuernden uCs Highpegel führt. Im HF-Empfänger wird der Eingangs-Pin des decodierenden uCs immer dann auf High-Pegel gezogen, wenn der aufmodulierte Ton empfangen wird. Das ist mit dem RP6-System und etwas Zusatz-Hardware auch für einen Nicht-Funkamateur relativ einfach machbar. Auch die im Radio z.T. noch empfangbaren Morse-Zeichen lassen sich mit einem uC decodieren. Dazu braucht man ebenfalls eine kleine Zusatz-Schaltung.

Planung

Auf allen drei Plattformen (Base, M32, M128) soll ein Morse-Sender und -Empfänger realisiert werden. Beide Funktionen sollen auch parallel nutzbar sein. Auf der RP6 Base und M32 sollen die Funktionen im üblichen Task-System der RP6 Library umgesetzt werden, damit gleichzeitig auch noch weitere Aufgaben ausgeführt werden können. Auf der CCPRO M128 soll der Morse-Sender und -Empfänger in einer 1ms-Interruptroutine parallel zum Hauptprogramm ablaufen.

Auf der M32 und M128 werden die als Morse-Code empfangenen Zeichen auf dem Display dargestellt, auf der Base am Terminal. Als Morse-Code zu sendende Zeichen können an allen Plattformen am Terminal als Text eingegeben werden. Denkbar ist auch, Morse-Zeichen direkt, z.B. mit einer Morse-Taste oder alternativ sogar mit den Bumpern des RP6 einzugeben, sie zu decodieren und anzuzeigen. Viele Möglichkeiten ...

Speicherung der Morse-Zeichen

Auf einem uC ist der Speicherplatz begrenzt, daher ist es wichtig, die Morse-Zeichen möglichst kompakt zu speichern. Da sie sich im Programmablauf nicht ändern, kann man sie auch im EEPROM oder Flash-Speicher ablegen. Ich habe mich für die letzte Option entschieden.

Wie kann man die Dits (Punkte) und Dahs (Striche) am besten speichern? Das längste Morse-Zeichen ...---... (SOS) hat 9 Dits/Dahs. Es ist auch das einzige so lange Zeichen,- alle anderen kommen mit 8 Dits/Dahs hin. Wenn ich SOS nicht berücksichtige, könnte ich die Morse-Zeichen in einem Byte so speichern, dass z.B. ein 0-Bit einem Dit und ein 1-Bit einem Dah entspricht. Das Problem dieser Lösung ist, dass man nicht erkennen kann, wo ein Morse-Zeichen zuende ist. Man müßte also mit mindestens 3 weiteren Bits die Länge des Morse-Zeichens festhalten. Dann bin ich bei einem Platzbedarf pro Morse-Zeichen von 11 Bit,- bei voller Speicherung auch der Ausnahme SOS bei 13 Bit.

Überschaubarer ist es, wenn ich eine 16-Bit Konstante für jedes Morse-Zeichen verwende. Daher lege ich mich auf folgendes Verfahren fest: Ich verwende jeweils 2 Bits für jedes Dit/Dah. Dabei steht die Bitfolge "01" für ein Dit und "11" für ein Dah. Die Bitfolge "00" wird als Ende des Morse-Zeichens gedeutet. Damit kann ich alle Morse-Zeichen einfach speichern,- allerdings nun wieder ohne SOS. Das ist aber kein Problem, weil das nicht existierende Morse-Zeichen ...---.. (SOI) anstelle von SOS gespeichert werden kann. Der Encoder oder Decoder erkennt dies und macht daraus dann wieder SOS.

Beispiel: Der Buchstabe "B" sieht als Morse-Zeichen so -... (Dah-Dit-Dit-Dit) aus. Als 16-Bit Konstante würde ich das "B" dann binär als 0b0000000001010111 speichern. Das entspricht der Hexadezimalzahl 0x0057 oder dezimal 87.

Ein weiteres Beispiel: Das Ausrufezeichen (!) sieht als (nicht ITU-konformes) Morse-Zeichen so -.-.-- (Dah-Dit-Dah-Dit-Dah-Dah) aus. Als 16-Bit Konstante würde ich das "!" dann binär als 0b0000111101110111 speichern. Das entspricht der Hexadezimalzahl 0x0F77 oder dezimal 3959.

Zusätzlich zu dieser Liste der Morse-Zeichen brauche ich für den Morse-Sender noch eine weitere Liste der ASCII-Zeichen mit ihrer Zuordnung zu den Morse-Zeichen. Für bestimmte Signale wird optional eine weitere Liste benötigt.

Darstellung der Morse-Zeichen

Zu den "normalen" im Morse-Code definierten Zeichen zählen:

 !  "  $  &  '  (  )  +  ,  -  .  /  0..9  :  ;  =  ?  @  A..Z  _ 

Die Buchstaben werden als Großbuchstaben angezeigt.

Diese Tabelle zeigt die im Morse-Code definierten Sonderzeichen und ihre Darstellung im Terminal der C-Control Pro IDE (ANSI), im Terminal des RP6Loaders (RP6LOADER), auf dem LC-Display (LCD) und dem Backlight Display (BLD):

Zeichen ANSI RP6LOADER LCD BLD Signal Bedeutung
^G ^g ^g ^g ^g
CH, ^H ch ch ch ch
^J ^j ^j ^j ^j
/S %s %s %s %s
^S ^s ^s ^s ^s VE Verstanden
/Z %z %z %z %z
.Z *z *z *z *z
/A, °A 193 194 %a 160
Ä 196 197 225 ae AA Zeilenende
C~ 199 200 c\ c~
\E 200 201 \e \e
/E 201 202 %e %e
Eth 208 209 et et
~N 209 210 238 ~n
Ö 214 215 239 oe
Ü 220 221 245 ue
Thorn 222 223 to to
ß 223 224 226 224

Die Sonderzeichen sind in den Zeichensätzen der Terminals (RP6Loader und C-Control Pro IDE) und der Displays leider an unterschiedlichen Positionen oder gar nicht enthalten. Beispiel: Der deutsche Umlaut "Ö" ist nach ANSI an Position 214 zu finden, im Zeichensatz des RP6Loaders an Position 215 und beim LCD an Position 239. Beim BLD ist das "Ö" gar nicht vorhanden.

Um die für den Morse-Code relevanten Sonderzeichen darstellen zu können, kann im Header der Morse Libraries durch Definition von ANSI, RP6LOADER, LCD oder BLD die Textausgabe der Decoder an das jeweilige Ausgabe-Ziel angepaßt werden.

Diese Tabelle zeigt die im Morse-Code definierten Morse-Signal-Namen:

Signal Bedeutung
HH Fehler
SK Verkehrsende
CT Spruchanfang
BK Unterbrechung
CL Station abmelden
CQ Achtung
DO Wähle Wabun Code
SOS (See-)Notruf

Auf den Displays der M32 und M128 und im Terminal-Fenster des RP6Loaders werden die Sonderzeichen und Signal-Namen als Kleinbuchstaben dargestellt. So sind sie auch in den Tabellen der Morse Libraries gespeichert. Im Programm der Morse-Station (M32) erfolgt die Eingabe der Namen von Sonderzeichen und Signalen im Terminal-Fenster allerdings in Großbuchstaben, da es einfacher ist, die normalen Zeichen mit der Tastatur als Kleinbuchstaben einzugeben.

Diese Tabelle zeigt die Morse-Signal-Namen, für die kein eigener Morse-Code existiert:

Signal ASCII Bedeutung
AS & Warten
K K Kommen
DE B Von ..., dies ist ...
KN ( Stationsruf
AR + Spruchende
NR / Zahl folgt
BT = Separator
IMI ? Wiederholung
R R Empfang ok

Will man diese Signale senden, benutzt man einfach das Zeichen, das in der Spalte ASCII aufgeführt ist. Empfängt man eines dieser Zeichen einzeln, handelt es sich am ehesten um das Signal aus dieser Tabelle. Die Empfehlung ITU-R M.1677 der ITU enthält genaue Informationen über die Benutzung der Signale.

Decodierung der Morse-Zeichen

Ein Decoder von Morse-Zeichen muss in der Lage sein, zwei Impulslängen und drei Pausenlängen voneinander zu unterscheiden. Dabei liegt die kürzeste Impuls-/Pausendauer bei 8ms (@ 150 WpM), die längste Pausendauer bei 2,8s (@ 3 WpM).

Diese Tabelle zeigt die zu decodierenden Impuls- und Pausenlängen:

Dit Impuls Dah Impuls Dit-Dah Pause Zeichen Pause Wörter Pause
Dits 1 3 1 3 7
3 WpM 400 ms 1200 ms 400 ms 1200 ms 2800 ms
150 WpM 8 ms 24 ms 8 ms 24 ms 56 ms

Für einen uC ist das technisch kein Problem. Eine Herausforderung ist, dass die Impuls- und Pausendauern zwar eine feste Abhängigkeit voneinander haben, dass aber die "Grundlänge" eines Dits (Punkt) dem Decoder primär nicht bekannt ist. Sie schwankt bei 3..150 WpM von 400..8 ms. Die längste Pause (Länge: 7 Dits) dauert bei 3..150 WpM von 2800..56 ms. Der Decoder muss also seine Grundgeschwindigkeit fortlaufend bis zu einem Faktor von 50 an den Morse-Sender anpassen können.

Eine weitere Herausforderung besteht darin, dass eine Morse-Sendung kein zuverlässiges Start- oder Ende-Signal (im Sinne eines technisch definierten "Übertragungs-Protokolls") kennt. Der Decoder muss also ständig "an der Leitung lauschen", weil jeder Impuls z.B. ein erstes "E" sein könnte. Theoretisch müßte er auch jede Pause in der Länge von 7 Dits als Leerzeichen decodieren und bei längeren Pausen lange "Ketten" von Leerzeichen produzieren. Meist wird das aber begrenzt: Bei unserem Decoder standardmäßig auf 3 Leerzeichen (einstellbar durch SPACE_CNT_LIMIT!).

Der eigentliche Morse-Decoder in den Libraries ist die Funktion task_MorseDec() bzw. decodeMorse() in CompactC. Immer, wenn die Funktion bei der RP6Base und M32 wieder in der Hauptschleife aufgerufen wird oder bei der M128 im Rahmen der 1ms Interruptroutine, wird der Eingangspin ausgewertet ("polling") und die jeweilige Impuls- oder Pausenlänge aufaddiert. Da man bei der RP6Base und M32 nicht genau weiß, in welchen Abständen die Task aufgerufen wird, wird die 100us Timer-Variable (timer) der RP6 Library benutzt, um die Impuls-/Pausenlängen zu bestimmen. Dabei dienen die Pausen (Dauer: 1, 3, 7 Dits) als Abbruchkriterium für die Impulse,- diese (Dauer: 1, 3 Dits) umgekehrt als Ende der Pausen. Je nach Pausendauer wird entschieden, ob ein Dit/Dah (Pause 1 Dit), ein komplettes Morse-Zeichen (Pause 3 Dits) oder ein Wort (Pause 7 Dits) zuende ist. Die Impulsdauer bestimmt, ob ein Punkt (Dit) oder ein Strich (Dah = 3 Dits) decodiert wird.

Da der Morse-Decoder sich der Sendegeschwindigkeit anpassen muss, wird die Länge der Punkte und Striche permanent mit der im Decoder zugrunde gelegten Länge verglichen. Ist ein empfangener Punkt um 10% kürzer als eingestellt, wird die Geschwindigkeit des Decoders erhöht. Ist ein empfangener Strich um 10% länger als eingestellt, wird die Geschwindigkeit des Decoders verringert. Die Schnelligkeit dieser Anpassung kann mit SPEED_VAR beeinflußt werden: Wird der Wert z.B. höher gewählt, kann sich der Decoder rascher an Wechsel der Sendegeschwindigkeit anpassen. Eine gewisse Trägheit der Anpassung ist aber auch sinnvoll. Die Grundgeschwindigkeit des Morse-Decoders ist auf 12 WpM bzw. 60 CpM (SPEED) eingestellt. Kennt man die Sendegeschwindigkeit schon, kann man die Variable decspeed entsprechend festlegen.

Die Punkte und Striche der Morse-Zeichen kann man auf allen drei Plattformen mit einer LED visualisieren (LIGHTDEC), auf der M32 und M128 auch hörbar machen (SOUND). Die Tonhöhe ist von ca. 300 bis 1000 Hz wählbar (durch Anpassen der Variable tonepitch). SOUND ist in den Libraries standardmäßig nicht definiert (AUSgeschaltet). Bei einer Änderung der Definition von LIGHTDEC oder SOUND muss die Library neu kompiliert werden. Wenn man beide Funktionen (Morse-Sender und -Empfänger) der Morse Library gleichzeitig benutzt, sollte SOUND NICHT definiert sein.

Mit der Definition INVERTDEC kann man den Eingangspegel des Decoders umkehren: Ein Lowpegel am gewählten Eingang wird als Dit-/Dah-Impuls gedeutet und ein Highpegel als Pause. Diese Einstellung ist auch erforderlich, wenn man als Eingang den IR-Empfänger der RP6Base nutzen will.

Wenn ein Morse-Zeichen decodiert wurde, schreibt der Morse-Decoder seinen Namen in einen Ring-Puffer (Array morsedec_buffer). Aus ihm kann der Name mit den Funktionen readMorseChar() und readMorseChars() vom Hauptprogramm gelesen werden. Dabei entspricht ein Morse-Zeichen nicht immer auch genau EINEM ASCII-Zeichen im Puffer. Wurde z.B. das Morse-Zeichen -.-.--.- decodiert, steht dieser Code für das Signal "CQ". Der Ring-Puffer enthält also nach dem Decodieren die 2 ASCII-Zeichen dieses Signal-Namens. Dabei werden alle Sonderzeichen und Signal-Namen als Kleinbuchstaben (im Beispiel also als "cq") abgelegt, die normalen Buchstaben des Alphabets jedoch als Großbuchstaben ("A".."Z"). Die maximale Länge von Signal-Namen beträgt 3 Zeichen ("sos"). Mit der Funktion getMorseDecBufferLength() kann man ermitteln, wieviele Zeichen noch im Empfangspuffer sind.

Encodierung der Morse-Zeichen

Ein Morse-Sender muss zwei Impulslängen und drei Pausenlängen in der gewünschten Geschwindigkeit erzeugen können. Dabei liegt die kürzeste Impuls-/Pausendauer bei 8ms (@ 150 WpM), die längste Pausendauer bei 2,8s (@ 3 WpM).

Der eigentliche Morse-Encoder in den Libraries ist die Funktion task_MorseEnc() bzw. encodeMorse() in CompactC. Immer, wenn die Funktion bei der RP6Base und M32 wieder in der Hauptschleife aufgerufen wird oder bei der M128 im Rahmen der 1ms Interruptroutine, wird die Rest-Länge des aktuell zu sendenden Impulses oder der zu sendenden Pause errechnet und ggf. der jeweilige Zustand (Impuls/Pause) beendet oder gewechselt. Da man bei der RP6Base und M32 nicht genau weiß, in welchen Abständen die Task aufgerufen wird, wird die 100us Timer-Variable (timer) der RP6 Library benutzt, um die Impuls-/Pausenlängen zu bestimmen. Die Grundgeschwindigkeit des Morse-Encoders ist auf 12 WpM bzw. 60 CpM (SPEED) eingestellt, kann aber durch Anpassen der Variable encspeed verändert werden.

Die Punkte und Striche der Morse-Zeichen kann man auf allen drei Plattformen mit einer LED visualisieren (LIGHTENC), auf der M32 und M128 auch hörbar machen (SOUND). Die Tonhöhe ist von ca. 300 bis 1000 Hz wählbar (durch Anpassen der Variable tonepitch). SOUND ist in den Libraries standardmäßig nicht definiert (AUSgeschaltet). Bei einer Änderung der Definition von LIGHTENC oder SOUND muss die Library neu kompiliert werden. Wenn man beide Funktionen (Morse-Sender und -Empfänger) der Morse Library gleichzeitig benutzt, sollte SOUND NICHT definiert sein.

Der Morse-Encoder entnimmt so lange zu sendende Morse-Zeichen (genauer: Indizes der Morse-Zeichen aus der Tabelle ms_ft) aus einem Ring-Puffer (Array morseenc_buffer), bis dieser Puffer leer ist. Mit den Funktionen writeMorseChar() und writeMorseString() kann das Hauptprogramm zu sendende Zeichen/Signal-Namen (als Indizes) in dem Puffer ablegen. Sonderzeichen und Signal-Namen müssen in Kleinbuchstaben (z.B. "cq") angegeben werden. Mit der Funktion getMorseEncBufferLength() kann man ermitteln, wieviele Indizes noch im Sendepuffer sind.

Die Funktion pauseMorse() ermöglicht das Senden längerer Pausen mit nur einem Index im Sendepuffer. Hierdurch spart man wertvollen Platz in diesem Puffer.


Libraries

RP6 Base

Die RP6Base Morse Library gehört in den Ordner \RP6Lib\RP6base.

Header

Datei RP6BaseMorseLib.h:

/* ****************************************************************************
 *                           _______________________
 *                           \| RP6  ROBOT SYSTEM |/
 *                            \_-_-_-_-_-_-_-_-_-_/         >>> BASE CONTROLLER
 * ----------------------------------------------------------------------------
 * ------------------------ [c]2012 - Dirk ------------------------------------
 * ****************************************************************************
 * File: RP6BaseMorseLib.h
 * Version: 3.6w
 * Target: RP6 Base - ATMEGA32 @8.00MHz
 * Author(s): Dirk
 * ****************************************************************************
 * Description:
 * This is the RP6BaseMorse library header file.
 * You have to include this file, if you want to use the library
 * RP6BaseMorseLib.c in your own projects.
 *
 * ****************************************************************************
 * THE CHANGELOG CAN BE FOUND AT THE END OF THIS FILE!
 * ****************************************************************************
 */

#ifndef RP6BASEMORSE_H
#define RP6BASEMORSE_H

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

#include "RP6RobotBaseLib.h" 	// The RP6 Robot Base Library.
								// Always needs to be included!

/*****************************************************************************/
// Defines:

#define SPEED						100		// = 12 WpM = 60 CpM
// Calculate SPEED: SPEED = 1200 / WpM
//                  SPEED = 6000 / CpM
#define SPEED_MIN					400		// = 3 WpM = 15 CpM
#define SPEED_MAX					8		// = 150 WpM = 750 CpM
#define SPEED_VAR					5		// Decoder speed variation

#define LIMITED_PAUSE						// Decoder: Spaces limited
#define SPACE_CNT_LIMIT				3		// Max. number of spaces

//#define INVERTDEC							// Invert decoder input level

//#define DEBUG								// Decoder debug mode

//#define IRCOMMENC							// Use IRCOMM to send Morse code
// IMPORTANT: If you use the IRCOMM LEDs to send Morse code, you cannot use
//            the ACS or the IRCOMM_sendRC5() function at the same time! The
//            ACS may be deactivated while sending Morse code by calling the
//            function disableACS().

//#define ANSI								// Use ANSI char set
#define RP6LOADER							// Use RP6Loader terminal char set
// IMPORTANT: You may activate only ONE of the two above definitions!

#define LINE_LENGTH					32		// Terminal line length

#define LIGHTDEC							// SL1 shows decoder Morse sign
#define LIGHTENC							// SL2 shows encoder Morse sign

#define MS_SIGNALS_MAXINDEX			7
#define MS_SPECIALS_MAXINDEX		25
#define MORSESIGNS_MAXINDEX			79

// Flash constants (Morse tables):
const uint16_t ms_ft[MORSESIGNS_MAXINDEX + 1];
const uint8_t ms_a0uc_ft[MORSESIGNS_MAXINDEX + 1];
const uint8_t ms_a1uc_ft[MORSESIGNS_MAXINDEX + 1];
const uint8_t ms_a2uc_ft[MORSESIGNS_MAXINDEX + 1];
const uint8_t a_ms_ft[256];

#define MORSEDEC_BUFFER_MAXINDEX	31		// Morse decoder buffer length
#define MORSEENC_BUFFER_MAXINDEX	31		// Morse encoder buffer length

// Morse decoder/encoder status:
#define MORSE_BUFFER_OK				0
#define MORSE_BUFFER_OVERFLOW		1		// Morse buffer overflow

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

extern uint8_t morsedec_status;
extern uint8_t morseenc_status;
extern uint8_t morse_error;

char morsedec_buffer[MORSEDEC_BUFFER_MAXINDEX + 2];
uint8_t dec_write_pos, dec_read_pos;
char morseenc_buffer[MORSEENC_BUFFER_MAXINDEX + 2];
uint8_t enc_write_pos, enc_read_pos;

uint16_t decspeed;
uint8_t speedvar;

uint16_t encspeed;

#ifdef DEBUG
uint16_t ditlength, dahlength;
#endif

/*****************************************************************************/
// Functions:

uint8_t Lower2UpperCase(uint8_t);
uint8_t Upper2LowerCase(uint8_t);

uint16_t MsIndex2MorseCode(uint8_t);
uint8_t MorseCode2MsIndex(uint16_t);
void MorseCode2MsName(char *, uint16_t);
uint8_t MsName2MsIndex(char *);

void MorseCode2MorseSign(char *, uint16_t);
uint16_t MorseSign2MorseCode(char *);

void clearMorseDecBuffer(void);
void initMorseDecoder(void);
void storeMsChar2DecBuffer(uint8_t);
void task_MorseDec(void);
uint8_t readMorseChar(void);
uint8_t readMorseChars(char *, uint8_t);
uint8_t getMorseDecBufferLength(void);

void initMorseEncoder(void);
uint8_t fetchMsIndexFromEncBuffer(void);
void task_MorseEnc(void);
void storeMsIndex2EncBuffer(uint8_t);
void pauseMorse(uint8_t);
void writeMorseChar(uint8_t);
void writeMorseString(char *);
uint8_t getMorseEncBufferLength(void);

#ifndef DEBUG
void writeMorse(void);
#else
void writeDebugInfo(void);
#endif


#endif

/******************************************************************************
 * Additional info
 * ****************************************************************************
 * Changelog:
 * 
 *  ---> changes are documented in the file "RP6BaseMorseLib.c"
 *
 * ****************************************************************************
 */

/*****************************************************************************/
// EOF

Library

Datei RP6BaseMorseLib.c:

/* ****************************************************************************
 *                           _______________________
 *                           \| RP6  ROBOT SYSTEM |/
 *                            \_-_-_-_-_-_-_-_-_-_/         >>> BASE CONTROLLER
 * ----------------------------------------------------------------------------
 * ------------------------ [c]2012 - Dirk ------------------------------------
 * ****************************************************************************
 * File: RP6BaseMorseLib.c
 * Version: 3.6w
 * Target: RP6 Base - ATMEGA32 @8.00MHz
 * Author(s): Dirk
 * ****************************************************************************
 * Description:
 *
 * The RP6 Base Morse Library.
 *
 * ****************************************************************************
 * ATTENTION: The 100us timer is used for the Morse decoder and encoder
 *            task! Please do not alter the variable "timer" elsewhere in
 *            your program!
 *
 * ****************************************************************************
 * THE CHANGELOG CAN BE FOUND AT THE END OF THIS FILE!
 * ****************************************************************************
 */
 
/*****************************************************************************/
// Includes:

#include "RP6BaseMorseLib.h"

/*****************************************************************************/
// Defines:

// RP6 Base Morse Decoder Connection (input):
#define MORSEDEC_PORT	PORTC
#define MORSEDEC_DDR	DDRC
#define MORSEDEC_PIN	PINC
//#define MORSEDEC_IN		SCL					// PINC0  XBUS Pin 10
#define MORSEDEC_IN		SDA					// PINC1  XBUS Pin 12

//#define MORSEDEC_PORT	PORTA
//#define MORSEDEC_DDR	DDRA
//#define MORSEDEC_PIN	PINA
//#define MORSEDEC_IN		E_INT1				// PINA4  XBUS Pin 8

//#define MORSEDEC_PORT	PORTB
//#define MORSEDEC_DDR	DDRB
//#define MORSEDEC_PIN	PINB
//#define MORSEDEC_IN		ACS					// PINB2 (IR receiver)
// IMPORTANT: If you use the IR receiver as input for the Morse decoder,
//            you have to switch it's power on in the main program:
//            ==> powerON(); <==
//            Activate INVERTDEC in the RP6Base Morse Library header!
//            The ACS may be deactivated while receiving Morse code by
//            calling the function disableACS().

// RP6 Base Morse Encoder Connection (output):
//#define MORSEENC_PORT	PORTC
//#define MORSEENC_DDR	DDRC
//#define MORSEENC_PIN	PINC
//#define MORSEENC_IN		SCL					// PINC0  XBUS Pin 10
//#define MORSEENC_IN		SDA					// PINC1  XBUS Pin 12

#define MORSEENC_PORT	PORTA
#define MORSEENC_DDR	DDRA
#define MORSEENC_PIN	PINA
#define MORSEENC_IN		E_INT1				// PINA4  XBUS Pin 8

// ----------------------------------------------------------------------------
// MORSE TABLES:

// Morse Table [0..79]:
// Morse decoders and encoders use this table for receiving or sending Morse
// code. This table consists of 16-bit constants. Each table index [0..79]
// (or each word constant) represents one Morse sign.
// The dots (dit) and the dashes (dah) are stored as two bits: The bits "01"
// stand for a dit and "11" for a dah, read from right to left in the binary
// notation. Between dits and dahs of a Morse sign you have to send a pause
// with the length of one dit. Between Morse signs there is a pause with the
// length of three dits (or one dah).
//
// Example:                     End <<<<7<<6<<5<<4<<3<<2<<1<<<< Start
//                                  ---DahDitDitDahDitDitDit
// 0x35D5 = 0b0011010111010101 -> 0b 00 11 01 01 11 01 01 01 -> $ (Dollar)
const uint16_t ms_ft[] PROGMEM =
// Signals (prosigns):
// Hex		  Binary		   Sign	   Index  Prosign
{0x5555, // 0b0101010101010101			 0		HH
 0x0DD5, // 0b0000110111010101					SK
 0x0377, // 0b0000001101110111					CT
 0x3757, // 0b0011011101010111					BK
 0x5D77, // 0b0101110101110111					CL
 0xDF77, // 0b1101111101110111			 5		CQ
 0x0FD7, // 0b0000111111010111					DO
 0x5FD5, // 0b0101111111010101			 7		SOS
//------------------------------------------------------
// Special characters:
// Hex		  Binary		   Sign	   Index  Prosign
 0x01DF, // 0b0000000111011111  ^G		 8
 0x00FF, // 0b0000000011111111  CH,^H
 0x01FD, // 0b0000000111111101  ^J		10
 0x15D5, // 0b0001010111010101  /S
 0x01D5, // 0b0000000111010101  ^S				VE
 0x075F, // 0b0000011101011111  /Z
 0x035F, // 0b0000001101011111  .Z
 0x037D, // 0b0000001101111101  /A,°A	15
 0x00DD, // 0b0000000011011101  Ä				AA
 0x0177, // 0b0000000101110111  C~
 0x035D, // 0b0000001101011101  \E
 0x0175, // 0b0000000101110101  /E
 0x01F5, // 0b0000000111110101  Eth		20
 0x03DF, // 0b0000001111011111  ~N
 0x007F, // 0b0000000001111111  Ö
 0x00F5, // 0b0000000011110101  Ü
 0x017D, // 0b0000000101111101  Thorn
 0x17D5, // 0b0001011111010101  ß		25
//------------------------------------------------------
// Normal characters:
// Hex		  Binary		   Sign	   Index  Prosign
 0x0F77, // 0b0000111101110111  !		26
 0x075D, // 0b0000011101011101  "
 0x35D5, // 0b0011010111010101  $
 0x015D, // 0b0000000101011101  &				AS
 0x07FD, // 0b0000011111111101  '		30
 0x01F7, // 0b0000000111110111  (				KN
 0x0DF7, // 0b0000110111110111  )
 0x01DD, // 0b0000000111011101  +				AR
 0x0F5F, // 0b0000111101011111  ,
 0x0D57, // 0b0000110101010111  -		35
 0x0DDD, // 0b0000110111011101  .
 0x01D7, // 0b0000000111010111  /				NR
 0x03FF, // 0b0000001111111111  0
 0x03FD, // 0b0000001111111101  1
 0x03F5, // 0b0000001111110101  2		40
 0x03D5, // 0b0000001111010101  3
 0x0355, // 0b0000001101010101  4
 0x0155, // 0b0000000101010101  5
 0x0157, // 0b0000000101010111  6
 0x015F, // 0b0000000101011111  7		45
 0x017F, // 0b0000000101111111  8
 0x01FF, // 0b0000000111111111  9
 0x057F, // 0b0000010101111111  :
 0x0777, // 0b0000011101110111  ;
 0x0357, // 0b0000001101010111  =		50		BT
 0x05F5, // 0b0000010111110101  ?				IMI
 0x077D, // 0b0000011101111101  @
 0x000D, // 0b0000000000001101  A
 0x0057, // 0b0000000001010111  B				DE
 0x0077, // 0b0000000001110111  C		55
 0x0017, // 0b0000000000010111  D
 0x0001, // 0b0000000000000001  E
 0x0075, // 0b0000000001110101  F
 0x001F, // 0b0000000000011111  G
 0x0055, // 0b0000000001010101  H		60
 0x0005, // 0b0000000000000101  I
 0x00FD, // 0b0000000011111101  J
 0x0037, // 0b0000000000110111  K				K
 0x005D, // 0b0000000001011101  L
 0x000F, // 0b0000000000001111  M		65
 0x0007, // 0b0000000000000111  N
 0x003F, // 0b0000000000111111  O
 0x007D, // 0b0000000001111101  P
 0x00DF, // 0b0000000011011111  Q
 0x001D, // 0b0000000000011101  R		70		R
 0x0015, // 0b0000000000010101  S
 0x0003, // 0b0000000000000011  T
 0x0035, // 0b0000000000110101  U
 0x00D5, // 0b0000000011010101  V
 0x003D, // 0b0000000000111101  W		75
 0x00D7, // 0b0000000011010111  X
 0x00F7, // 0b0000000011110111  Y
 0x005F, // 0b0000000001011111  Z
 0x0DF5};// 0b0000110111110101  _		79
// Remarks: - SOS (Morse sign ...---...) can not be stored in a 16-bit
//            constant because SOS is the only Morse sign with 9 dits/dahs.
//            So SOS is stored as the (not existing) Morse sign ...---..
//            (SOI) and must be treated special in decoders/encoders.  


// Morse-ASCII-Table [0..79]:
// Morse decoders use this table for receiving Morse code.
const uint8_t ms_a0uc_ft[] PROGMEM = 
//H   S   C   B    C   C   D   S
{104,115, 99, 98, 99, 99,100,115,
//0                    5
#ifdef ANSI
//                            ANSI [index 15..25]:
//^   C   ^   %    ^   %   *   /A  Ä   C~  \E  /E  Et  ~N   Ö   Ü  To   ß
  94, 99, 94, 37, 94, 37, 42,193,196,199,200,201,208,209,214,220,222,223,
//        10                   15                  20                   25
#endif
#ifdef RP6LOADER
//                            RPLoader terminal [index 15..25]:
//^   C   ^   %    ^   %   *   /A  Ä   C~  \E  /E  Et  ~N   Ö   Ü  To   ß
  94, 99, 94, 37, 94, 37, 42,194,197,200,201,202,209,210,215,221,223,224,
//        10                   15                  20                   25
#endif
//!  "  $  &  '  (  )   +  ,  -  .  /  0  1  2   3  4  5  6  7  8  9  :  ;
 33,34,36,38,39,40,41,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,
//            30             35              40             45
//=  ?  @  A  B  C   D   E    F   G   H   I   J   K   L   M   N   O    P   Q
 61,63,64,65,66,67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81,
//50            55                   60                   65
// R  S   T   U   V   W   X   Y    Z   _  
  82, 83, 84, 85, 86, 87, 88, 89, 90,95};		// Et = Eth,  To = Thorn
//70                  75              79

const uint8_t ms_a1uc_ft[] PROGMEM = 
//H   K   T   K    L   Q   O   O
{104,107,116,107,108,113,111,111,
//0                    5
//G   H   J   S    S   Z   Z
 103,104,106,115,115,122,122, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32,
//        10                   15                  20                   25
 32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,
//            30             35              40             45
 32,32,32,32,32,32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32,
//50            55                   60                   65
  32, 32, 32, 32, 32, 32, 32, 32, 32,32};		// Et = Eth,  To = Thorn
//70                  75              79

const uint8_t ms_a2uc_ft[] PROGMEM = 
//                             S
{ 32, 32, 32, 32, 32, 32, 32,115,
// 0                   5
  32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32,
//        10                   15                  20                   25
 32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,
//            30             35              40             45
 32,32,32,32,32,32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32,
//50            55                   60                   65
  32, 32, 32, 32, 32, 32, 32, 32, 32,32};		// Et = Eth,  To = Thorn
//70                  75              79
// Prosigns and special characters are stored as lower case letters (hh,
// sk, ^g, ch ...) in this table.
// Remarks: - The special chars  ^G, ^J, /S, ^S, /Z, .Z [indices 8, 10..14]
//            are represented as ^g, ^j, %s, ^s, %z, *z in this table.
//          - The special chars [indices 15..25] are represented in several
//            ways in this table depending on the output target (ANSI,
//            RP6LOADER).
//          - If Morse decoders receive a pause with the length of 7 dits,
//            they have to give out the ASCII code ' ' (space [32]).


// ASCII-Morse-Table [0..255]:
// Morse encoders use this table to send Morse code.
const uint8_t a_ms_ft[] PROGMEM =
{51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,
//0              5              10              15             20
 51,51,51,51,51,51,51,51,
//24                30
//_  !  "  ?  $  ?  &  '  (  )   X  +  ,  -  .  /  0  1   2  3  4  5  6  7
 79,26,27,51,28,51,29,30,31,32,76,33,34,35,36,37,38,39,40,41,42,43,44,45,
//32       35             40              45             50              55
//8  9  :  ;  ?  =  ?  ?   @  A  B  C  D  E  F  G  H   I  J  K  L  M  N  O
 46,47,48,49,51,50,51,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,
//56          60             65              70              75
//P  Q  R  S  T  U  V  W  X   Y  Z  [  ?  ]  ?  _   ?  A  B  C  D  E  F  G
 68,69,70,71,72,73,74,75,76,77,78,31,51,32,51,79,51,53,54,55,56,57,58,59,
//80             85             90              95             100
//H  I  J  K  L  M  N  O   P  Q  R  S  T  U  V  W   X  Y  Z  {  ?  }  ?  ?
 60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,31,51,32,51,51,
//104              110             115            120             125
//?  ?  ?  ?  ?  ?  ?  ?   ?  ?  ?  ?  ?  ?  ?  ?  ?   ?  ?  ?  ?  ?  ?  ?
 51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,
//128  130            135             140            145             150
//?  ?  ?  ?  ?  ?  ?  ?   _  ?  ?  ?  ?  ?  ?  ?  ?   ?  ?  ?  ?  ?  ?  ?
 51,51,51,51,51,51,51,51,79,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,
//152     155            160             165             170            175
//?  ?  ?  ?  ?  ?  ?  ?  ?   ?  ?  ?  ?  ?  ?  ?  ?  /A  ?  ?  Ä  ?  ?  C~
 51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,15,51,51,16,51,51,17,
//176        180             185            190             195
//\E/E  ?  ?  ?  ?  ?  ?  Et ~N  ?  ?  ?  ?  Ö  X   ?  ?  ?  ?  Ü  ?  To ß
 18,19,51,51,51,51,51,51,20,21,51,51,51,51,22,76,51,51,51,51,23,51,24,25,
//200           205             210            215             220
//? /A  ?  ?  Ä  ?  ?  C~ \E /E  ?  ?  ?  ?  ?  ?  Et ~N  ?  ?  ?  ?  Ö  /
 51,15,51,51,16,51,51,17,18,19,51,51,51,51,51,51,20,21,51,51,51,51,22,37,
//224              230             235            240             245
//?  ?  ?  ?  Ü  ?  To ?
 51,51,51,51,23,51,24,51};					// Et = Eth,  To = Thorn
//248                 255
// Remarks: - ASCII codes 91 '[' and 123 '{' are converted to Morse
//            code '(' [31].
//          - ASCII codes 93 ']' and 125 '}' are converted to Morse
//            code ')' [32].
//          - ASCII code 215 (multiplication sign) is converted to
//            Morse code 'X' [76].
//          - ASCII code 247 (division sign) is converted to Morse
//            code '/' [37].
//          - ASCII codes 32 (sp) and 160 (nbsp) are represented as
//            '_' [79] in this table but must be treated special in
//            encoders: The Morse encoder has to send a pause with
//            the length of 7 dits for a space.
//          - All non printable ASCII codes [0..31] and other codes
//            not defined in the Morse code are converted to Morse
//            code '?' [51].

// MORSE TABLES (END)
// ----------------------------------------------------------------------------

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

uint8_t morsedec_status;
uint8_t morseenc_status;
uint8_t morse_error;

/*****************************************************************************/
// Functions:

/**
 * Convert lower case to upper case letters
 *
 * Input:  ASCII code [0..255]
 * Output: ASCII code, only with upper case letters
 *
 */
uint8_t Lower2UpperCase(uint8_t ch)
{uint8_t chuc;
	chuc = ch;
	if ((ch >= 97) && (ch <= 122)) {
		chuc -= 32;
	}
	if ((ch >= 224) && (ch <= 254) && (ch != 247)) {
		chuc -= 32;
	}
	return (chuc);
}

/**
 * Convert upper case to lower case letters
 *
 * Input:  ASCII code [0..255]
 * Output: ASCII code, only with lower case letters
 *
 */
uint8_t Upper2LowerCase(uint8_t ch)
{uint8_t chlc;
	chlc = ch;
	if ((ch >= 65) && (ch <= 90)) {
		chlc += 32;
	}
	if ((ch >= 192) && (ch <= 222) && (ch != 215)) {
		chlc += 32;
	}
	return (chlc);
}

/**
 * Output the Morse code of a Morse table index
 *
 * Input:  Morse table index [0..MORSESIGNS_MAXINDEX]
 * Output: Morse code (See table ms_ft[] above!)
 *
 */
uint16_t MsIndex2MorseCode(uint8_t msindex)
{
	morse_error = false;
	return (pgm_read_word(&ms_ft[msindex]));
}

/**
 * Output the table index of a Morse code
 *
 * Input:  Morse code (See table ms_ft[] above!)
 * Output: Morse table index [0..MORSESIGNS_MAXINDEX]
 *
 */
uint8_t MorseCode2MsIndex(uint16_t morsecode)
{uint8_t msidx;
	for (msidx = 0; msidx <= MORSESIGNS_MAXINDEX; msidx++) {
		if (morsecode == pgm_read_word(&ms_ft[msidx])) {break;}
	}
	if (msidx <= MORSESIGNS_MAXINDEX) {
		morse_error = false;
		return (msidx);					// Morse table index
	}
	else {
		morse_error = true;				// Unknown Morse code:
		return (51);					//  Return table index of '?'
	}
}

/**
 * Output the Morse sign name of a Morse code
 *
 * Input:  Morse code (See table ms_ft[] above!)
 * Output: String with Morse sign name (1..3 ASCII letters)
 *
 */
void MorseCode2MsName(char *msname, uint16_t morsecode)
{uint8_t msidx;
	msidx = MorseCode2MsIndex(morsecode);
	msname[0] = pgm_read_byte(&ms_a0uc_ft[msidx]);
	msname[1] = pgm_read_byte(&ms_a1uc_ft[msidx]);
	if (msname[1] == 32) {msname[1] = '\0';}
	msname[2] = pgm_read_byte(&ms_a2uc_ft[msidx]);
	if (msname[2] == 32) {
		msname[2] = '\0';
	}
	else {
		msname[3] = '\0';
	}
}

/**
 * Output the Morse table index of a Morse sign name
 *
 * Input:  String with Morse sign name (1..3 ASCII letters)
 * Output: Morse table index [0..MORSESIGNS_MAXINDEX]
 *
 */
uint8_t MsName2MsIndex(char *msname)
{uint8_t msidx;
	for (msidx = 0; msidx <= MORSESIGNS_MAXINDEX; msidx++) {
		if (msname[0] == pgm_read_byte(&ms_a0uc_ft[msidx])) {
			if ((pgm_read_byte(&ms_a1uc_ft[msidx]) == 32)
			 || (msname[1] == pgm_read_byte(&ms_a1uc_ft[msidx]))) {
				if ((pgm_read_byte(&ms_a2uc_ft[msidx]) == 32)
				 || (msname[2] == pgm_read_byte(&ms_a2uc_ft[msidx]))) {
					break;
				}
			}
		}
	}
	if (msidx <= MORSESIGNS_MAXINDEX) {
		morse_error = false;
		return (msidx);					// Morse table index
	}
	else {
		morse_error = true;				// Unknown Morse sign name:
		return (51);					//  Return table index of '?'
	}
}

/**
 * Output the Morse sign of a Morse code
 *
 * Input:  Morse code (See table ms_ft[] above!)
 * Output: String with the Morse sign (1..9 dits [.] or dahs [-])
 *
 * Example: $  -> 0b0011010111010101  -> Morse sign ...-..-
 *
 */
void MorseCode2MorseSign(char *morsesign, uint16_t morsecode)
{uint8_t i; uint16_t ms_code;
	ms_code = morsecode;
	i = 0;
	do {
		switch (ms_code & 3) {
			case 1 :					// dit!
				morsesign[i] = '.';
				i++; break;
			case 3 :					// dah!
				morsesign[i] = '-';
				i++;
		}
		ms_code >>= 2;
	} while (ms_code);
	if (morsecode == 0x5FD5) {			// SOS: Add last dit!
		morsesign[i] = '.';
		i++;
	}
	morsesign[i] = '\0';
	morse_error = false;
}

/**
 * Output the Morse code of a Morse sign
 *
 * Input:  String with the Morse sign (1..9 dits [.] or dahs [-])
 * Output: Morse code (See table ms_ft[] above!)
 *
 * Example: $  -> Morse sign ...-..-  -> 0b0011010111010101
 *
 */
uint16_t MorseSign2MorseCode(char *morsesign)
{uint8_t i, ch; uint16_t ms_code;
	ms_code = 0;
	ch = 1;
	for (i = 0; i <= 7; i++) {
		ms_code >>= 2;
		if (ch) {
			ch = morsesign[i];
			switch (ch) {
				case '.' :					// dit!
					ms_code |= 0x4000; break;
				case '-' :					// dah!
					ms_code |= 0xC000;
			}
		}
		
	}
	if ((ms_code == 0x5FD5) && (morsesign[8] != '.')) {
		ms_code = 0x05F5;	// SOS: If last dit doesn't exist, return '?'!
		morse_error = true;
	}
	else {
		morse_error = false;
	}
	return (ms_code);
}

/*****************************************************************************/
// Morse decoder functions:

/**
 * Clear the Morse decoder ring buffer
 *
 */
void clearMorseDecBuffer(void)
{
	morsedec_status = MORSE_BUFFER_OK;		// Decoder buffer status ok
	dec_write_pos = 255;					// Reset buffer write position
	dec_read_pos = 255;						// Reset buffer read position
}

/**
 * Init Morse Decoder
 *
 * Call this once before using the Morse decoder (receiver) task!
 *
 */
void initMorseDecoder(void)
{
	MORSEDEC_DDR &= ~MORSEDEC_IN;			// Decoder input pin
	MORSEDEC_PORT |= MORSEDEC_IN;			// MORSEDEC_IN -> Pullup
	morse_error = false;					// Reset Morse error flag
	clearMorseDecBuffer();					// Clear the decoder buffer
	decspeed = SPEED;						// Decoder speed
	speedvar = SPEED_VAR;					// Decoder speed variation
}

/**
 * Store a decoded (prosign) Morse sign char into the decoder ring buffer
 *
 * Input: ASCII char (part of a string with the (pro)sign name)
 *
 */
void storeMsChar2DecBuffer(uint8_t ch)
{
	if (getMorseDecBufferLength() < MORSEDEC_BUFFER_MAXINDEX) {
		dec_write_pos++;
		if (dec_write_pos > MORSEDEC_BUFFER_MAXINDEX) {
			dec_write_pos = 0;
		}
		morsedec_buffer[dec_write_pos] = ch;
		morsedec_status = MORSE_BUFFER_OK;	// Decoder buffer status ok
	}
	else {
		morsedec_status = MORSE_BUFFER_OVERFLOW;// Decoder buffer overflow
	}
}

/**
 * Morse decoder task
 *
 */
void task_MorseDec(void)
{uint16_t time_100usecs;
 static char ms_sign[10]; uint8_t temp;
 static uint16_t last_timer, signal, pause;
 static uint8_t ditdah, ditdah_cnt;
 char ms_name[4]; 
#ifdef LIMITED_PAUSE
 static uint8_t space_cnt;
#endif 
	time_100usecs = timer - last_timer;
	last_timer += time_100usecs;
	temp = MORSEDEC_PIN & MORSEDEC_IN;		// Read Morse level
#ifdef INVERTDEC
	temp = (!temp);							// Invert input level
#endif
	if (temp) {								// Signal on
#ifdef LIGHTDEC
		statusLEDs.LED1 = true;
		updateStatusLEDs();
#endif
		signal += time_100usecs;
		if (pause > (decspeed * 20)) {		// Pause > 2 dits:
			if (ditdah) {					//  Morse sign end (length 3 dits)
				ms_sign[ditdah_cnt] = ditdah;
				ditdah_cnt++;
				ms_sign[ditdah_cnt] = '\0';
				ditdah_cnt = 0;
				ditdah = 0;
				MorseCode2MsName(ms_name, MorseSign2MorseCode(ms_sign));
				temp = 0;
				while (ms_name[temp]) {
					storeMsChar2DecBuffer(ms_name[temp++]);
				}
			}
			pause = 0;
		}
		if (pause) {						// Short pause: 
			if (ditdah) {					//  Dit or dah end (length 1 dit)
				ms_sign[ditdah_cnt] = ditdah;
				ditdah_cnt++;
				ms_sign[ditdah_cnt] = '\0';
				if (ditdah_cnt > 8) {ditdah_cnt = 0;}
				ditdah = 0;
			}
			pause = 0;
		}
	}
	else {									// Signal off (pause)
#ifdef LIGHTDEC
		statusLEDs.LED1 = false;
		updateStatusLEDs();
#endif
		pause += time_100usecs;
		if (pause > (decspeed * 50)) {		// Pause > 5 dits:
			if (ditdah) {					//  Space or longer pause
				ms_sign[ditdah_cnt] = ditdah;
				ditdah_cnt++;
				ms_sign[ditdah_cnt] = '\0';
				ditdah_cnt = 0;
				ditdah = 0;
				MorseCode2MsName(ms_name, MorseSign2MorseCode(ms_sign));
				temp = 0;
				while (ms_name[temp]) {
					storeMsChar2DecBuffer(ms_name[temp++]);
				}
#ifdef LIMITED_PAUSE
				space_cnt = SPACE_CNT_LIMIT;
				space_cnt--;
#endif
				storeMsChar2DecBuffer(' ');		// Add a space after a sign
				pause = 0;
			}
#ifdef LIMITED_PAUSE
			if (space_cnt) {
#endif
				if (pause >= (decspeed * 70)) {// Pause >= 7 dits:
					storeMsChar2DecBuffer(' '); // Add spaces while pause
					pause -= (decspeed * 70);
#ifdef LIMITED_PAUSE
					space_cnt--;
#endif
				}
#ifdef LIMITED_PAUSE
			}
			else {
				pause = 0;
			}
#endif
		}
		if (signal > (decspeed * 20)) {	// Signal > 2 dits:
#ifdef DEBUG
			dahlength = signal;
#endif
			ditdah = '-';					//  Dah (length 3 dits)!
			if (signal >= (decspeed * 33)) {// Signal >= 3.3 dits (+10%):
				decspeed += speedvar;		//   Reduce decoder speed
				if (decspeed > SPEED_MIN) {decspeed = SPEED_MIN;}
			}
			signal = 0;
		}
		if (signal) {						// Short signal:
#ifdef DEBUG
			ditlength = signal;
#endif
			ditdah = '.';					//  Dit!
			if (signal <= (decspeed * 9)) {// Signal <= 0.9 dits (-10%):
				decspeed -= speedvar;		//  Increase decoder speed
				if (decspeed < SPEED_MAX) {decspeed = SPEED_MAX;}
			}
			signal = 0;
		}
	}
}

/**
 * Read next character from the Morse decoder ring buffer
 *
 * Output: Printable ASCII character [32..255] (as part of
 *         a received/decoded (prosign) Morse sign name)
 *         OR 0 (false), if the ring buffer is empty
 *
 */
uint8_t readMorseChar(void)
{uint8_t ch;
	if (dec_read_pos != dec_write_pos) {
		dec_read_pos++;
		if (dec_read_pos > MORSEDEC_BUFFER_MAXINDEX) {
			dec_read_pos = 0;
		}
		ch = morsedec_buffer[dec_read_pos];
	}
	else {
		ch = 0;
	}
	return (ch);
}

/**
 * Read next [numberOfChars] characters from the Morse decoder ring buffer
 *
 * Output: Number of characters copied to *buf,
 *         string *buf with the copied characters
 *
 */
uint8_t readMorseChars(char *buf, uint8_t numberOfChars)
{uint8_t ch, i;
	i = 0;
	while (i < numberOfChars) {
		ch = readMorseChar();
		if (ch) {
			buf[i] = ch;
		}
		else {break;}
		i++;
	}
	buf[i] = '\0';
	return (i);
}

/**
 * Get the number of characters still in the Morse decoder ring buffer
 *
 * Output: Number of characters (0: Buffer is empty!)
 *
 */
uint8_t getMorseDecBufferLength(void)
{int16_t dec_posdiff;
	dec_posdiff = dec_write_pos - dec_read_pos;
	if (dec_posdiff < 0) {
		dec_posdiff += (MORSEDEC_BUFFER_MAXINDEX + 1);
	}
	return ((uint8_t) dec_posdiff);
}

/*****************************************************************************/
// Morse encoder functions:

/**
 * Init Morse Encoder
 *
 * Call this once before using the Morse encoder (sender) task!
 *
 */
void initMorseEncoder(void)
{
	MORSEENC_DDR |= MORSEENC_IN;			// Encoder output pin
	MORSEENC_PORT &= ~MORSEENC_IN;			// Output low
	morse_error = false;					// Reset Morse error flag
	morseenc_status = MORSE_BUFFER_OK;		// Encoder buffer status ok
	enc_write_pos = 255;					// Reset buffer write pointer
	enc_read_pos = 255;						// Reset buffer read pointer
	encspeed = SPEED;						// Set encoder speed
#ifdef IRCOMMENC
	TCCR2 &= ~(1 << COM20);				// OC2 disconnected
	IRCOMM_OFF();							// IRCOMM LEDs off
#endif
}

/**
 * Fetch next Morse table index from the Morse encoder ring buffer
 *
 * Output: Morse table index [0..MORSESIGNS_MAXINDEX(..127)]
 *         OR pause length [129..255] (pause 1..127 dits)
 *         OR 128 (0x80), if the ring buffer is empty
 *
 */
uint8_t fetchMsIndexFromEncBuffer(void)
{uint8_t msidx;
	if (enc_read_pos != enc_write_pos) {
		enc_read_pos++;
		if (enc_read_pos > MORSEENC_BUFFER_MAXINDEX) {
			enc_read_pos = 0;
		}
		msidx = morseenc_buffer[enc_read_pos];
	}
	else {
		msidx = 0x80;
	}
	return (msidx);
}

/**
 * Morse encoder task
 *
 */
void task_MorseEnc(void)
{static uint8_t busy_flag, signal_flag, pause_flag, sos_flag, pause_dits;
 static uint16_t last_timer, ms_code; uint8_t msidx;
	if (busy_flag) {						// Encoder busy!
		if (signal_flag) {					// Sending signal
			if (!pause_flag) {				// Waiting for signal end
				if ((timer - last_timer)
				 >= (encspeed * 10 * (ms_code & 3))) {
#ifdef LIGHTENC
					statusLEDs.LED2 = false;
					updateStatusLEDs();
#endif
#ifdef IRCOMMENC
					TCCR2 &= ~(1 << COM20);// OC2 disconnected
					IRCOMM_OFF();			// IRCOMM LEDs off
#endif
					MORSEENC_PORT &= ~MORSEENC_IN;
					last_timer = timer;
					pause_flag = true;
					ms_code >>= 2;
				}
			}
			else {							// Pause after a signal
				if (ms_code) {				// Dit/dah (signal) end:
					if ((timer - last_timer) >= (encspeed * 10)) {
						signal_flag = false;//  Pause 1 dit
					}
				}
				else {						// Morse sign end:
					if (sos_flag) {			//  Case SOS:
						ms_code = 0x0001;	//   Add last dit
						sos_flag = false;
					}
					else {					//  Case sign end:
						if ((timer - last_timer) >= (encspeed * 30)) {
							busy_flag = false;// Pause 3 dits
						}
					}
				}
			}
		}
		else {								// Signal end
			if (pause_dits) {				// Make a longer pause
				if ((timer - last_timer) >= (encspeed * 10 * pause_dits)) {
					busy_flag = false;		// Longer pause end
				}
			}
			else {							// Start new signal (dit/dah)
#ifdef LIGHTENC
				statusLEDs.LED2 = true;
				updateStatusLEDs();
#endif
#ifdef IRCOMMENC
				TCCR2 |= (1 << COM20);		// IRCOMM LEDs on (36kHz modulated)
#endif
				MORSEENC_PORT |= MORSEENC_IN; 
				last_timer = timer;
				pause_flag = false;
				signal_flag = true;
			}
		}
	}
	else {									// Encoder not busy!
		msidx = fetchMsIndexFromEncBuffer();// Get next index to send
		if (msidx == 0x80) {				//  from the ring buffer
			return;							// Buffer empty: Return
		}
		else {
			if (msidx < 0x80) {				// Morse sign to send
				ms_code = MsIndex2MorseCode(msidx);
				if (ms_code == 0x5FD5) {
					sos_flag = true;		// Sign is SOS
				}
				else {
					sos_flag = false;
				}
				pause_dits = 0;
			}
			else {							// (msidx > 0x80): Longer pause
				last_timer = timer;
				pause_dits = msidx - 0x80;
			}
			signal_flag = false;
			busy_flag = true;				// Sign / longer pause can be sent
		}
	}
}

/**
 * Store a Morse table index into the Morse encoder ring buffer
 *
 * Input: Morse table index [0..MORSESIGNS_MAXINDEX(..127)]
 *        OR pause length [129..255] (pause 1..127 dits)
 *
 */
void storeMsIndex2EncBuffer(uint8_t msindex)
{
	if (getMorseEncBufferLength() < MORSEENC_BUFFER_MAXINDEX) {
		enc_write_pos++;
		if (enc_write_pos > MORSEENC_BUFFER_MAXINDEX) {
			enc_write_pos = 0;
		}
		morseenc_buffer[enc_write_pos] = msindex;
		morseenc_status = MORSE_BUFFER_OK;	// Encoder buffer status ok
	}
	else {
		morseenc_status = MORSE_BUFFER_OVERFLOW; // Encoder buffer overflow
	}
}

/**
 * Write a pause length to send into the Morse encoder ring buffer
 *
 * Input: Pause length [1..127 dits] (0.14..18.14 spaces)
 *
 * With this function you can reach longer pauses.
 *   Examples:
 *   pauseMorse(7);  is identical with  writeMorseChar(' ');
 *   pauseMorse(14); is identical with  writeMorseString("  ");
 * The function pauseMorse(len) only writes one byte into the encoder ring
 * buffer for a longer pause, while writeMorseChar(' ') writes one byte for
 * each space to send. You should use writeMorseChar(' ') for single spaces
 * (between words) and pauseMorse(len) for longer pauses.
 *
 * ATTENTION: !-----------------------------------------------------------!
 *            ! The max. pause length you can reach with this function is !
 *            ! about 6 seconds! So the max. input value of this function !
 *            ! depends on encspeed!!!                                    !
 *            !-----------------------------------------------------------!
 *            !   ==>  Max. pause length [dits] = 6000 / encspeed  <==    !
 *            !-----------------------------------------------------------!
 *            For encspeeds from 8 (SPEED_MAX) to 47 the max. pause length
 *            is 127 dits. For encspeeds from 48 to 400 (SPEED_MIN) you
 *            calculate the max. number of dits with the above formula.
 *            At SPEED_MIN you may only pause for 15 (6000 / 400) dits!
 *
 */
void pauseMorse(uint8_t len)
{
	if (len) {
		storeMsIndex2EncBuffer(len | 0x80);
	}
}

/**
 * Write a character to send into the Morse encoder ring buffer
 *
 * Input: ASCII code [0..255]
 *
 */
void writeMorseChar(uint8_t ch)
{static uint8_t sign_flag, chidx; uint8_t msidx;
 static char last_3ch[4];
	switch (ch) {
		case 32 :							// Space   [ASCII code 32]
			if (sign_flag) {				// Space directly after a sign
				pauseMorse(4);				//  (length 4 dits)
				if (morseenc_status == MORSE_BUFFER_OK) {
					sign_flag = false;
				}
			}
			else {							// Pause for all other spaces
				pauseMorse(7);				//  (length 7 dits)
			}
			break;
		default :
			// Chars used for prosign/special sign names:
			//  ` a..z # % * ^ ~[BLD 126] \[LCD 164]
			if (((ch >= '`') && (ch <= 'z')) || (ch == 35) || (ch == 37)
			 || (ch == 42) || (ch == 94) || (ch == 126) || (ch == 164)) {
				last_3ch[chidx] = ch; last_3ch[chidx + 1] = '\0';
				msidx = MsName2MsIndex(last_3ch);// Name in Morse table?
				if (morse_error) {
					chidx++;
					if (chidx > 2) {chidx = 0;}
					return;
				}
			}
			else {							// Normal chars
				msidx = pgm_read_byte(&a_ms_ft[ch]);
			}
			storeMsIndex2EncBuffer(msidx);
			if (morseenc_status == MORSE_BUFFER_OK) {
				sign_flag = true;
			}
	}
	chidx = 0;
}

/**
 * Write a string to send into the Morse encoder ring buffer
 *
 * Input: String with ASCII text
 *
 */
void writeMorseString(char *str)
{
	while (*str) {
		writeMorseChar(*str++);
	}
}

/**
 * Get the number of indices still in the Morse encoder ring buffer
 *
 * Output: Number of indices (0: Buffer is empty!)
 *
 */
uint8_t getMorseEncBufferLength(void)
{int16_t enc_posdiff;
	enc_posdiff = enc_write_pos - enc_read_pos;
	if (enc_posdiff < 0) {
		enc_posdiff += (MORSEENC_BUFFER_MAXINDEX + 1);
	}
	return ((uint8_t) enc_posdiff);
}

/*****************************************************************************/
// Useful UART functions:

#ifndef DEBUG
/**
 * Send received Morse signs to the serial interface as ASCII text
 *
 */
void writeMorse(void)
{static uint8_t pos; uint8_t ch;
#ifdef LIMITED_PAUSE
 static uint8_t space_cnt;
#endif
	ch = readMorseChar();
	if (ch) {
		writeChar(ch);
#ifdef LIMITED_PAUSE
		if (ch == ' ') {space_cnt++;}
		else {space_cnt = 0;}
		if (space_cnt >= SPACE_CNT_LIMIT) {
			space_cnt = 0;
			pos = 0;
			writeString_P("|\n");
			return;
		}
#endif
		pos++;
		if (pos >= LINE_LENGTH) {
			pos = 0;
			writeChar('\n');
		}
	}
}

#else

/**
 * Send decoder debug information to the serial interface
 *
 * Format: .0000 -0000 S000 D000  A:[X] B000
 *
 *   .    -> Dit length [0.1ms]
 *   -    -> Dah length [0.1ms]
 *   S    -> Decoder speed (should be (dit length / 10)!) [ms]
 *   D    -> Deviation (decoder speed - (dit length / 10)) [ms]
 *   A    -> The last received ASCII char
 *   B    -> Decoder buffer length (chars still in the buffer)
 *
 */
void writeDebugInfo(void)
{uint8_t ch;
	ch = readMorseChar();
	if (ch) {
		writeString_P(".");
		writeIntegerLength(ditlength, DEC, 4);
		writeString_P(" -");
		writeIntegerLength(dahlength, DEC, 4);
		writeString_P(" S");
		writeIntegerLength(decspeed, DEC, 3);
		writeString_P(" D");
		writeIntegerLength((decspeed - (ditlength / 10)), DEC, 3);
		writeString_P("  A:[");
		writeChar(ch);
		writeString_P("] B");
		writeIntegerLength(getMorseDecBufferLength(), DEC, 3);
		writeChar('\n');
	}
}
#endif

/******************************************************************************
 * Additional info
 * ****************************************************************************
 * Changelog:
 * - v. 3.6w 2012 by Dirk
 *
 * ****************************************************************************
 */

/*****************************************************************************/
// EOF

RP6 CONTROL M32

Die RP6Control Morse Library gehört in den Ordner \RP6Lib\RP6control.

Header

Datei RP6ControlMorseLib.h:

/* ****************************************************************************
 *                           _______________________
 *                           \| RP6  ROBOT SYSTEM |/
 *                            \_-_-_-_-_-_-_-_-_-_/             >>> RP6 CONTROL
 * ----------------------------------------------------------------------------
 * ------------------------ [c]2012 - Dirk ------------------------------------
 * ****************************************************************************
 * File: RP6ControlMorseLib.h
 * Version: 3.6w
 * Target: RP6 CONTROL - ATMEGA32 @16.00MHz
 * Author(s): Dirk
 * ****************************************************************************
 * Description:
 * This is the RP6ControlMorse library header file.
 * You have to include this file, if you want to use the library
 * RP6ControlMorseLib.c in your own projects.
 *
 * ****************************************************************************
 * THE CHANGELOG CAN BE FOUND AT THE END OF THIS FILE!
 * ****************************************************************************
 */

#ifndef RP6CONTROLMORSE_H
#define RP6CONTROLMORSE_H

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

#include "RP6ControlLib.h" 		// The RP6 Control Library. 
								// Always needs to be included!

/*****************************************************************************/
// Defines:

#define SPEED						100		// = 12 WpM = 60 CpM
// Calculate SPEED: SPEED = 1200 / WpM
//                  SPEED = 6000 / CpM
#define SPEED_MIN					400		// = 3 WpM = 15 CpM
#define SPEED_MAX					8		// = 150 WpM = 750 CpM
#define SPEED_VAR					5		// Decoder speed variation

#define LIMITED_PAUSE						// Decoder: Spaces limited
#define SPACE_CNT_LIMIT				3		// Max. number of spaces

//#define INVERTDEC							// Invert decoder input level

//#define DEBUG								// Decoder debug mode

//#define ANSI								// Use ANSI char set
//#define RP6LOADER							// Use RP6Loader terminal char set
#define LCD									// Use LCD (190911) char set
//#define BLD									// Use BLD (191621) char set
// IMPORTANT: You may activate only ONE of the four above definitions!

//#define LIGHTDEC							// LED1 shows decoder Morse sign
//#define LIGHTENC							// LED2 shows encoder Morse sign

//#define SOUND								// Make Morse sign audible
#define Tone_D1						149		// 294Hz
#define Tone_Dis1					155		// 311Hz
#define Tone_E1						160		// 330Hz
#define Tone_F1						166		// 349Hz
#define Tone_Fis1					171		// 370Hz
#define Tone_G1						175		// 392Hz
#define Tone_Gis1					180		// 415Hz
#define Tone_A1						184		// 440Hz
#define Tone_Ais1					188		// 466Hz
#define Tone_H1						192		// 494Hz
#define Tone_C2						195		// 523Hz
#define Tone_Cis2					199		// 554Hz
#define Tone_D2						202		// 587Hz
#define Tone_Dis2					205		// 622Hz
#define Tone_E2						208		// 659Hz
#define Tone_F2						210		// 698Hz
#define Tone_Fis2					213		// 740Hz
#define Tone_G2						215		// 784Hz
#define Tone_Gis2					217		// 831Hz
#define Tone_A2						219		// 880Hz
#define Tone_Ais2					221		// 932Hz
#define Tone_H2						223		// 988Hz
#define Tone_Off					0

#define MS_SIGNALS_MAXINDEX			7
#define MS_SPECIALS_MAXINDEX		25
#define MORSESIGNS_MAXINDEX			79

// Flash constants (Morse tables):
const uint16_t ms_ft[MORSESIGNS_MAXINDEX + 1];
const uint8_t ms_a0uc_ft[MORSESIGNS_MAXINDEX + 1];
const uint8_t ms_a1uc_ft[MORSESIGNS_MAXINDEX + 1];
const uint8_t ms_a2uc_ft[MORSESIGNS_MAXINDEX + 1];
const uint8_t a_ms_ft[256];

#define MORSEDEC_BUFFER_MAXINDEX	31		// Morse decoder buffer length
#define MORSEENC_BUFFER_MAXINDEX	31		// Morse encoder buffer length

// Morse decoder/encoder status:
#define MORSE_BUFFER_OK				0
#define MORSE_BUFFER_OVERFLOW		1		// Morse buffer overflow

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

extern uint8_t morsedec_status;
extern uint8_t morseenc_status;
extern uint8_t morse_error;
#ifdef SOUND
uint8_t tonepitch;
#endif

char morsedec_buffer[MORSEDEC_BUFFER_MAXINDEX + 2];
uint8_t dec_write_pos, dec_read_pos;
char morseenc_buffer[MORSEENC_BUFFER_MAXINDEX + 2];
uint8_t enc_write_pos, enc_read_pos;

uint16_t decspeed;
uint8_t speedvar;

uint16_t encspeed;

#ifdef DEBUG
uint16_t ditlength, dahlength;
#endif

/*****************************************************************************/
// Functions:

uint8_t Lower2UpperCase(uint8_t);
uint8_t Upper2LowerCase(uint8_t);

uint16_t MsIndex2MorseCode(uint8_t);
uint8_t MorseCode2MsIndex(uint16_t);
void MorseCode2MsName(char *, uint16_t);
uint8_t MsName2MsIndex(char *);

void MorseCode2MorseSign(char *, uint16_t);
uint16_t MorseSign2MorseCode(char *);

void clearMorseDecBuffer(void);
void initMorseDecoder(void);
void storeMsChar2DecBuffer(uint8_t);
void task_MorseDec(void);
uint8_t readMorseChar(void);
uint8_t readMorseChars(char *, uint8_t);
uint8_t getMorseDecBufferLength(void);

void initMorseEncoder(void);
uint8_t fetchMsIndexFromEncBuffer(void);
void task_MorseEnc(void);
void storeMsIndex2EncBuffer(uint8_t);
void pauseMorse(uint8_t);
void writeMorseChar(uint8_t);
void writeMorseString(char *);
uint8_t getMorseEncBufferLength(void);

#ifndef DEBUG
void writeMorseLCD(void);
#else
void showDebugInfoLCD(void);
#endif


#endif

/******************************************************************************
 * Additional info
 * ****************************************************************************
 * Changelog:
 * 
 *  ---> changes are documented in the file "RP6ControlMorseLib.c"
 *
 * ****************************************************************************
 */

/*****************************************************************************/
// EOF

Library

Datei RP6ControlMorseLib.c:

/* ****************************************************************************
 *                           _______________________
 *                           \| RP6  ROBOT SYSTEM |/
 *                            \_-_-_-_-_-_-_-_-_-_/             >>> RP6 CONTROL
 * ----------------------------------------------------------------------------
 * ------------------------ [c]2012 - Dirk ------------------------------------
 * ****************************************************************************
 * File: RP6ControlMorseLib.c
 * Version: 3.6w
 * Target: RP6 CONTROL - ATMEGA32 @16.00MHz
 *         with optional LC-Display 16x2 chars (CONRAD 190911-62)
 *         [or Backlight Display 16x2 chars (CONRAD 191621)]
 * Author(s): Dirk
 * ****************************************************************************
 * Description:
 *
 * The RP6 Control Morse Library.
 *
 * ****************************************************************************
 * ATTENTION: The 100us timer is used for the Morse decoder and encoder
 *            task! Please do not alter the variable "timer" elsewhere in
 *            your program!
 *
 * ****************************************************************************
 * THE CHANGELOG CAN BE FOUND AT THE END OF THIS FILE!
 * ****************************************************************************
 */
 
/*****************************************************************************/
// Includes:

#include "RP6ControlMorseLib.h"

/*****************************************************************************/
// Defines:

// RP6 Control Morse Decoder Connection (input):
//#define MORSEDEC_PORT	PORTC
//#define MORSEDEC_DDR	DDRC
//#define MORSEDEC_PIN	PINC
//#define MORSEDEC_IN		SCL					// PINC0  XBUS Pin 10
//#define MORSEDEC_IN		SDA					// PINC1  XBUS Pin 12

#define MORSEDEC_PORT	PORTD
#define MORSEDEC_DDR	DDRD
#define MORSEDEC_PIN	PIND
#define MORSEDEC_IN		EINT1				// PIND2  XBUS Pin 8

// RP6 Control Morse Encoder Connection (output):
#define MORSEENC_PORT	PORTC
#define MORSEENC_DDR	DDRC
#define MORSEENC_PIN	PINC
//#define MORSEENC_IN		SCL					// PINC0  XBUS Pin 10
#define MORSEENC_IN		SDA					// PINC1  XBUS Pin 12

//#define MORSEENC_PORT	PORTD
//#define MORSEENC_DDR	DDRD
//#define MORSEENC_PIN	PIND
//#define MORSEENC_IN		EINT1				// PIND2  XBUS Pin 8

// ----------------------------------------------------------------------------
// MORSE TABLES:

// Morse Table [0..79]:
// Morse decoders and encoders use this table for receiving or sending Morse
// code. This table consists of 16-bit constants. Each table index [0..79]
// (or each word constant) represents one Morse sign.
// The dots (dit) and the dashes (dah) are stored as two bits: The bits "01"
// stand for a dit and "11" for a dah, read from right to left in the binary
// notation. Between dits and dahs of a Morse sign you have to send a pause
// with the length of one dit. Between Morse signs there is a pause with the
// length of three dits (or one dah).
//
// Example:                     End <<<<7<<6<<5<<4<<3<<2<<1<<<< Start
//                                  ---DahDitDitDahDitDitDit
// 0x35D5 = 0b0011010111010101 -> 0b 00 11 01 01 11 01 01 01 -> $ (Dollar)
const uint16_t ms_ft[] PROGMEM =
// Signals (prosigns):
// Hex		  Binary		   Sign	   Index  Prosign
{0x5555, // 0b0101010101010101			 0		HH
 0x0DD5, // 0b0000110111010101					SK
 0x0377, // 0b0000001101110111					CT
 0x3757, // 0b0011011101010111					BK
 0x5D77, // 0b0101110101110111					CL
 0xDF77, // 0b1101111101110111			 5		CQ
 0x0FD7, // 0b0000111111010111					DO
 0x5FD5, // 0b0101111111010101			 7		SOS
//------------------------------------------------------
// Special characters:
// Hex		  Binary		   Sign	   Index  Prosign
 0x01DF, // 0b0000000111011111  ^G		 8
 0x00FF, // 0b0000000011111111  CH,^H
 0x01FD, // 0b0000000111111101  ^J		10
 0x15D5, // 0b0001010111010101  /S
 0x01D5, // 0b0000000111010101  ^S				VE
 0x075F, // 0b0000011101011111  /Z
 0x035F, // 0b0000001101011111  .Z
 0x037D, // 0b0000001101111101  /A,°A	15
 0x00DD, // 0b0000000011011101  Ä				AA
 0x0177, // 0b0000000101110111  C~
 0x035D, // 0b0000001101011101  \E
 0x0175, // 0b0000000101110101  /E
 0x01F5, // 0b0000000111110101  Eth		20
 0x03DF, // 0b0000001111011111  ~N
 0x007F, // 0b0000000001111111  Ö
 0x00F5, // 0b0000000011110101  Ü
 0x017D, // 0b0000000101111101  Thorn
 0x17D5, // 0b0001011111010101  ß		25
//------------------------------------------------------
// Normal characters:
// Hex		  Binary		   Sign	   Index  Prosign
 0x0F77, // 0b0000111101110111  !		26
 0x075D, // 0b0000011101011101  "
 0x35D5, // 0b0011010111010101  $
 0x015D, // 0b0000000101011101  &				AS
 0x07FD, // 0b0000011111111101  '		30
 0x01F7, // 0b0000000111110111  (				KN
 0x0DF7, // 0b0000110111110111  )
 0x01DD, // 0b0000000111011101  +				AR
 0x0F5F, // 0b0000111101011111  ,
 0x0D57, // 0b0000110101010111  -		35
 0x0DDD, // 0b0000110111011101  .
 0x01D7, // 0b0000000111010111  /				NR
 0x03FF, // 0b0000001111111111  0
 0x03FD, // 0b0000001111111101  1
 0x03F5, // 0b0000001111110101  2		40
 0x03D5, // 0b0000001111010101  3
 0x0355, // 0b0000001101010101  4
 0x0155, // 0b0000000101010101  5
 0x0157, // 0b0000000101010111  6
 0x015F, // 0b0000000101011111  7		45
 0x017F, // 0b0000000101111111  8
 0x01FF, // 0b0000000111111111  9
 0x057F, // 0b0000010101111111  :
 0x0777, // 0b0000011101110111  ;
 0x0357, // 0b0000001101010111  =		50		BT
 0x05F5, // 0b0000010111110101  ?				IMI
 0x077D, // 0b0000011101111101  @
 0x000D, // 0b0000000000001101  A
 0x0057, // 0b0000000001010111  B				DE
 0x0077, // 0b0000000001110111  C		55
 0x0017, // 0b0000000000010111  D
 0x0001, // 0b0000000000000001  E
 0x0075, // 0b0000000001110101  F
 0x001F, // 0b0000000000011111  G
 0x0055, // 0b0000000001010101  H		60
 0x0005, // 0b0000000000000101  I
 0x00FD, // 0b0000000011111101  J
 0x0037, // 0b0000000000110111  K				K
 0x005D, // 0b0000000001011101  L
 0x000F, // 0b0000000000001111  M		65
 0x0007, // 0b0000000000000111  N
 0x003F, // 0b0000000000111111  O
 0x007D, // 0b0000000001111101  P
 0x00DF, // 0b0000000011011111  Q
 0x001D, // 0b0000000000011101  R		70		R
 0x0015, // 0b0000000000010101  S
 0x0003, // 0b0000000000000011  T
 0x0035, // 0b0000000000110101  U
 0x00D5, // 0b0000000011010101  V
 0x003D, // 0b0000000000111101  W		75
 0x00D7, // 0b0000000011010111  X
 0x00F7, // 0b0000000011110111  Y
 0x005F, // 0b0000000001011111  Z
 0x0DF5};// 0b0000110111110101  _		79
// Remarks: - SOS (Morse sign ...---...) can not be stored in a 16-bit
//            constant because SOS is the only Morse sign with 9 dits/dahs.
//            So SOS is stored as the (not existing) Morse sign ...---..
//            (SOI) and must be treated special in decoders/encoders.  


// Morse-ASCII-Table [0..79]:
// Morse decoders use this table for receiving Morse code.
const uint8_t ms_a0uc_ft[] PROGMEM = 
//H   S   C   B    C   C   D   S
{104,115, 99, 98, 99, 99,100,115,
//0                    5
#ifdef ANSI
//                            ANSI [index 15..25]:
//^   C   ^   %    ^   %   *   /A  Ä   C~  \E  /E  Et  ~N   Ö   Ü  To   ß
  94, 99, 94, 37, 94, 37, 42,193,196,199,200,201,208,209,214,220,222,223,
//        10                   15                  20                   25
#endif
#ifdef RP6LOADER
//                            RPLoader terminal [index 15..25]:
//^   C   ^   %    ^   %   *   /A  Ä   C~  \E  /E  Et  ~N   Ö   Ü  To   ß
  94, 99, 94, 37, 94, 37, 42,194,197,200,201,202,209,210,215,221,223,224,
//        10                   15                  20                   25
#endif
#ifdef LCD
//                            LCD [index 15..25]:
//^   C   ^   %    ^   %   *   %   Ä   C   \   %   E   -N   Ö   Ü   T   ß
  94, 99, 94, 37, 94, 37, 42, 37,225, 99, 96, 37,101,238,239,245,116,226,
//        10                   15                  20                   25
#endif
#ifdef BLD
//                            BLD [index 15..25]:
//^   C   ^   %    ^   %   *   /A  A   C   \   %   E    ~   O   U   T   ß
  94, 99, 94, 37, 94, 37, 42,160, 97, 99, 96, 37,101,126,111,117,116,224,
//        10                   15                  20                   25
#endif
//!  "  $  &  '  (  )   +  ,  -  .  /  0  1  2   3  4  5  6  7  8  9  :  ;
 33,34,36,38,39,40,41,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,
//            30             35              40             45
//=  ?  @  A  B  C   D   E    F   G   H   I   J   K   L   M   N   O    P   Q
 61,63,64,65,66,67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81,
//50            55                   60                   65
// R  S   T   U   V   W   X   Y    Z   _  
  82, 83, 84, 85, 86, 87, 88, 89, 90,95};		// Et = Eth,  To = Thorn
//70                  75              79

const uint8_t ms_a1uc_ft[] PROGMEM = 
//H   K   T   K    L   Q   O   O
{104,107,116,107,108,113,111,111,
//0                    5
#ifdef ANSI
//                            ANSI [index 15..25]:
//G   H   J   S    S   Z   Z
 103,104,106,115,115,122,122, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32,
//        10                   15                  20                   25
#endif
#ifdef RP6LOADER
//                            RPLoader terminal [index 15..25]:
//G   H   J   S    S   Z   Z
 103,104,106,115,115,122,122, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32,
//        10                   15                  20                   25
#endif
#ifdef LCD
//                            LCD [index 15..25]:
//G   H   J   S    S   Z   Z   A       \   E   E   T                O
 103,104,106,115,115,122,122, 97, 32,164,101,101,116, 32, 32, 32,111, 32,
//        10                   15                  20                   25
#endif
#ifdef BLD
//                            BLD [index 15..25]:
//G   H   J   S    S   Z   Z       E   ~   E   E   T    N   E   E   O
 103,104,106,115,115,122,122, 32,101,126,101,101,116,110,101,101,111, 32,
//        10                   15                  20                   25
#endif
 32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,
//            30             35              40             45
 32,32,32,32,32,32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32,
//50            55                   60                   65
  32, 32, 32, 32, 32, 32, 32, 32, 32,32};		// Et = Eth,  To = Thorn
//70                  75              79

const uint8_t ms_a2uc_ft[] PROGMEM = 
//                             S
{ 32, 32, 32, 32, 32, 32, 32,115,
// 0                   5
  32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32,
//        10                   15                  20                   25
 32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,
//            30             35              40             45
 32,32,32,32,32,32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32,
//50            55                   60                   65
  32, 32, 32, 32, 32, 32, 32, 32, 32,32};		// Et = Eth,  To = Thorn
//70                  75              79
// Prosigns and special characters are stored as lower case letters (hh,
// sk, ^g, ch ...) in this table.
// Remarks: - The special chars  ^G, ^J, /S, ^S, /Z, .Z [indices 8, 10..14]
//            are represented as ^g, ^j, %s, ^s, %z, *z in this table.
//          - The special chars [indices 15..25] are represented in several
//            ways in this table depending on the output target (ANSI,
//            RP6LOADER, LCD, BLD).
//          - If Morse decoders receive a pause with the length of 7 dits,
//            they have to give out the ASCII code ' ' (space [32]).


// ASCII-Morse-Table [0..255]:
// Morse encoders use this table to send Morse code.
const uint8_t a_ms_ft[] PROGMEM =
{51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,
//0              5              10              15             20
 51,51,51,51,51,51,51,51,
//24                30
//_  !  "  ?  $  ?  &  '  (  )   X  +  ,  -  .  /  0  1   2  3  4  5  6  7
 79,26,27,51,28,51,29,30,31,32,76,33,34,35,36,37,38,39,40,41,42,43,44,45,
//32       35             40              45             50              55
//8  9  :  ;  ?  =  ?  ?   @  A  B  C  D  E  F  G  H   I  J  K  L  M  N  O
 46,47,48,49,51,50,51,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,
//56          60             65              70              75
//P  Q  R  S  T  U  V  W  X   Y  Z  [  ?  ]  ?  _   ?  A  B  C  D  E  F  G
 68,69,70,71,72,73,74,75,76,77,78,31,51,32,51,79,51,53,54,55,56,57,58,59,
//80             85             90              95             100
//H  I  J  K  L  M  N  O   P  Q  R  S  T  U  V  W   X  Y  Z  {  ?  }  ?  ?
 60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,31,51,32,51,51,
//104              110             115            120             125
//?  ?  ?  ?  ?  ?  ?  ?   ?  ?  ?  ?  ?  ?  ?  ?  ?   ?  ?  ?  ?  ?  ?  ?
 51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,
//128  130            135             140            145             150
//?  ?  ?  ?  ?  ?  ?  ?   _  ?  ?  ?  ?  ?  ?  ?  ?   ?  ?  ?  ?  ?  ?  ?
 51,51,51,51,51,51,51,51,79,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,
//152     155            160             165             170            175
//?  ?  ?  ?  ?  ?  ?  ?  ?   ?  ?  ?  ?  ?  ?  ?  ?  /A  ?  ?  Ä  ?  ?  C~
 51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,15,51,51,16,51,51,17,
//176        180             185            190             195
//\E/E  ?  ?  ?  ?  ?  ?  Et ~N  ?  ?  ?  ?  Ö  X   ?  ?  ?  ?  Ü  ?  To ß
 18,19,51,51,51,51,51,51,20,21,51,51,51,51,22,76,51,51,51,51,23,51,24,25,
//200           205             210            215             220
//? /A  ?  ?  Ä  ?  ?  C~ \E /E  ?  ?  ?  ?  ?  ?  Et ~N  ?  ?  ?  ?  Ö  /
 51,15,51,51,16,51,51,17,18,19,51,51,51,51,51,51,20,21,51,51,51,51,22,37,
//224              230             235            240             245
//?  ?  ?  ?  Ü  ?  To ?
 51,51,51,51,23,51,24,51};					// Et = Eth,  To = Thorn
//248                 255
// Remarks: - ASCII codes 91 '[' and 123 '{' are converted to Morse
//            code '(' [31].
//          - ASCII codes 93 ']' and 125 '}' are converted to Morse
//            code ')' [32].
//          - ASCII code 215 (multiplication sign) is converted to
//            Morse code 'X' [76].
//          - ASCII code 247 (division sign) is converted to Morse
//            code '/' [37].
//          - ASCII codes 32 (sp) and 160 (nbsp) are represented as
//            '_' [79] in this table but must be treated special in
//            encoders: The Morse encoder has to send a pause with
//            the length of 7 dits for a space.
//          - All non printable ASCII codes [0..31] and other codes
//            not defined in the Morse code are converted to Morse
//            code '?' [51].

// MORSE TABLES (END)
// ----------------------------------------------------------------------------

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

uint8_t morsedec_status;
uint8_t morseenc_status;
uint8_t morse_error;

/*****************************************************************************/
// Functions:

/**
 * Convert lower case to upper case letters
 *
 * Input:  ASCII code [0..255]
 * Output: ASCII code, only with upper case letters
 *
 */
uint8_t Lower2UpperCase(uint8_t ch)
{uint8_t chuc;
	chuc = ch;
	if ((ch >= 97) && (ch <= 122)) {
		chuc -= 32;
	}
	if ((ch >= 224) && (ch <= 254) && (ch != 247)) {
		chuc -= 32;
	}
	return (chuc);
}

/**
 * Convert upper case to lower case letters
 *
 * Input:  ASCII code [0..255]
 * Output: ASCII code, only with lower case letters
 *
 */
uint8_t Upper2LowerCase(uint8_t ch)
{uint8_t chlc;
	chlc = ch;
	if ((ch >= 65) && (ch <= 90)) {
		chlc += 32;
	}
	if ((ch >= 192) && (ch <= 222) && (ch != 215)) {
		chlc += 32;
	}
	return (chlc);
}

/**
 * Output the Morse code of a Morse table index
 *
 * Input:  Morse table index [0..MORSESIGNS_MAXINDEX]
 * Output: Morse code (See table ms_ft[] above!)
 *
 */
uint16_t MsIndex2MorseCode(uint8_t msindex)
{
	morse_error = false;
	return (pgm_read_word(&ms_ft[msindex]));
}

/**
 * Output the table index of a Morse code
 *
 * Input:  Morse code (See table ms_ft[] above!)
 * Output: Morse table index [0..MORSESIGNS_MAXINDEX]
 *
 */
uint8_t MorseCode2MsIndex(uint16_t morsecode)
{uint8_t msidx;
	for (msidx = 0; msidx <= MORSESIGNS_MAXINDEX; msidx++) {
		if (morsecode == pgm_read_word(&ms_ft[msidx])) {break;}
	}
	if (msidx <= MORSESIGNS_MAXINDEX) {
		morse_error = false;
		return (msidx);					// Morse table index
	}
	else {
		morse_error = true;				// Unknown Morse code:
		return (51);					//  Return table index of '?'
	}
}

/**
 * Output the Morse sign name of a Morse code
 *
 * Input:  Morse code (See table ms_ft[] above!)
 * Output: String with Morse sign name (1..3 ASCII letters)
 *
 */
void MorseCode2MsName(char *msname, uint16_t morsecode)
{uint8_t msidx;
	msidx = MorseCode2MsIndex(morsecode);
	msname[0] = pgm_read_byte(&ms_a0uc_ft[msidx]);
	msname[1] = pgm_read_byte(&ms_a1uc_ft[msidx]);
	if (msname[1] == 32) {msname[1] = '\0';}
	msname[2] = pgm_read_byte(&ms_a2uc_ft[msidx]);
	if (msname[2] == 32) {
		msname[2] = '\0';
	}
	else {
		msname[3] = '\0';
	}
}

/**
 * Output the Morse table index of a Morse sign name
 *
 * Input:  String with Morse sign name (1..3 ASCII letters)
 * Output: Morse table index [0..MORSESIGNS_MAXINDEX]
 *
 */
uint8_t MsName2MsIndex(char *msname)
{uint8_t msidx;
	for (msidx = 0; msidx <= MORSESIGNS_MAXINDEX; msidx++) {
		if (msname[0] == pgm_read_byte(&ms_a0uc_ft[msidx])) {
			if ((pgm_read_byte(&ms_a1uc_ft[msidx]) == 32)
			 || (msname[1] == pgm_read_byte(&ms_a1uc_ft[msidx]))) {
				if ((pgm_read_byte(&ms_a2uc_ft[msidx]) == 32)
				 || (msname[2] == pgm_read_byte(&ms_a2uc_ft[msidx]))) {
					break;
				}
			}
		}
	}
	if (msidx <= MORSESIGNS_MAXINDEX) {
		morse_error = false;
		return (msidx);					// Morse table index
	}
	else {
		morse_error = true;				// Unknown Morse sign name:
		return (51);					//  Return table index of '?'
	}
}

/**
 * Output the Morse sign of a Morse code
 *
 * Input:  Morse code (See table ms_ft[] above!)
 * Output: String with the Morse sign (1..9 dits [.] or dahs [-])
 *
 * Example: $  -> 0b0011010111010101  -> Morse sign ...-..-
 *
 */
void MorseCode2MorseSign(char *morsesign, uint16_t morsecode)
{uint8_t i; uint16_t ms_code;
	ms_code = morsecode;
	i = 0;
	do {
		switch (ms_code & 3) {
			case 1 :					// dit!
				morsesign[i] = '.';
				i++; break;
			case 3 :					// dah!
				morsesign[i] = '-';
				i++;
		}
		ms_code >>= 2;
	} while (ms_code);
	if (morsecode == 0x5FD5) {			// SOS: Add last dit!
		morsesign[i] = '.';
		i++;
	}
	morsesign[i] = '\0';
	morse_error = false;
}

/**
 * Output the Morse code of a Morse sign
 *
 * Input:  String with the Morse sign (1..9 dits [.] or dahs [-])
 * Output: Morse code (See table ms_ft[] above!)
 *
 * Example: $  -> Morse sign ...-..-  -> 0b0011010111010101
 *
 */
uint16_t MorseSign2MorseCode(char *morsesign)
{uint8_t i, ch; uint16_t ms_code;
	ms_code = 0;
	ch = 1;
	for (i = 0; i <= 7; i++) {
		ms_code >>= 2;
		if (ch) {
			ch = morsesign[i];
			switch (ch) {
				case '.' :					// dit!
					ms_code |= 0x4000; break;
				case '-' :					// dah!
					ms_code |= 0xC000;
			}
		}
		
	}
	if ((ms_code == 0x5FD5) && (morsesign[8] != '.')) {
		ms_code = 0x05F5;	// SOS: If last dit doesn't exist, return '?'!
		morse_error = true;
	}
	else {
		morse_error = false;
	}
	return (ms_code);
}

/*****************************************************************************/
// Morse decoder functions:

/**
 * Clear the Morse decoder ring buffer
 *
 */
void clearMorseDecBuffer(void)
{
	morsedec_status = MORSE_BUFFER_OK;		// Decoder buffer status ok
	dec_write_pos = 255;					// Reset buffer write position
	dec_read_pos = 255;						// Reset buffer read position
}

/**
 * Init Morse Decoder
 *
 * Call this once before using the Morse decoder (receiver) task!
 *
 */
void initMorseDecoder(void)
{
	MORSEDEC_DDR &= ~MORSEDEC_IN;			// Decoder input pin
	MORSEDEC_PORT |= MORSEDEC_IN;			// MORSEDEC_IN -> Pullup
	morse_error = false;					// Reset Morse error flag
	clearMorseDecBuffer();					// Clear the decoder buffer
	decspeed = SPEED;						// Decoder speed
	speedvar = SPEED_VAR;					// Decoder speed variation
#ifdef SOUND
	tonepitch = Tone_C2;					// Set tone pitch
#endif
}

/**
 * Store a decoded (prosign) Morse sign char into the decoder ring buffer
 *
 * Input: ASCII char (part of a string with the (pro)sign name)
 *
 */
void storeMsChar2DecBuffer(uint8_t ch)
{
	if (getMorseDecBufferLength() < MORSEDEC_BUFFER_MAXINDEX) {
		dec_write_pos++;
		if (dec_write_pos > MORSEDEC_BUFFER_MAXINDEX) {
			dec_write_pos = 0;
		}
		morsedec_buffer[dec_write_pos] = ch;
		morsedec_status = MORSE_BUFFER_OK;	// Decoder buffer status ok
	}
	else {
		morsedec_status = MORSE_BUFFER_OVERFLOW;// Decoder buffer overflow
	}
}

/**
 * Morse decoder task
 *
 */
void task_MorseDec(void)
{uint16_t time_100usecs;
 static char ms_sign[10]; uint8_t temp;
 static uint16_t last_timer, signal, pause;
 static uint8_t ditdah, ditdah_cnt;
 char ms_name[4]; 
#ifdef SOUND
 static uint8_t tone_off;
#endif
#ifdef LIMITED_PAUSE
 static uint8_t space_cnt;
#endif 
	time_100usecs = timer - last_timer;
	last_timer += time_100usecs;
	temp = MORSEDEC_PIN & MORSEDEC_IN;		// Read Morse level
#ifdef INVERTDEC
	temp = (!temp);							// Invert input level
#endif
	if (temp) {								// Signal on
#ifdef SOUND
		if (tone_off) {
			setBeeperPitch(tonepitch);
			tone_off = false;
		}
#endif
#ifdef LIGHTDEC
		externalPort.LED1 = true;
		outputExt();
#endif
		signal += time_100usecs;
		if (pause > (decspeed * 20)) {		// Pause > 2 dits:
			if (ditdah) {					//  Morse sign end (length 3 dits)
				ms_sign[ditdah_cnt] = ditdah;
				ditdah_cnt++;
				ms_sign[ditdah_cnt] = '\0';
				ditdah_cnt = 0;
				ditdah = 0;
				MorseCode2MsName(ms_name, MorseSign2MorseCode(ms_sign));
				temp = 0;
				while (ms_name[temp]) {
					storeMsChar2DecBuffer(ms_name[temp++]);
				}
			}
			pause = 0;
		}
		if (pause) {						// Short pause: 
			if (ditdah) {					//  Dit or dah end (length 1 dit)
				ms_sign[ditdah_cnt] = ditdah;
				ditdah_cnt++;
				ms_sign[ditdah_cnt] = '\0';
				if (ditdah_cnt > 8) {ditdah_cnt = 0;}
				ditdah = 0;
			}
			pause = 0;
		}
	}
	else {									// Signal off (pause)
#ifdef SOUND
		setBeeperPitch(Tone_Off);
		tone_off = true;
#endif
#ifdef LIGHTDEC
		externalPort.LED1 = false;
		outputExt();
#endif
		pause += time_100usecs;
		if (pause > (decspeed * 50)) {		// Pause > 5 dits:
			if (ditdah) {					//  Space or longer pause
				ms_sign[ditdah_cnt] = ditdah;
				ditdah_cnt++;
				ms_sign[ditdah_cnt] = '\0';
				ditdah_cnt = 0;
				ditdah = 0;
				MorseCode2MsName(ms_name, MorseSign2MorseCode(ms_sign));
				temp = 0;
				while (ms_name[temp]) {
					storeMsChar2DecBuffer(ms_name[temp++]);
				}
#ifdef LIMITED_PAUSE
				space_cnt = SPACE_CNT_LIMIT;
				space_cnt--;
#endif
				storeMsChar2DecBuffer(' ');		// Add a space after a sign
				pause = 0;
			}
#ifdef LIMITED_PAUSE
			if (space_cnt) {
#endif
				if (pause >= (decspeed * 70)) {// Pause >= 7 dits:
					storeMsChar2DecBuffer(' '); // Add spaces while pause
					pause -= (decspeed * 70);
#ifdef LIMITED_PAUSE
					space_cnt--;
#endif
				}
#ifdef LIMITED_PAUSE
			}
			else {
				pause = 0;
			}
#endif
		}
		if (signal > (decspeed * 20)) {	// Signal > 2 dits:
#ifdef DEBUG
			dahlength = signal;
#endif
			ditdah = '-';					//  Dah (length 3 dits)!
			if (signal >= (decspeed * 33)) {// Signal >= 3.3 dits (+10%):
				decspeed += speedvar;		//   Reduce decoder speed
				if (decspeed > SPEED_MIN) {decspeed = SPEED_MIN;}
			}
			signal = 0;
		}
		if (signal) {						// Short signal:
#ifdef DEBUG
			ditlength = signal;
#endif
			ditdah = '.';					//  Dit!
			if (signal <= (decspeed * 9)) {// Signal <= 0.9 dits (-10%):
				decspeed -= speedvar;		//  Increase decoder speed
				if (decspeed < SPEED_MAX) {decspeed = SPEED_MAX;}
			}
			signal = 0;
		}
	}
}

/**
 * Read next character from the Morse decoder ring buffer
 *
 * Output: Printable ASCII character [32..255] (as part of
 *         a received/decoded (prosign) Morse sign name)
 *         OR 0 (false), if the ring buffer is empty
 *
 */
uint8_t readMorseChar(void)
{uint8_t ch;
	if (dec_read_pos != dec_write_pos) {
		dec_read_pos++;
		if (dec_read_pos > MORSEDEC_BUFFER_MAXINDEX) {
			dec_read_pos = 0;
		}
		ch = morsedec_buffer[dec_read_pos];
	}
	else {
		ch = 0;
	}
	return (ch);
}

/**
 * Read next [numberOfChars] characters from the Morse decoder ring buffer
 *
 * Output: Number of characters copied to *buf,
 *         string *buf with the copied characters
 *
 */
uint8_t readMorseChars(char *buf, uint8_t numberOfChars)
{uint8_t ch, i;
	i = 0;
	while (i < numberOfChars) {
		ch = readMorseChar();
		if (ch) {
			buf[i] = ch;
		}
		else {break;}
		i++;
	}
	buf[i] = '\0';
	return (i);
}

/**
 * Get the number of characters still in the Morse decoder ring buffer
 *
 * Output: Number of characters (0: Buffer is empty!)
 *
 */
uint8_t getMorseDecBufferLength(void)
{int16_t dec_posdiff;
	dec_posdiff = dec_write_pos - dec_read_pos;
	if (dec_posdiff < 0) {
		dec_posdiff += (MORSEDEC_BUFFER_MAXINDEX + 1);
	}
	return ((uint8_t) dec_posdiff);
}

/*****************************************************************************/
// Morse encoder functions:

/**
 * Init Morse Encoder
 *
 * Call this once before using the Morse encoder (sender) task!
 *
 */
void initMorseEncoder(void)
{
	MORSEENC_DDR |= MORSEENC_IN;			// Encoder output pin
	MORSEENC_PORT &= ~MORSEENC_IN;			// Output low
	morse_error = false;					// Reset Morse error flag
	morseenc_status = MORSE_BUFFER_OK;		// Encoder buffer status ok
	enc_write_pos = 255;					// Reset buffer write pointer
	enc_read_pos = 255;						// Reset buffer read pointer
	encspeed = SPEED;						// Set encoder speed
#ifdef SOUND
	tonepitch = Tone_C2;					// Set tone pitch
#endif
}

/**
 * Fetch next Morse table index from the Morse encoder ring buffer
 *
 * Output: Morse table index [0..MORSESIGNS_MAXINDEX(..127)]
 *         OR pause length [129..255] (pause 1..127 dits)
 *         OR 128 (0x80), if the ring buffer is empty
 *
 */
uint8_t fetchMsIndexFromEncBuffer(void)
{uint8_t msidx;
	if (enc_read_pos != enc_write_pos) {
		enc_read_pos++;
		if (enc_read_pos > MORSEENC_BUFFER_MAXINDEX) {
			enc_read_pos = 0;
		}
		msidx = morseenc_buffer[enc_read_pos];
	}
	else {
		msidx = 0x80;
	}
	return (msidx);
}

/**
 * Morse encoder task
 *
 */
void task_MorseEnc(void)
{static uint8_t busy_flag, signal_flag, pause_flag, sos_flag, pause_dits;
 static uint16_t last_timer, ms_code; uint8_t msidx;
	if (busy_flag) {						// Encoder busy!
		if (signal_flag) {					// Sending signal
			if (!pause_flag) {				// Waiting for signal end
				if ((timer - last_timer)
				 >= (encspeed * 10 * (ms_code & 3))) {
#ifdef SOUND
					setBeeperPitch(Tone_Off);
#endif
#ifdef LIGHTENC
					externalPort.LED2 = false;
					outputExt();
#endif
					MORSEENC_PORT &= ~MORSEENC_IN;
					last_timer = timer;
					pause_flag = true;
					ms_code >>= 2;
				}
			}
			else {							// Pause after a signal
				if (ms_code) {				// Dit/dah (signal) end:
					if ((timer - last_timer) >= (encspeed * 10)) {
						signal_flag = false;//  Pause 1 dit
					}
				}
				else {						// Morse sign end:
					if (sos_flag) {			//  Case SOS:
						ms_code = 0x0001;	//   Add last dit
						sos_flag = false;
					}
					else {					//  Case sign end:
						if ((timer - last_timer) >= (encspeed * 30)) {
							busy_flag = false;// Pause 3 dits
						}
					}
				}
			}
		}
		else {								// Signal end
			if (pause_dits) {				// Make a longer pause
				if ((timer - last_timer) >= (encspeed * 10 * pause_dits)) {
					busy_flag = false;		// Longer pause end
				}
			}
			else {							// Start new signal (dit/dah)
#ifdef SOUND
				setBeeperPitch(tonepitch);
#endif
#ifdef LIGHTENC
				externalPort.LED2 = true;
				outputExt();
#endif
				MORSEENC_PORT |= MORSEENC_IN; 
				last_timer = timer;
				pause_flag = false;
				signal_flag = true;
			}
		}
	}
	else {									// Encoder not busy!
		msidx = fetchMsIndexFromEncBuffer();// Get next index to send
		if (msidx == 0x80) {				//  from the ring buffer
			return;							// Buffer empty: Return
		}
		else {
			if (msidx < 0x80) {				// Morse sign to send
				ms_code = MsIndex2MorseCode(msidx);
				if (ms_code == 0x5FD5) {
					sos_flag = true;		// Sign is SOS
				}
				else {
					sos_flag = false;
				}
				pause_dits = 0;
			}
			else {							// (msidx > 0x80): Longer pause
				last_timer = timer;
				pause_dits = msidx - 0x80;
			}
			signal_flag = false;
			busy_flag = true;				// Sign / longer pause can be sent
		}
	}
}

/**
 * Store a Morse table index into the Morse encoder ring buffer
 *
 * Input: Morse table index [0..MORSESIGNS_MAXINDEX(..127)]
 *        OR pause length [129..255] (pause 1..127 dits)
 *
 */
void storeMsIndex2EncBuffer(uint8_t msindex)
{
	if (getMorseEncBufferLength() < MORSEENC_BUFFER_MAXINDEX) {
		enc_write_pos++;
		if (enc_write_pos > MORSEENC_BUFFER_MAXINDEX) {
			enc_write_pos = 0;
		}
		morseenc_buffer[enc_write_pos] = msindex;
		morseenc_status = MORSE_BUFFER_OK;	// Encoder buffer status ok
	}
	else {
		morseenc_status = MORSE_BUFFER_OVERFLOW; // Encoder buffer overflow
	}
}

/**
 * Write a pause length to send into the Morse encoder ring buffer
 *
 * Input: Pause length [1..127 dits] (0.14..18.14 spaces)
 *
 * With this function you can reach longer pauses.
 *   Examples:
 *   pauseMorse(7);  is identical with  writeMorseChar(' ');
 *   pauseMorse(14); is identical with  writeMorseString("  ");
 * The function pauseMorse(len) only writes one byte into the encoder ring
 * buffer for a longer pause, while writeMorseChar(' ') writes one byte for
 * each space to send. You should use writeMorseChar(' ') for single spaces
 * (between words) and pauseMorse(len) for longer pauses.
 *
 * ATTENTION: !-----------------------------------------------------------!
 *            ! The max. pause length you can reach with this function is !
 *            ! about 6 seconds! So the max. input value of this function !
 *            ! depends on encspeed!!!                                    !
 *            !-----------------------------------------------------------!
 *            !   ==>  Max. pause length [dits] = 6000 / encspeed  <==    !
 *            !-----------------------------------------------------------!
 *            For encspeeds from 8 (SPEED_MAX) to 47 the max. pause length
 *            is 127 dits. For encspeeds from 48 to 400 (SPEED_MIN) you
 *            calculate the max. number of dits with the above formula.
 *            At SPEED_MIN you may only pause for 15 (6000 / 400) dits!
 *
 */
void pauseMorse(uint8_t len)
{
	if (len) {
		storeMsIndex2EncBuffer(len | 0x80);
	}
}

/**
 * Write a character to send into the Morse encoder ring buffer
 *
 * Input: ASCII code [0..255]
 *
 */
void writeMorseChar(uint8_t ch)
{static uint8_t sign_flag, chidx; uint8_t msidx;
 static char last_3ch[4];
	switch (ch) {
		case 32 :							// Space   [ASCII code 32]
			if (sign_flag) {				// Space directly after a sign
				pauseMorse(4);				//  (length 4 dits)
				if (morseenc_status == MORSE_BUFFER_OK) {
					sign_flag = false;
				}
			}
			else {							// Pause for all other spaces
				pauseMorse(7);				//  (length 7 dits)
			}
			break;
		default :
			// Chars used for prosign/special sign names:
			//  ` a..z # % * ^ ~[BLD 126] \[LCD 164]
			if (((ch >= '`') && (ch <= 'z')) || (ch == 35) || (ch == 37)
			 || (ch == 42) || (ch == 94) || (ch == 126) || (ch == 164)) {
				last_3ch[chidx] = ch; last_3ch[chidx + 1] = '\0';
				msidx = MsName2MsIndex(last_3ch);// Name in Morse table?
				if (morse_error) {
					chidx++;
					if (chidx > 2) {chidx = 0;}
					return;
				}
			}
			else {							// Normal chars
				msidx = pgm_read_byte(&a_ms_ft[ch]);
			}
			storeMsIndex2EncBuffer(msidx);
			if (morseenc_status == MORSE_BUFFER_OK) {
				sign_flag = true;
			}
	}
	chidx = 0;
}

/**
 * Write a string to send into the Morse encoder ring buffer
 *
 * Input: String with ASCII text
 *
 */
void writeMorseString(char *str)
{
	while (*str) {
		writeMorseChar(*str++);
	}
}

/**
 * Get the number of indices still in the Morse encoder ring buffer
 *
 * Output: Number of indices (0: Buffer is empty!)
 *
 */
uint8_t getMorseEncBufferLength(void)
{int16_t enc_posdiff;
	enc_posdiff = enc_write_pos - enc_read_pos;
	if (enc_posdiff < 0) {
		enc_posdiff += (MORSEENC_BUFFER_MAXINDEX + 1);
	}
	return ((uint8_t) enc_posdiff);
}

/*****************************************************************************/
// Useful LCD functions:

#ifndef DEBUG
/**
 * Show received Morse signs on the LCD 16x2 chars as ASCII text
 *
 */
void writeMorseLCD(void)
{static uint8_t pos; static char line2[17]; uint8_t ch;
	ch = readMorseChar();
	if (ch) {
		writeCharLCD(ch);
		line2[pos] = ch;
		pos++;
		if (pos >= 16) {
			pos = 0;
			clearLCD();
			writeStringLCD(line2);			// Copy line 2 to line 1
			setCursorPosLCD(1, 0);			// line 2, pos 1
		}
	}
}

#else

/**
 * Show decoder debug information on the LCD
 *
 * Format: .0000 -0000 S000
 *         B000 A[XXX] D000
 *
 *   .    -> Dit length [0.1ms]
 *   -    -> Dah length [0.1ms]
 *   S    -> Decoder speed (should be (dit length / 10)!) [ms]
 *   B    -> Decoder buffer length (chars still in the buffer)
 *   A    -> The 3 last received ASCII chars
 *   D    -> Deviation (decoder speed - (dit length / 10)) [ms]
 *
 */
void showDebugInfoLCD(void)
{static char last_3ch[4]; uint8_t ch;
	ch = readMorseChar();
	if (ch) {
		last_3ch[0] = last_3ch[1]; last_3ch[1] = last_3ch[2];
		last_3ch[2] = ch; last_3ch[3] = '\0';
		setCursorPosLCD(0, 0);				// line 1, pos 1
		writeStringLCD_P(".");
		writeIntegerLengthLCD(ditlength, DEC, 4);
		writeStringLCD_P(" -");
		writeIntegerLengthLCD(dahlength, DEC, 4);
		writeStringLCD_P(" S");
		writeIntegerLengthLCD(decspeed, DEC, 3);
		setCursorPosLCD(1, 0);				// line 2, pos 1
		writeStringLCD_P("B");
		writeIntegerLengthLCD(getMorseDecBufferLength(), DEC, 3);
		writeStringLCD_P(" A[");
		writeStringLCD(last_3ch);
		writeStringLCD_P("] D");
		writeIntegerLengthLCD((decspeed - (ditlength / 10)), DEC, 3);
	}
}
#endif

/******************************************************************************
 * Additional info
 * ****************************************************************************
 * Changelog:
 * - v. 3.6w 2012 by Dirk
 *
 * ****************************************************************************
 */

/*****************************************************************************/
// EOF

RP6 CCPRO M128

Die RP6 CCPRO M128 Morse Library gehört in den Ordner \RP6CCLib.

Datei RP6MorseCClib.cc:

/* ****************************************************************************
 *                           _______________________
 *                           \| RP6  ROBOT SYSTEM |/
 *                            \_-_-_-_-_-_-_-_-_-_/              >>> CCPRO M128
 * ----------------------------------------------------------------------------
 * ----------------------- [c]2012 - Dirk -------------------------------------
 * ****************************************************************************
 * File: RP6MorseCClib.cc
 * Version: 1.5w - CompactC
 * Target: RP6 CCPRO M128 - C-Control PRO M128 @14.7456MHz
 *         mit optionalem LC-Display 16x2 Zeichen (CONRAD 190911)
 *         [oder Backlight Display 16x2 Zeichen (CONRAD 191621)]
 * Author(s): Dirk
 * ****************************************************************************
 * Beschreibung:
 * Dies ist meine RP6 CCPRO M128 Morse Bibliothek
 *
 * ****************************************************************************
 * Mit den Funktionen in dieser Bibliothek kann der RP6 mit CCPRO M128
 * Morse Zeichen senden und empfangen.
 *
 * ****************************************************************************
 * CHANGELOG FINDEN SIE AM ENDE DIESER DATEI!
 * ****************************************************************************
 */

 // Alles nur EINMAL einbinden!
#ifndef __RP6MORSECCLIB__
#define __RP6MORSECCLIB__


/******************************************************************************/
// Defines:

// RP6 CCPRO M128 Morse-Decoder Anschluß (Eingang):
//#define MORSEDEC_IN 24          // PortD.0 (RP6: SCL)
#define MORSEDEC_IN 25          // PortD.1 (RP6: SDA)
//#define MORSEDEC_IN 37          // PortE.5 (RP6: INT1)

// RP6 CCPRO M128 Morse-Encoder Anschluß (Ausgang):
#define MORSEENC_IN 37          // PortE.5 (RP6: INT1)

#define SPEED                       100 // = 12 WpM = 60 CpM
// Berechne SPEED: SPEED = 1200 / WpM
//                 SPEED = 6000 / CpM
#define SPEED_MIN                   400 // = 3 WpM = 15 CpM
#define SPEED_MAX                   8   // = 150 WpM = 750 CpM
#define SPEED_VAR                   5   // Decoder Speed Variation

#define LIMITED_PAUSE                   // Decoder: Leerzeichen begrenzt
#define SPACE_CNT_LIMIT             3   // Max. Anzahl Leerzeichen

//#define INVERTDEC						// Decoder Eingangspegel umkehren

//#define DEBUG                           // Decoder Debug Modus

//#define ANSI							// Nutzt ANSI (IDE Terminal) Zeichensatz
#define LCD								// Nutzt LCD (190911) Zeichensatz
//#define BLD								// Nutzt BLD (191621) Zeichensatz
// WICHTIG: Nur EINE der o.g. drei Definitionen darf aktiviert werden!

#define LIGHTDEC						// LED1 zeigt die Decoder Morse Zeichen
#define LIGHTENC						// LED2 zeigt die Encoder Morse Zeichen

//#define SOUND                           // Macht die Morse Zeichen hörbar
#define Tone_D1                     392 //294Hz
#define Tone_Dis1                   370 //311Hz
#define Tone_E1                     349 //330Hz
#define Tone_F1                     330 //349Hz
#define Tone_Fis1                   311 //370Hz
#define Tone_G1                     294 //392Hz
#define Tone_Gis1                   277 //415Hz
#define Tone_A1                     262 //440Hz
#define Tone_Ais1                   247 //466Hz
#define Tone_H1                     233 //494Hz
#define Tone_C2                     220 //523Hz
#define Tone_Cis2                   208 //554Hz
#define Tone_D2                     196 //587Hz
#define Tone_Dis2                   185 //622Hz
#define Tone_E2                     175 //659Hz
#define Tone_F2                     165 //698Hz
#define Tone_Fis2                   156 //740Hz
#define Tone_G2                     147 //784Hz
#define Tone_Gis2                   139 //831Hz
#define Tone_A2                     131 //880Hz
#define Tone_Ais2                   124 //932Hz
#define Tone_H2                     117 //988Hz

#define MS_SIGNALS_MAXINDEX         7
#define MS_SPECIALS_MAXINDEX        25
#define MORSESIGNS_MAXINDEX         79

#define MORSEDEC_BUFFER_MAXINDEX    31  // Morse Decoder Puffer Länge
#define MORSEENC_BUFFER_MAXINDEX    31  // Morse Encoder Puffer Länge

// Morse Decoder/Encoder Status:
#define MORSE_BUFFER_OK             0
#define MORSE_BUFFER_OVERFLOW       1   // Morse Puffer Überlauf

// ----------------------------------------------------------------------------
// MORSE TABELLEN:

// Morse Tabelle [0..79]:
// Morse Decoder und Encoder nutzen diese Tabelle, um Morse Code zu empfangen
// oder zu senden. Diese Tabelle enthält 16-Bit Konstanten. Jeder Tabellen-
// index [0..79] (oder jede Word Konstante) stellt ein Morse Zeichen dar.
// Die Punkte (dit) und Striche (dah) werden als 2 Bits gespeichert: Die Bits
// "01" stehen für ein dit und "11" für ein dah, gelesen von rechts nach links
// in der binären Darstellung. Zwischen dits und dahs eines Morse Zeichens
// muss man eine Pause mit der Länge eines dits senden. Zwischen Morse Zeichen
// gibt es eine Pause mit der Länge von drei dits (oder einem dah).
//
// Beispiel:                   Ende <<<<7<<6<<5<<4<<3<<2<<1<<<< Start
//                                  ---DahDitDitDahDitDitDit
// 0x35D5 = 0b0011010111010101 -> 0b 00 11 01 01 11 01 01 01 -> $ (Dollar)
flash word ms_ft[MORSESIGNS_MAXINDEX + 1] =
// Signale:
// Hex        Binär            Zeichen  Index  Signal
{0x5555, // 0b0101010101010101            0      HH
 0x0DD5, // 0b0000110111010101                   SK
 0x0377, // 0b0000001101110111                   CT
 0x3757, // 0b0011011101010111                   BK
 0x5D77, // 0b0101110101110111                   CL
 0xDF77, // 0b1101111101110111            5      CQ
 0x0FD7, // 0b0000111111010111                   DO
 0x5FD5, // 0b0101111111010101            7      SOS
//------------------------------------------------------
// Sonderzeichen:
// Hex        Binär            Zeichen  Index  Signal
 0x01DF, // 0b0000000111011111  ^G        8
 0x00FF, // 0b0000000011111111  CH,^H
 0x01FD, // 0b0000000111111101  ^J       10
 0x15D5, // 0b0001010111010101  /S
 0x01D5, // 0b0000000111010101  ^S               VE
 0x075F, // 0b0000011101011111  /Z
 0x035F, // 0b0000001101011111  .Z
 0x037D, // 0b0000001101111101  /A,°A    15
 0x00DD, // 0b0000000011011101  Ä                AA
 0x0177, // 0b0000000101110111  C~
 0x035D, // 0b0000001101011101  \E
 0x0175, // 0b0000000101110101  /E
 0x01F5, // 0b0000000111110101  Eth      20
 0x03DF, // 0b0000001111011111  ~N
 0x007F, // 0b0000000001111111  Ö
 0x00F5, // 0b0000000011110101  Ü
 0x017D, // 0b0000000101111101  Thorn
 0x17D5, // 0b0001011111010101  ß        25
//------------------------------------------------------
// Normale Zeichen:
// Hex        Binär            Zeichen  Index  Signal
 0x0F77, // 0b0000111101110111  !        26
 0x075D, // 0b0000011101011101  "
 0x35D5, // 0b0011010111010101  $
 0x015D, // 0b0000000101011101  &                AS
 0x07FD, // 0b0000011111111101  '        30
 0x01F7, // 0b0000000111110111  (                KN
 0x0DF7, // 0b0000110111110111  )
 0x01DD, // 0b0000000111011101  +                AR
 0x0F5F, // 0b0000111101011111  ,
 0x0D57, // 0b0000110101010111  -        35
 0x0DDD, // 0b0000110111011101  .
 0x01D7, // 0b0000000111010111  /                NR
 0x03FF, // 0b0000001111111111  0
 0x03FD, // 0b0000001111111101  1
 0x03F5, // 0b0000001111110101  2        40
 0x03D5, // 0b0000001111010101  3
 0x0355, // 0b0000001101010101  4
 0x0155, // 0b0000000101010101  5
 0x0157, // 0b0000000101010111  6
 0x015F, // 0b0000000101011111  7        45
 0x017F, // 0b0000000101111111  8
 0x01FF, // 0b0000000111111111  9
 0x057F, // 0b0000010101111111  :
 0x0777, // 0b0000011101110111  ;
 0x0357, // 0b0000001101010111  =        50      BT
 0x05F5, // 0b0000010111110101  ?                IMI
 0x077D, // 0b0000011101111101  @
 0x000D, // 0b0000000000001101  A
 0x0057, // 0b0000000001010111  B                DE
 0x0077, // 0b0000000001110111  C        55
 0x0017, // 0b0000000000010111  D
 0x0001, // 0b0000000000000001  E
 0x0075, // 0b0000000001110101  F
 0x001F, // 0b0000000000011111  G
 0x0055, // 0b0000000001010101  H        60
 0x0005, // 0b0000000000000101  I
 0x00FD, // 0b0000000011111101  J
 0x0037, // 0b0000000000110111  K                K
 0x005D, // 0b0000000001011101  L
 0x000F, // 0b0000000000001111  M        65
 0x0007, // 0b0000000000000111  N
 0x003F, // 0b0000000000111111  O
 0x007D, // 0b0000000001111101  P
 0x00DF, // 0b0000000011011111  Q
 0x001D, // 0b0000000000011101  R        70      R
 0x0015, // 0b0000000000010101  S
 0x0003, // 0b0000000000000011  T
 0x0035, // 0b0000000000110101  U
 0x00D5, // 0b0000000011010101  V
 0x003D, // 0b0000000000111101  W        75
 0x00D7, // 0b0000000011010111  X
 0x00F7, // 0b0000000011110111  Y
 0x005F, // 0b0000000001011111  Z
 0x0DF5};// 0b0000110111110101  _        79
// Bemerkungen: - SOS (Morse Zeichen ...---...) kann nicht in einer 16-Bit
//                Konstante gespeichert werden, weil SOS das einzige Morse
//                Zeichen mit 9 dits/dahs ist. Daher wird SOS als das (nicht
//                existierende) Morse Zeichen ...---.. (SOI) gespeichert und
//                muss in Decodern/Encodern besonders behandelt werden.


// Morse-ASCII-Tabelle [0..79]:
// Morse Decoder nutzen diese Tabelle, um Morse Code zu empfangen.
flash unsigned char ms_a0uc_ft[MORSESIGNS_MAXINDEX + 1] =
//H   S   C   B   C   C   D   S
{104,115, 99, 98, 99, 99,100,115,
//0                   5
#ifdef ANSI
//                           ANSI [Index 15..25]:
//^   C   ^   %   ^   %   *   /A  Ä   C~  \E  /E  Et  ~N  Ö   Ü   To  ß
  94, 99, 94, 37, 94, 37, 42,193,196,199,200,201,208,209,214,220,222,223,
//        10                  15                  20                  25
#endif
#ifdef LCD
//                           LCD [Index 15..25]:
//^   C   ^   %   ^   %   *   %   Ä   C   \   %   E   -N  Ö   Ü   T   ß
  94, 99, 94, 37, 94, 37, 42, 37,225, 99, 96, 37,101,238,239,245,116,226,
//        10                  15                  20                  25
#endif
#ifdef BLD
//                           BLD [Index 15..25]:
//^   C   ^   %   ^   %   *   /A  A   C   \   %   E   ~   O   U   T   ß
  94, 99, 94, 37, 94, 37, 42,160, 97, 99, 96, 37,101,126,111,117,116,224,
//        10                  15                  20                  25
#endif
//!  "  $  &  '  (  )  +  ,  -  .  /  0  1  2  3  4  5  6  7  8  9  :  ;
 33,34,36,38,39,40,41,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,
//           30             35             40             45
//=  ?  @  A  B  C  D   E   F   G   H   I   J   K   L   M   N   O   P   Q
 61,63,64,65,66,67, 68, 69, 70, 71, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81,
//50            55                  60                  65
//R   S   T   U   V   W   X   Y   Z   _
  82, 83, 84, 85, 86, 87, 88, 89, 90,95};       // Et = Eth,  To = Thorn
//70                  75             79

flash unsigned char ms_a1uc_ft[MORSESIGNS_MAXINDEX + 1] =
//H   K   T   K   L   Q   O   O
{104,107,116,107,108,113,111,111,
//0                   5
#ifdef ANSI
//                           ANSI [Index 15..25]:
//G   H   J   S   S   Z   Z
 103,104,106,115,115,122,122, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32,
//        10                  15                  20                  25
#endif
#ifdef LCD
//                           LCD [Index 15..25]:
//G   H   J   S   S   Z   Z   A       \   E   E   T               O
 103,104,106,115,115,122,122, 97, 32,164,101,101,116, 32, 32, 32,111, 32,
//        10                  15                  20                  25
#endif
#ifdef BLD
//                           BLD [Index 15..25]:
//G   H   J   S   S   Z   Z       E   ~   E   E   T   N   E   E   O
 103,104,106,115,115,122,122, 32,101,126,101,101,116,110,101,101,111, 32,
//        10                  15                  20                  25
#endif
 32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,
//           30             35             40             45
 32,32,32,32,32,32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32,
//50            55                  60                  65
  32, 32, 32, 32, 32, 32, 32, 32, 32,32};       // Et = Eth,  To = Thorn
//70                  75             79

flash unsigned char ms_a2uc_ft[MORSESIGNS_MAXINDEX + 1] =
//                            S
{ 32, 32, 32, 32, 32, 32, 32,115,
//0                   5
  32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32,
//        10                  15                  20                  25
 32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,32,
//           30             35             40             45
 32,32,32,32,32,32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32, 32,
//50            55                  60                  65
  32, 32, 32, 32, 32, 32, 32, 32, 32,32};       // Et = Eth,  To = Thorn
//70                  75             79
// Signale und Sonderzeichen sind in dieser Tabelle als Kleinbuchstaben
// gespeichert (hh, sk, ^g, ch ...).
// Bemerkungen: - Die Sonderzeichen ^G, ^J, /S, ^S, /Z, .Z [Index 8, 10..14]
//                sind  hier  als   ^g, ^j, %s, ^s, %z, *z dargestellt.
//              - Die Sonderzeichen [Index 15..25] werden je nach Ausgabe-
//                Ziel (ANSI, LCD, BLD) unterschiedlich dargestellt.
//              - Wenn Morse Decoder eine Pause mit einer Länge von 7 dits
//                empfangen, müssen sie den ASCII Code ' ' (Leerzeichen [32])
//                ausgeben.


// ASCII-Morse-Tabelle [0..255]:
// Morse Encoder nutzen diese Tabelle, um Morse Code zu senden.
flash byte a_ms_ft[256] =
{51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,
//0              5             10             15             20
 51,51,51,51,51,51,51,51,
//24               30
//_  !  "  ?  $  ?  &  '  (  )  X  +  ,  -  .  /  0  1  2  3  4  5  6  7
 79,26,27,51,28,51,29,30,31,32,76,33,34,35,36,37,38,39,40,41,42,43,44,45,
//32      35             40             45             50             55
//8  9  :  ;  ?  =  ?  ?  @  A  B  C  D  E  F  G  H  I  J  K  L  M  N  O
 46,47,48,49,51,50,51,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,
//56         60             65             70             75
//P  Q  R  S  T  U  V  W  X  Y  Z  [  ?  ]  ?  _  ?  A  B  C  D  E  F  G
 68,69,70,71,72,73,74,75,76,77,78,31,51,32,51,79,51,53,54,55,56,57,58,59,
//80            85             90             95            100
//H  I  J  K  L  M  N  O  P  Q  R  S  T  U  V  W  X  Y  Z  {  ?  }  ?  ?
 60,61,62,63,64,65,66,67,68,69,70,71,72,73,74,75,76,77,78,31,51,32,51,51,
//104             110            115            120            125
//?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?
 51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,
//128 130            135            140            145            150
//?  ?  ?  ?  ?  ?  ?  ?  _  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?
 51,51,51,51,51,51,51,51,79,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,
//152    155            160            165            170            175
//?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ?  ? /A  ?  ?  Ä  ?  ? C~
 51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,51,15,51,51,16,51,51,17,
//176       180            185            190            195
//\E/E  ?  ?  ?  ?  ?  ? Et ~N  ?  ?  ?  ?  Ö  X  ?  ?  ?  ?  Ü  ? To  ß
 18,19,51,51,51,51,51,51,20,21,51,51,51,51,22,76,51,51,51,51,23,51,24,25,
//200          205            210            215            220
//? /A  ?  ?  Ä  ?  ? C~ \E /E  ?  ?  ?  ?  ?  ? Et ~N  ?  ?  ?  ?  Ö  /
 51,15,51,51,16,51,51,17,18,19,51,51,51,51,51,51,20,21,51,51,51,51,22,37,
//224             230            235            240            245
//?  ?  ?  ?  Ü  ? To  ?
 51,51,51,51,23,51,24,51};                      // Et = Eth,  To = Thorn
//248                255
// Bemerkungen: - ASCII Codes 91 '[' und 123 '{' werden umgewandelt in
//                Morse Code '(' [31].
//              - ASCII Codes 93 ']' und 125 '}' werden umgewandelt in
//                Morse Code ')' [32].
//              - ASCII Code 215 (Multiplikationszeichen) wird umgewandelt
//                in Morse Code 'X' [76].
//              - ASCII Code 247 (Divisionszeichen) wird umgewandelt in
//                Morse Code '/' [37].
//              - ASCII Codes 32 (sp) und 160 (nbsp) sind als '_' [79] in
//                dieser Tabelle dargestellt, müssen aber in Encodern
//                besonders behandelt werden: Ein Morse Encoder muss eine
//                Pause mit einer Länge von 7 dits für ein Leerzeichen
//                senden.
//              - Alle nicht druckbaren ASCII Codes [0..31] und andere
//                Codes, die nicht im Morse Code definiert sind, werden
//                in Morse Code '?' [51] umgewandelt.

// MORSE TABELLEN (ENDE)
// ----------------------------------------------------------------------------

/******************************************************************************/
// Variablen:
word timer;
byte morsedec_status;
byte morseenc_status;
byte morse_error;
#ifdef SOUND
word tonepitch;
#endif

// Feld Variablen für die Morse Tabellen:
word ms_rt[MORSESIGNS_MAXINDEX + 1];
unsigned char ms_a0uc_rt[MORSESIGNS_MAXINDEX + 1];
unsigned char ms_a1uc_rt[MORSESIGNS_MAXINDEX + 1];
unsigned char ms_a2uc_rt[MORSESIGNS_MAXINDEX + 1];
byte a_ms_rt[256];

unsigned char morsedec_buffer[MORSEDEC_BUFFER_MAXINDEX + 2];
byte dec_write_pos, dec_read_pos;
unsigned char morseenc_buffer[MORSEENC_BUFFER_MAXINDEX + 2];
byte enc_write_pos, enc_read_pos;

word decspeed;
byte speedvar;

word encspeed;

#ifdef DEBUG
word ditlength, dahlength;
#endif

/******************************************************************************/
// Funktionen:

/**
 * Kopiere die Morse Tabellen vom Flash Speicher ins RAM
 *
 */
void copyFlashTables2RAM(void)
{
    ms_rt = ms_ft;
    ms_a0uc_rt = ms_a0uc_ft;
    ms_a1uc_rt = ms_a1uc_ft;
    ms_a2uc_rt = ms_a2uc_ft;
    a_ms_rt = a_ms_ft;
}

/**
 * Wandele Kleinbuchstaben in Großbuchstaben um
 *
 * Eingabe: ASCII Code [0..255]
 * Ausgabe: ASCII Code, nur mit Großbuchstaben
 *
 */
unsigned char Lower2UpperCase(unsigned char ch)
{unsigned char chuc;
    chuc = ch;
    if ((ch >= 97) && (ch <= 122)) {
        chuc = chuc - 32;
    }
    if ((ch >= 224) && (ch <= 254) && (ch != 247)) {
        chuc = chuc - 32;
    }
    return (chuc);
}

/**
 * Wandele Großbuchstaben in Kleinbuchstaben um
 *
 * Eingabe: ASCII Code [0..255]
 * Ausgabe: ASCII Code, nur mit Kleinbuchstaben
 *
 */
unsigned char Upper2LowerCase(unsigned char ch)
{unsigned char chlc;
    chlc = ch;
    if ((ch >= 65) && (ch <= 90)) {
        chlc = chlc + 32;
    }
    if ((ch >= 192) && (ch <= 222) && (ch != 215)) {
        chlc = chlc + 32;
    }
    return (chlc);
}

/**
 * Ausgabe des Morse Codes eines Morse Tabellenindex
 *
 * Eingabe: Morse Tabellenindex [0..MORSESIGNS_MAXINDEX]
 * Ausgabe: Morse Code (Siehe Tabelle ms_ft[] oben!)
 *
 */
word MsIndex2MorseCode(byte msindex)
{
    morse_error = false;
    return (ms_rt[msindex]);
}

/**
 * Ausgabe des Tabellenindex eines Morse Codes
 *
 * Eingabe: Morse Code (Siehe Tabelle ms_ft[] oben!)
 * Ausgabe: Morse Tabellenindex [0..MORSESIGNS_MAXINDEX]
 *
 */
byte MorseCode2MsIndex(word morsecode)
{byte msidx;
    for (msidx = 0; msidx <= MORSESIGNS_MAXINDEX; msidx++) {
        if (morsecode == ms_rt[msidx]) {break;}
    }
    if (msidx <= MORSESIGNS_MAXINDEX) {
        morse_error = false;
        return (msidx);                 // Morse Tabellenindex
    }
    else {
        morse_error = true;             // Unbekannter Morse Code:
        return (51);                    //  Gib Tabellenindex von '?' zurück
    }
}

/**
 * Ausgabe des Morse Zeichen Namens eines Morse Codes
 *
 * Eingabe: Morse Code (Siehe Tabelle ms_ft[] oben!)
 * Ausgabe: String mit dem Morse Zeichen Namen (1..3 ASCII Zeichen)
 *
 */
void MorseCode2MsName(unsigned char msname[], word morsecode)
{byte msidx;
    msidx = MorseCode2MsIndex(morsecode);
    msname[0] = ms_a0uc_rt[msidx];
    msname[1] = ms_a1uc_rt[msidx];
    if (msname[1] == 32) {msname[1] = 0;}
    msname[2] = ms_a2uc_rt[msidx];
    if (msname[2] == 32) {
        msname[2] = 0;
    }
    else {
        msname[3] = 0;
    }
}

/**
 * Ausgabe des Morse Tabellenindex eines Morse Zeichen Namens
 *
 * Eingabe: String mit dem Morse Zeichen Namen (1..3 ASCII Zeichen)
 * Ausgabe: Morse Tabellenindex [0..MORSESIGNS_MAXINDEX]
 *
 */
byte MsName2MsIndex(unsigned char msname[])
{byte msidx;
    for (msidx = 0; msidx <= MORSESIGNS_MAXINDEX; msidx++) {
        if (msname[0] == ms_a0uc_rt[msidx]) {
            if ((ms_a1uc_rt[msidx] == 32)
             || (msname[1] == ms_a1uc_rt[msidx])) {
                if ((ms_a2uc_rt[msidx] == 32)
                 || (msname[2] == ms_a2uc_rt[msidx])) {
                    break;
                }
            }
        }
    }
    if (msidx <= MORSESIGNS_MAXINDEX) {
        morse_error = false;
        return (msidx);                 // Morse Tabellenindex
    }
    else {
        morse_error = true;             // Unbekannter Morse Zeichen Name:
        return (51);                    //  Gib Tabellenindex von '?' zurück
    }
}

/**
 * Ausgabe des Morse Zeichens eines Morse Codes
 *
 * Eingabe: Morse Code (Siehe Tabelle ms_ft[] oben!)
 * Ausgabe: String mit dem Morse Zeichen (1..9 dits [.] oder dahs [-])
 *
 * Beispiel: $  -> 0b0011010111010101  -> Morse Zeichen ...-..-
 *
 */
void MorseCode2MorseSign(unsigned char morsesign[], word morsecode)
{byte i; word ms_code;
    ms_code = morsecode;
    i = 0;
    do {
        switch (ms_code & 3) {
            case 1 :                    // dit!
                morsesign[i] = '.';
                i++; break;
            case 3 :                    // dah!
                morsesign[i] = '-';
                i++;
        }
        ms_code = ms_code >> 2;
    } while (ms_code);
    if (morsecode == 0x5FD5) {          // SOS: Füge letztes dit hinzu!
        morsesign[i] = '.';
        i++;
    }
    morsesign[i] = 0;
    morse_error = false;
}

/**
 * Ausgabe des Morse Codes eines Morse Zeichens
 *
 * Eingabe: String mit dem Morse Zeichen (1..9 dits [.] oder dahs [-])
 * Ausgabe: Morse Code (Siehe Tabelle ms_ft[] oben!)
 *
 * Beispiel: $  -> Morse Zeichen ...-..-  -> 0b0011010111010101
 *
 */
word MorseSign2MorseCode(unsigned char morsesign[])
{byte i; unsigned char ch; word ms_code;
    ms_code = 0;
    ch = 1;
    for (i = 0; i <= 7; i++) {
        ms_code = ms_code >> 2;
        if (ch) {
            ch = morsesign[i];
            switch (ch) {
                case '.' :              // dit!
                    ms_code = ms_code | 0x4000; break;
                case '-' :              // dah!
                    ms_code = ms_code | 0xC000;
            }
        }

    }
    if ((ms_code == 0x5FD5) && (morsesign[8] != '.')) {
        ms_code = 0x05F5;    // SOS: Wenn das letzte dit nicht existiert,
        morse_error = true;  //      gib '?' zurück!
    }
    else {
        morse_error = false;
    }
    return (ms_code);
}

/******************************************************************************/
// Morse Decoder Funktionen:

/**
 * Lösche den Morse Decoder Ring Puffer
 *
 */
void clearMorseDecBuffer(void)
{
    morsedec_status = MORSE_BUFFER_OK;  // Decoder Puffer Status ok
    dec_write_pos = 255;                // Puffer Schreibposition zurücksetzen
    dec_read_pos = 255;                 // Puffer Leseposition zurücksetzen
}

/**
 * Initialisiere den Morse Decoder
 *
 * Einmal aufrufen, bevor die Morse Decoder (Empfänger) Funktion benutzt wird!
 *
 */
void initMorseDecoder(void)
{
    copyFlashTables2RAM();              // Fülle die Tabellen im RAM
    Port_DataDirBit(MORSEDEC_IN, PORT_IN); // Decoder Eingangs Pin
    Port_WriteBit(MORSEDEC_IN, 1);         // MORSEDEC_IN -> Pullup
    morse_error = false;                // Setze das Morse Fehler Flag zurück
    clearMorseDecBuffer();              // Lösche den Decoder Puffer
    decspeed = SPEED;                   // Decoder Speed
    speedvar = SPEED_VAR;               // Decoder Speed Variation
#ifdef SOUND
    tonepitch = Tone_C2;                // Tonhöhe festlegen
#endif
}

/**
 * Speichere ein decodiertes Signal / Morse Zeichen in den Decoder Ring Puffer
 *
 * Eingabe: ASCII Zeichen (Teil eines Strings mit dem Signal / Zeichen Namen)
 *
 */
void storeMsChar2DecBuffer(unsigned char ch)
{
    if (getMorseDecBufferLength() < MORSEDEC_BUFFER_MAXINDEX) {
        dec_write_pos++;
        if (dec_write_pos > MORSEDEC_BUFFER_MAXINDEX) {
            dec_write_pos = 0;
        }
        morsedec_buffer[dec_write_pos] = ch;
        morsedec_status = MORSE_BUFFER_OK;      // Decoder Puffer Status ok
    }
    else {
        morsedec_status = MORSE_BUFFER_OVERFLOW;// Decoder Puffer Überlauf
    }
}

/**
 * Morse Decoder
 *
 * Die Funktion decodeMorse() muss alle 1ms aufgerufen werden.
 *
 */
void decodeMorse(void)
{static unsigned char ms_sign[10]; byte temp;
 static word signal, pause;
 static byte ditdah, ditdah_cnt;
 unsigned char ms_name[4];
#ifdef SOUND
 static byte tone_off;
#endif
#ifdef LIMITED_PAUSE
 static byte space_cnt;
#endif
    Thread_Lock(1);
    temp = Port_ReadBit(MORSEDEC_IN);   // Lese den Morse Pegel
#ifdef INVERTDEC
	temp = (!temp);						// Eingangspegel umkehren
#endif
    if (temp) {                         // Highpegel (Morsesignal an = dit/dah)
#ifdef SOUND
        if (tone_off) {
            sound(tonepitch);
            tone_off = false;
        }
#endif
#ifdef LIGHTDEC
        Port_WriteBit(PORT_LED1, 1);
#endif
        signal++;
        if (pause > (decspeed * 2)) {   // Pause > 2 dits:
            if (ditdah) {               //  Morse Zeichen Ende (Länge 3 dits)
                ms_sign[ditdah_cnt] = ditdah;
                ditdah_cnt++;
                ms_sign[ditdah_cnt] = 0;
                ditdah_cnt = 0;
                ditdah = 0;
                MorseCode2MsName(ms_name, MorseSign2MorseCode(ms_sign));
                temp = 0;
                while (ms_name[temp]) {
                    storeMsChar2DecBuffer(ms_name[temp++]);
                }
            }
            pause = 0;
        }
        if (pause) {                    // Kurze Pause:
            if (ditdah) {               //  Dit oder dah Ende (Länge 1 dit)
                ms_sign[ditdah_cnt] = ditdah;
                ditdah_cnt++;
                ms_sign[ditdah_cnt] = 0;
                if (ditdah_cnt > 8) {ditdah_cnt = 0;}
                ditdah = 0;
            }
            pause = 0;
        }
    }
    else {                              // Lowpegel (Morsesignal aus = Pause)
#ifdef SOUND
        sound_off();
        tone_off = true;
#endif
#ifdef LIGHTDEC
        Port_WriteBit(PORT_LED1, 0);
#endif
        pause++;
        if (pause > (decspeed * 5)) {   // Pause > 5 dits:
            if (ditdah) {               //  Leerzeichen oder längere Pause
                ms_sign[ditdah_cnt] = ditdah;
                ditdah_cnt++;
                ms_sign[ditdah_cnt] = 0;
                ditdah_cnt = 0;
                ditdah = 0;
                MorseCode2MsName(ms_name, MorseSign2MorseCode(ms_sign));
                temp = 0;
                while (ms_name[temp]) {
                    storeMsChar2DecBuffer(ms_name[temp++]);
                }
#ifdef LIMITED_PAUSE
                space_cnt = SPACE_CNT_LIMIT;
                space_cnt--;
#endif
                storeMsChar2DecBuffer(' ');     // Füge ein Leerzeichen nach
                pause = 0;                      //  dem Zeichen an
            }
#ifdef LIMITED_PAUSE
            if (space_cnt) {
#endif
                if (pause >= (decspeed * 7)) {  // Pause >= 7 dits:
                    storeMsChar2DecBuffer(' '); //  Füge Leerzeichen an
                    pause = pause - (decspeed * 7);
#ifdef LIMITED_PAUSE
                    space_cnt--;
#endif
                }
#ifdef LIMITED_PAUSE
            }
            else {
                pause = 0;
            }
#endif
        }
        if (signal > (decspeed * 2)) {          // Highpegel > 2 dits:
#ifdef DEBUG
            dahlength = signal;
#endif
            ditdah = '-';                       //  Dah (Länge 3 dits)!
            if (signal >= (decspeed * 3.3)) {   // Highpegel >= 3,3 dits (+10%):
                decspeed = decspeed + speedvar; //  Reduziere Decoder Speed
                if (decspeed > SPEED_MIN) {decspeed = SPEED_MIN;}
            }
            signal = 0;
        }
        if (signal) {                           // Kurzer Highpegel:
#ifdef DEBUG
            ditlength = signal;
#endif
            ditdah = '.';                       //  Dit!
            if (signal <= (decspeed * 0.9)) {   // Highpegel <= 0,9 dits (-10%):
                decspeed = decspeed - speedvar; //  Erhöhe Decoder Speed
                if (decspeed < SPEED_MAX) {decspeed = SPEED_MAX;}
            }
            signal = 0;
        }
    }
    Thread_Lock(0);
}

/**
 * Lese nächstes Zeichen aus dem Morse Decoder Ring Puffer
 *
 * Ausgabe: Druckbares ASCII Zeichen [32..255] (als Teil eines
 *          empfangenen/decodierten Signal / Morse Zeichen Namens)
 *          ODER 0 (false), wenn der Ring Puffer leer ist
 *
 */
unsigned char readMorseChar(void)
{unsigned char ch;
    if (dec_read_pos != dec_write_pos) {
        dec_read_pos++;
        if (dec_read_pos > MORSEDEC_BUFFER_MAXINDEX) {
            dec_read_pos = 0;
        }
        ch = morsedec_buffer[dec_read_pos];
    }
    else {
        ch = 0;
    }
    return (ch);
}

/**
 * Lese nächste [numberOfChars] Zeichen aus dem Morse Decoder Ring Puffer
 *
 * Ausgabe: Anzahl der Zeichen, die nach *buf kopiert wurden,
 *          String *buf mit den kopierten Zeichen
 *
 */
byte readMorseChars(unsigned char buf[], byte numberOfChars)
{byte i; unsigned char ch;
    i = 0;
    while (i < numberOfChars) {
        ch = readMorseChar();
        if (ch) {
            buf[i] = ch;
        }
        else {break;}
        i++;
    }
    buf[i] = 0;
    return (i);
}

/**
 * Ermittele die Anzahl der Zeichen im Morse Decoder Ring Puffer
 *
 * Ausgabe: Anzahl der Zeichen (0: Puffer ist leer!)
 *
 */
byte getMorseDecBufferLength(void)
{int dec_posdiff;
    dec_posdiff = dec_write_pos - dec_read_pos;
    if (dec_posdiff < 0) {
        dec_posdiff = dec_posdiff + (MORSEDEC_BUFFER_MAXINDEX + 1);
    }
    return (dec_posdiff);
}

/******************************************************************************/
// Morse Encoder Funktionen:

/**
 * Inititialisiere den Morse Encoder
 *
 * Einmal aufrufen, bevor die Morse Encoder (Sender) Funktion benutzt wird!
 *
 */
void initMorseEncoder(void)
{
    copyFlashTables2RAM();              // Fülle die Tabellen im RAM
    Port_DataDirBit(MORSEENC_IN, PORT_OUT); // Encoder Ausgangs Pin
    Port_WriteBit(MORSEENC_IN, 0);          // Ausgang low
    morse_error = false;                // Setze das Morse Fehler Flag zurück
    morseenc_status = MORSE_BUFFER_OK;  // Encoder Puffer Status ok
    enc_write_pos = 255;                // Puffer Schreibposition zurücksetzen
    enc_read_pos = 255;                 // Puffer Leseposition zurücksetzen
    encspeed = SPEED;                   // Setze Encoder Speed
#ifdef SOUND
    tonepitch = Tone_C2;                // Tonhöhe festlegen
#endif
}

/**
 * Hole den nächsten Morse Tabellenindex aus dem Morse Encoder Ring Puffer
 *
 * Ausgabe: Morse Tabellenindex [0..MORSESIGNS_MAXINDEX(..127)]
 *          ODER Pausenlänge [129..255] (Pause 1..127 dits)
 *          ODER 128 (0x80), wenn der Ring Puffer leer ist
 *
 */
byte fetchMsIndexFromEncBuffer(void)
{byte msidx;
    if (enc_read_pos != enc_write_pos) {
        enc_read_pos++;
        if (enc_read_pos > MORSEENC_BUFFER_MAXINDEX) {
            enc_read_pos = 0;
        }
        msidx = morseenc_buffer[enc_read_pos];
    }
    else {
        msidx = 0x80;
    }
    return (msidx);
}

/**
 * Morse Encoder
 *
 * Die Funktion encodeMorse() muss alle 1ms aufgerufen werden.
 *
 */
void encodeMorse(void)
{static byte busy_flag, signal_flag, pause_flag, sos_flag, pause_dits;
 static word timer, ms_code; byte msidx;
    Thread_Lock(1);
    timer++;
    if (busy_flag) {                        // Encoder beschäftigt!
        if (signal_flag) {                  // Highpegel (dit/dah) senden
            if (!pause_flag) {              // Warten auf Highpegel Ende
                if (timer >= (encspeed * (ms_code & 3))) {
#ifdef SOUND
                    sound_off();
#endif
#ifdef LIGHTENC
                    Port_WriteBit(PORT_LED2, 0);
#endif
                    Port_WriteBit(MORSEENC_IN, 0);
                    timer = 0;
                    pause_flag = true;
                    ms_code = ms_code >> 2;
                }
            }
            else {                          // Pause nach Highpegel
                if (ms_code) {              // Dit/dah (Highpegel) Ende:
                    if (timer >= encspeed) {
                        signal_flag = false;//  Pause 1 dit
                    }
                }
                else {                      // Morse Zeichen Ende:
                    if (sos_flag) {         //  Falls SOS:
                        ms_code = 0x0001;   //   Füge letztes dit an
                        sos_flag = false;
                    }
                    else {                  //  Falls Zeichen Ende:
                        if (timer >= (encspeed * 3)) {
                            busy_flag = false;// Pause 3 dits
                        }
                    }
                }
            }
        }
        else {                              // Highpegel (dit/dah) Ende
            if (pause_dits) {               // Mache eine längere Pause
                if (timer >= (encspeed * pause_dits)) {
                    busy_flag = false;      // Längere Pause Ende
                }
            }
            else {                          // Starte neuen Highpegel (dit/dah)
#ifdef SOUND
                sound(tonepitch);
#endif
#ifdef LIGHTENC
                Port_WriteBit(PORT_LED2, 1);
#endif
                Port_WriteBit(MORSEENC_IN, 1);
                timer = 0;
                pause_flag = false;
                signal_flag = true;
            }
        }
    }
    else {                                  // Encoder nicht beschäftigt!
        msidx = fetchMsIndexFromEncBuffer();// Hole nächsten Index zum Senden
        if (msidx == 0x80) {                //  aus dem Ring Puffer
            Thread_Lock(0);
            return;                         // Puffer ist leer: Return
        }
        else {
            if (msidx < 0x80) {             // Zu sendendes Morse Zeichen
                ms_code = MsIndex2MorseCode(msidx);
                if (ms_code == 0x5FD5) {
                    sos_flag = true;        // Zeichen ist SOS
                }
                else {
                    sos_flag = false;
                }
                pause_dits = 0;
            }
            else {                          // (msidx > 0x80): Längere Pause
                timer = 0;
                pause_dits = msidx - 0x80;
            }
            signal_flag = false;
            busy_flag = true;               // Zeichen / längere Pause kann
        }                                   //  gesendet werden
    }
    Thread_Lock(0);
}

/**
 * Speichere einen Morse Tabellenindex in den Morse Encoder Ring Puffer
 *
 * Eingabe: Morse Tabellenindex [0..MORSESIGNS_MAXINDEX(..127)]
 *          ODER Pausenlänge [129..255] (Pause 1..127 dits)
 *
 */
void storeMsIndex2EncBuffer(byte msindex)
{
    if (getMorseEncBufferLength() < MORSEENC_BUFFER_MAXINDEX) {
        enc_write_pos++;
        if (enc_write_pos > MORSEENC_BUFFER_MAXINDEX) {
            enc_write_pos = 0;
        }
        morseenc_buffer[enc_write_pos] = msindex;
        morseenc_status = MORSE_BUFFER_OK;       // Encoder Puffer Status ok
    }
    else {
        morseenc_status = MORSE_BUFFER_OVERFLOW; // Encoder Puffer Überlauf
    }
}

/**
 * Schreibe eine zu sendende Pausenlänge in den Morse Encoder Ring Puffer
 *
 * Eingabe: Pausenlänge [1..127 dits] (0,14..18,14 Leerzeichen)
 *
 * Mit dieser Funktion kann man längere Pausen erreichen.
 *   Beispiele:
 *   pauseMorse(7);  ist identisch mit  writeMorseChar(' ');
 *   pauseMorse(14); ist identisch mit  writeMorseString("  ");
 * Die Funktion pauseMorse(len) schreibt nur ein Byte in den Encoder Ring
 * Puffer für eine längere Pause, während writeMorseChar(' ') ein Byte für
 * jedes zu sendende Leerzeichen schreibt. Man sollte writeMorseChar(' ')
 * benutzen, um einzelne Leerzeichen (zwischen Worten) und pauseMorse(len),
 * um längere Pausen zu senden.
 *
 * ACHTUNG: !-------------------------------------------------------------!
 *          ! Die max. Pausenlänge, die man mit dieser Funktion erreichen !
 *          ! kann, beträgt etwa 6 Sekunden!  Damit hängt der Eingabewert !
 *          ! dieser Funktion von encspeed ab!!!                          !
 *          !-------------------------------------------------------------!
 *          !     ==>  Max. Pausenlänge [dits] = 6000 / encspeed  <==     !
 *          !-------------------------------------------------------------!
 *           Für encspeed Werte von 8 (SPEED_MAX) bis 47 beträgt die max.
 *           Pausenlänge 127 dits.  Für encspeed Werte von 48 bis 400
 *           (SPEED_MIN) kann man die max. Anzahl von dits mit der obigen
 *           Formel berechnen.
 *           Bei SPEED_MIN kann man nur für 15 (6000 / 400) dits pausieren!
 *
 */
void pauseMorse(byte len)
{
	if (len) {
		storeMsIndex2EncBuffer(len | 0x80);
	}
}

/**
 * Schreibe ein zu sendendes Zeichen in den Morse Encoder Ring Puffer
 *
 * Eingabe: ASCII Code [0..255]
 *
 */
void writeMorseChar(unsigned char ch)
{static byte sign_flag, chidx; byte msidx;
 static unsigned char last_3ch[4];
	Thread_Lock(1);
	switch (ch) {
		case 32 :						// Leerzeichen   [ASCII Code 32]
			if (sign_flag) {			// Leerzeichen direkt nach einem
				pauseMorse(4);			//  Zeichen (Länge 4 dits)
				if (morseenc_status == MORSE_BUFFER_OK) {
					sign_flag = false;
				}
			}
			else {						// Pause für alle anderen Leerzeichen
				pauseMorse(7);			//  (Länge 7 dits)
			}
			break;
		default :
			// Zeichen für Signal/Sonderzeichen Namen:
			//  ` a..z # % * ^ ~[BLD 126] \[LCD 164]
			if (((ch >= '`') && (ch <= 'z')) || (ch == 35) || (ch == 37)
			 || (ch == 42) || (ch == 94) || (ch == 126) || (ch == 164)) {
				last_3ch[chidx] = ch; last_3ch[chidx + 1] = 0;
				msidx = MsName2MsIndex(last_3ch);// Name in der Morse Tabelle?
				if (morse_error) {
					chidx++;
					if (chidx > 2) {chidx = 0;}
					Thread_Lock(0);
					return;
				}
			}
			else {						// Normale Zeichen
				msidx = a_ms_rt[ch];
			}
			storeMsIndex2EncBuffer(msidx);
			if (morseenc_status == MORSE_BUFFER_OK) {
				sign_flag = true;
			}
	}
	chidx = 0;
	Thread_Lock(0);
}

/**
 * Schreibe einen zu sendenden String in den Morse Encoder Ring Puffer
 *
 * Eingabe: String mit ASCII Text
 *
 */
void writeMorseString(unsigned char str[])
{byte pos;
    pos = 0;
	while (str[pos]) {
		writeMorseChar(str[pos]);
        pos++;
	}
}

/**
 * Ermittele die Anzahl der Indices im Morse Encoder Ring Puffer
 *
 * Ausgabe: Anzahl der Indices (0: Puffer ist leer!)
 *
 */
byte getMorseEncBufferLength(void)
{int enc_posdiff;
	enc_posdiff = enc_write_pos - enc_read_pos;
	if (enc_posdiff < 0) {
		enc_posdiff = enc_posdiff + (MORSEENC_BUFFER_MAXINDEX + 1);
	}
	return (enc_posdiff);
}

/******************************************************************************/
// Nützliche LCD Funktionen:

#ifndef DEBUG
/**
 * Zeige empfangene Morse Zeichen auf dem LCD 16x2 Zeichen als ASCII Text
 *
 */
void writeMorseLCD(void)
{static byte pos; static unsigned char line2[17]; unsigned char ch;
	ch = readMorseChar();
	if (ch) {
    	writeCharLCD(ch);
		line2[pos] = ch;
		pos++;
		if (pos >= 16) {
			pos = 0;
			clearLCD();
			writeStringLCD(line2);		// Kopiere Zeile 2 nach Zeile 1
			setCursorPosLCD(1, 0);		// Zeile 2, Position 1
		}
	}
}

#else

/**
 * Zeige Decoder Debug Informationen auf dem LCD
 *
 * Format: .00 -000 S00
 *         B0 A[XXX] D0
 *
 *   .    -> Dit Länge [ms]
 *   -    -> Dah Länge [ms]
 *   S    -> Decoder Speed (sollte gleich dit Länge sein!) [ms]
 *   B    -> Decoder Pufferlänge (Zeichen noch im Puffer)
 *   A    -> Die 3 zuletzt empfangenen ASCII Zeichen
 *   D    -> Abweichung (Decoder Speed - dit Länge) [ms]
 *
 */
void showDebugInfoLCD(void)
{static unsigned char last_3ch[4]; unsigned char ch;
	ch = readMorseChar();
	if (ch) {
		last_3ch[0] = last_3ch[1]; last_3ch[1] = last_3ch[2];
		last_3ch[2] = ch; last_3ch[3] = 0;
		setCursorPosLCD(0, 0);			// Zeile 1, Position 1
		printLCD(".");
		printIntegerLCD(ditlength);
		printLCD(" -");
		printIntegerLCD(dahlength);
		printLCD(" S");
		printIntegerLCD(decspeed);
		printLCD("   ");
		setCursorPosLCD(1, 0);			// Zeile 2, Position 1
		printLCD("B");
		printIntegerLCD(getMorseDecBufferLength());
		printLCD(" A[");
		writeCharLCD(last_3ch[0]);
		writeCharLCD(last_3ch[1]);
		writeCharLCD(last_3ch[2]);
		printLCD("] D");
		printIntegerLCD(decspeed - ditlength);
		printLCD("   ");
	}
}
#endif

#endif

/******************************************************************************
 * Info
 * ****************************************************************************
 * Changelog:
 * - v. 1.5w 2012 by Dirk
 *
 * ****************************************************************************
 */

/*****************************************************************************/
// EOF


Demos

Mit den drei Demos wird folgende Testsituation hergestellt:

Die RP6Base ist der Morse-Sender, der permanent Morse-Zeichen an die RP6 CONTROL M32 sendet, die hier als Morse-Station dient. Auf dem Display der M32 werden die empfangenen Zeichen angezeigt. Im Terminal Fenster des RP6Loaders (das USB Interface ist an die M32 angeschlossen!) kann man dann gleichzeitig einen Text eingeben, der zeilenweise als Morse-Code gesendet wird. Adressat dieser Texte ist die RP6 CCPRO M128 als Morse-Empfänger. Auf ihrem Display werden die empfangenen Texte angezeigt.

Die Verbindungen der drei Plattformen über den XBUS zeigt diese Tabelle:

RP6Base Verbindung RP6 CONTROL M32 Verbindung RP6 CCPRO M128
Sender EINT1 (XBUS:8) Station SDA (XBUS:12) Empfänger
Sender PINA4---PIND2 Station PINC1---PortD.1 Empfänger

Für jede Demo muss ein eigener Ordner in \RP6BASE_EXAMPLES, \RP6CONTROL_EXAMPLES und \CCPRO_Examples\CompactC angelegt werden. In diesen Ordner wird die jeweilige Demo, für die Base und M32 auch noch make_all.bat, make_clean.bat, makefile (aus einem anderen Example), kopiert.

RP6 Base

makefile:

...
TARGET = RP6Base_Morse_Encoder
...
SRC += $(RP6_LIB_PATH)/RP6base/RP6RobotBaseLib.c
SRC += $(RP6_LIB_PATH)/RP6common/RP6uart.c
SRC += $(RP6_LIB_PATH)/RP6base/RP6BaseMorseLib.c
...

Datei RP6Base_Morse_Encoder.c:

/* 
 * ****************************************************************************
 * RP6 ROBOT SYSTEM - RP6 BASE TESTS
 * ****************************************************************************
 * Test: Morse Encoder Test 1
 * Author(s): Dirk
 * ****************************************************************************
 * Description:
 * This is the Morse encoder test with the RP6 Base Morse Library for the RP6.
 *
 * ****************************************************************************
 * ATTENTION: The 100us timer is used for the Morse decoder and encoder
 *            task! Please do not alter the variable "timer" elsewhere in
 *            your program!
 *
 * ############################################################################
 * 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!
 * ############################################################################
 * ****************************************************************************
 */

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

#include "RP6BaseMorseLib.h"		// The RP6 Base Morse Library.

/*****************************************************************************/
// Defines:

//#define MODIFY_SPEED

//#define PAUSE_TEST

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

uint8_t idx_cnt, name_idx, i, buf_len, old_buf_len; 
uint16_t morse_code;
char sign_name[4];
char morse_sign[10];

/*****************************************************************************/
// Functions:

/**
 * Calculate string length
 *
 */
uint16_t strlength(const char *string)
{uint16_t length = 0;
	while (*string++)
		length++;
	return length;
}

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

int main(void)
{  
	initRobotBase();	// Always call this first! The Processor will not
						// work correctly otherwise.

	// ---------------------------------------
	// Write messages to the Serial Interface
	// (here it is a RP6 text logo):
	writeString_P("\n\n   _______________________\n");
	writeString_P("   \\| RP6  ROBOT SYSTEM |/\n");
	writeString_P("    \\_-_-_-_-_-_-_-_-_-_/\n\n");

	writeString_P("################\n");
	writeString_P("<<RP6     Base>>\n");
	writeString_P(" Morseencoder 1 \n");
	writeString_P("  Version 3.6w  \n");
	writeString_P("################\n\n");
	mSleep(2500);

	// Clear the four Status LEDs:
	setLEDs(0b0000);

/*****************************************************************************/
// Main test program:

	mSleep(7500);							// Wait 7,5s

	initMorseEncoder();						// Init the Morse encoder

	idx_cnt = 255;

#ifndef MODIFY_SPEED
	startStopwatch2();
#endif
	startStopwatch3();

	writeString_P("\nNr  Code  Name  Sign    BufLen St\n");
	while (true) {
		task_MorseEnc();
#ifndef MODIFY_SPEED
		if (getStopwatch2() > 1000) {
#endif
			idx_cnt++;
#ifdef MODIFY_SPEED
			// Modify encoder speed for testing decoders:
			switch(idx_cnt) {

								// SPEED: UP >>> DOWN
				case 5 :  encspeed =  70; break;	// CQ
				case 10 : encspeed =  60; break;	// ^J
				case 15 : encspeed =  50; break;	// /A
				case 20 : encspeed =  40; break;	// Eth
				case 25 : encspeed =  30; break;	// ß
				case 30 : encspeed =  25; break;	// '
				case 35 : encspeed =  20; break;	// -
				case 40 : encspeed =  15; break;	// 2
				case 45 : encspeed =  10; break;	// 7
				case 50 : encspeed =  10; break;	// =
				case 55 : encspeed =   8; break;	// C
				case 60 : encspeed =   8; break;	// H
				case 65 : encspeed =  34; break;	// M
				case 70 : encspeed =  60; break;	// R
				case 75 : encspeed =  70; break;	// W
/*
								// SPEED: DOWN >>> UP
				case 5 :  encspeed =  70; break;	// CQ
				case 10 : encspeed =  80; break;	// ^J
				case 15 : encspeed = 100; break;	// /A
				case 20 : encspeed = 120; break;	// Eth
				case 25 : encspeed = 140; break;	// ß
				case 30 : encspeed = 160; break;	// '
				case 35 : encspeed = 160; break;	// -
				case 40 : encspeed = 200; break;	// 2
				case 45 : encspeed = 240; break;	// 7
				case 50 : encspeed = 300; break;	// =
				case 55 : encspeed = 400; break;	// C
				case 60 : encspeed = 400; break;	// H
				case 65 : encspeed = 290; break;	// M
				case 70 : encspeed = 180; break;	// R
				case 75 : encspeed =  70; break;	// W
*/
			}
#endif
			morse_code = MsIndex2MorseCode(idx_cnt);		// Index -> Code
			MorseCode2MorseSign(morse_sign, morse_code);	// Code  -> Sign
			MorseCode2MsName(sign_name, morse_code);		// Code  -> Name
			task_MorseEnc();
			writeIntegerLength(idx_cnt, DEC, 2);	// Output sign index
			writeString_P("  ");
			task_MorseEnc();
			writeIntegerLength(morse_code, HEX, 4);	// Output Morse code
			writeString_P("  ");
			writeString(sign_name);			// Output sign name
			for (i = 0; i <= (4 - strlength(sign_name)); i++) {
				writeChar(' ');
				task_MorseEnc();
			}
			writeString(morse_sign);		// Output Morse sign
			for (i = 0; i <= (10 - strlength(morse_sign)); i++) {
				writeChar(' ');
				task_MorseEnc();
			}
			name_idx = 0;
			while (sign_name[name_idx]) {
				writeMorseChar(sign_name[name_idx]);
				if (morseenc_status == MORSE_BUFFER_OK) {
					name_idx++;
				}
				task_MorseEnc();
			}
#ifdef PAUSE_TEST
			// Add some spaces (test of the real time spaces function):
			if (idx_cnt == 5) {				// CQ
				writeMorseChar(' ');		// 1 space after CQ
			}
			if (idx_cnt == 10) {			// ^J
				writeMorseChar(' ');
				writeMorseChar(' ');		// 2 spaces after ^J
			}
			if (idx_cnt == 15) {			// /A
				writeMorseChar(' ');
				writeMorseChar(' ');
				writeMorseChar(' ');		// 3 spaces after /A
			}
			if (idx_cnt == 20) {			// Eth
				writeMorseString("    ");	// 4 spaces after Eth
			}
			if (idx_cnt == 25) {			// ß
				writeMorseString("   ");
				pauseMorse(14);				// 5 spaces after ß
			}
#endif
			task_MorseEnc();
			buf_len = getMorseEncBufferLength();
			if (old_buf_len != buf_len) {
				writeIntegerLength(getMorseEncBufferLength(), DEC, 3);
				writeString_P("  ");
				task_MorseEnc();
				writeInteger(morseenc_status, DEC);	// Show encoder status
				old_buf_len = buf_len;
			}
			writeChar('\n');
			if (idx_cnt >= MORSESIGNS_MAXINDEX) {
				writeString_P("BufLen St\n");
				setStopwatch3(0);
				while (getStopwatch3() < 42000) {	// Wait 42s
					task_MorseEnc();
					buf_len = getMorseEncBufferLength();
					if (old_buf_len != buf_len) {
						writeString_P("  ");
						writeIntegerLength(getMorseEncBufferLength(), DEC, 3);
						task_MorseEnc();
						writeString_P("  ");
						writeInteger(morseenc_status, DEC);
						writeChar('\n');
						old_buf_len = buf_len;
					}
				}
				task_MorseEnc();
				writeString_P("Nr  Code  Name  Sign    BufLen St\n");
				idx_cnt = 255;
			}
#ifndef MODIFY_SPEED
			setStopwatch2(0);
		}
#endif
	}

/*****************************************************************************/
// End of main:

	return 0;
}

/******************************************************************************
 * Additional info
 * ****************************************************************************
 * Changelog:
 * - v. 3.6w 2012 by Dirk
 *
 * ****************************************************************************
 */

/*****************************************************************************/

RP6 CONTROL M32

makefile:

...
TARGET = RP6Control_Morse_Station
...
SRC += $(RP6_LIB_PATH)/RP6control/RP6ControlLib.c
SRC += $(RP6_LIB_PATH)/RP6control/RP6ControlMorseLib.c
SRC += $(RP6_LIB_PATH)/RP6common/RP6uart.c
...

Datei RP6Control_Morse_Station.c:

/* 
 * ****************************************************************************
 * RP6 ROBOT SYSTEM - RP6 CONTROL M32 TESTS
 * ****************************************************************************
 * Test: Morse Station 1
 * Author(s): Dirk
 * ****************************************************************************
 * Description:
 * This is the Morse Station test with the RP6 Control Morse Library for the
 * RP6 CONTROL.
 *
 * ****************************************************************************
 * ATTENTION: The 100us timer is used for the Morse decoder and encoder
 *            task! Please do not alter the variable "timer" elsewhere in
 *            your program!
 *
 * ############################################################################
 * 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!
 * ############################################################################
 * ****************************************************************************
 */

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

#include "RP6ControlMorseLib.h"		// The RP6 Control Morse Library.

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

// Reception buffer for the function getInputLine():
char receiveBuffer[UART_RECEIVE_BUFFER_SIZE + 1];

/*****************************************************************************/
// Functions:

/**
 * Convert lower case to upper case letters and vice versa
 *
 * Input:  ASCII code [0..255]
 * Output: ASCII code, lower case changed to upper case letters and vice versa
 *
 */
uint8_t ChangeCharCase(uint8_t ch)
{uint8_t chcc;
	chcc = ch;
	if ((ch >= 97) && (ch <= 122)) {
		chcc -= 32;
		return (chcc);						// LC -> UC
	}
	if ((ch >= 224) && (ch <= 254) && (ch != 247)) {
		chcc -= 32;
		return (chcc);						// LC -> UC
	}
	if ((ch >= 65) && (ch <= 90)) {
		chcc += 32;
		return (chcc);						// UC -> LC
	}
	if ((ch >= 192) && (ch <= 222) && (ch != 215)) {
		chcc += 32;
		return (chcc);						// UC -> LC
	}
	return (chcc);
}

/**
 * Get chars of an input line from the UART.
 *
 * Returns 0 (false), if the UART receive buffer is empty
 * OR a character of the input line has been received.
 * Returns 1, if the whole input line has been received
 * (with a "new line" character at the end).
 * Returns 2, if the UART receive buffer overflows.
 * The input line is stored in the receiveBuffer array.
 *
 */
uint8_t getInputLine(void)
{static uint8_t buffer_pos = 0;
	if(getBufferLength()) {							
		receiveBuffer[buffer_pos] = ChangeCharCase(readChar());
		if(receiveBuffer[buffer_pos] == '\n') {
			receiveBuffer[buffer_pos] = '\0';
			buffer_pos = 0;
			return 1;
		}
		else if(buffer_pos >= UART_RECEIVE_BUFFER_SIZE) {									
			receiveBuffer[UART_RECEIVE_BUFFER_SIZE] = '\0';	
			buffer_pos = 0;
			return 2;
		}
		buffer_pos++;
	}
	return 0;
}

/**
 * Task Morse Station
 *
 */
void task_MorseStation(void)
{
	task_MorseEnc();						// Morse encoder task
	if (getInputLine()) {
		writeMorseString(receiveBuffer);
	}
	task_MorseDec();						// Morse decoder task
	if (getStopwatch1() > 70) {

#ifndef DEBUG
		writeMorseLCD();
#else
		showDebugInfoLCD();
#endif
		setStopwatch1(0);
	}
}

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

int main(void)
{  
	initRP6Control();	// Always call this first! The Processor will not
						// work correctly otherwise. 

	initLCD();			// Initialize the LC-Display (LCD)
						// Always call this before using the LCD!

	// Write some text messages to the LCD:
	showScreenLCD("################", "################");
	mSleep(1500);
	showScreenLCD("<<RP6  Control>>", "<<LC - DISPLAY>>");
	mSleep(2500); 
	showScreenLCD(" Morse Station 1", "  Version 3.6w  ");
	mSleep(2500);
	clearLCD(); // Clear the whole LCD Screen

	writeString_P("################\n");
	writeString_P("<<RP6  Control>>\n");
	writeString_P(" Morse Station 1\n");
	writeString_P("  Version 3.6w  \n");
	writeString_P("################\n\n");
	writeString_P("Normal text:              Only lower case letters!\n");
	writeString_P("                          Max. 30 chars per line!!\n");
	writeString_P("Prosigns & special chars: Only UPPER CASE LETTERS!\n\n");
	writeString_P("Examples: hello world!    <- This is a normal text\n");
	writeString_P("          CQ SOS          <- Here you see PROSIGNS\n\n");

	// Clear the four Status LEDs:
	setLEDs(0b0000);

/*****************************************************************************/
// Main test program:

	initMorseDecoder();						// Init the Morse decoder
	initMorseEncoder();						// Init the Morse encoder

	startStopwatch1();						// Used for the test program

	clearReceptionBuffer();					// Clear UART reception buffer

	while (true) {
		task_MorseStation();				// Morse station task
		// Other tasks in the main loop (max. 3ms @ 750 CpM):
		mSleep(1);
	}

/*****************************************************************************/
// End of main:

	return 0;
}

/******************************************************************************
 * Additional info
 * ****************************************************************************
 * Changelog:
 * - v. 3.6w 2012 by Dirk
 *
 * ****************************************************************************
 */

/*****************************************************************************/

RP6 CCPRO M128

Datei RP6_Morse_Decoder.cc:

/*******************************************************************************
 * RP6 C-Control PRO M128 Erweiterungsmodul
 * ----------------------------------------------------------------------------
 * RP6_Morse_Decoder Testprogramm 1 - CompactC
 * ----------------------------------------------------------------------------
 * RP6_Morse_Decoder: Morse-Decoder
 * Mega128: Morse-Decoder-Eingang PD1 (PortD.1, RP6: SDA)
 * Der Morse-Decoder-Eingang kann in RP6MorseCClib.cc geändert werden.
 * erforderliche Library: IntFunc_Lib.cc und neue RP6MorseCClib.cc (v. 1.xw).
 *
 * Am Morse-Decoder-Eingang wird das Morse Signal eingespeist.
 * Auf dem LCD-Display werden die decodierten Morse Zeichen angezeigt.
 * Die LED1 blinkt im Takt der Morse Signale.
 *
 * ANMERKUNG: Die Zeile mit dem Kommentar "! Workaround Bug T1 !"
 *            muss entfernt werden, sobald der Fehler der Funktion
 *            Timer_T1Time() in einer neuen Version der IDE (> 2.1)
 *            beseitigt wurde!
 *
 * Hinweis:
 * Für allgemeine Programmierhinweise zur CCPRO schauen Sie sich bitte die
 * CCPRO Dokumentation und die zugehörigen Beispielprogramme an!
 * Es sei auch nochmals darauf hingewiesen, dass die normalen Beispielprogramme
 * für die CCPRO nur zum Teil direkt auf dem RP6-CCPRO Modul laufen.
 * Die Anschlussbelegung ist natürlich komplett anders als auf dem
 * C-Control Application Board. Auch die LCD Ansteuerung ist leicht anders,
 * da hier noch zusätzliche LEDs mit an dem Schieberegister angeschlossen sind.
 * --> Die C-Control Beispielprogramme müssen ein klein wenig angepasst
 * werden bevor sie auf diesem Modul laufen können!
 *
 * *****************************************************************************
 * Der Roboter bewegt sich in diesem Beispielprogramm NICHT und kann
 * am Rechner angeschlossen bleiben!
 ******************************************************************************/

// WICHTIG: Immer die RP6CCLib mit einbinden:
#include "../../RP6CCLib/RP6CCLib.cc"

// Die neue RP6MorseCCLib einbinden:
#include "../../RP6CCLib/RP6MorseCClib.cc"

int irqcnt;                             // globale Variablendeklaration

void main(void)
{
    // WICHTIG! Immer als erstes aufrufen:
	RP6_CCPRO_Init(); // Auf Startsignal warten, LCD und andere Dinge initialisieren !

    // ------------------------------------------------------

    // Zwei Zeilen Text mit dem LCD anzeigen:
    showScreenLCD("RP6 CCPRO M128", "RP6 Morsedecoder");

    // Zweimal piepsen:
    beep(200, 300, 100);   // Format: beep (<tonhöhe>, <dauer>, <pause>)
    beep(100, 100, 100);

    // Text über serielle Schnittstelle ausgeben:
    newline(); // Neue Zeile
    println("   ________________________");
    println("   \\| RP6  ROBOT SYSTEM |/");
    println("    \\_-_-_-_-_-_-_-_-_-_/ ");
    newline();
    println("    Let's go!  ");
    newline();

    // 2 Sekunden Pause:
    AbsDelay(2000);

    // ------------------------------------------------------
    // Morse-Decoder-Hauptprogramm:

    Port_WriteBit(PORT_LED1, 0);        // LED1 aus
    clearLCD();                         // Display löschen

    initMorseDecoder();                 // Initialisierung des Decoders
    Irq_SetVect(INT_TIM1CMPA, INT_1ms); // ISR definieren
    Timer_T1Time(14746, PS_1);          // Timer1: 1ms Interrupt
    DirAcc_Write(0x4e,8|PS_1);          // ! Workaround Bug T1 !

    while (1)                           // Endlosschleife
    {
#ifndef DEBUG
		writeMorseLCD();
#else
		showDebugInfoLCD();
#endif
		// Andere Aufgaben in der Hauptschleife:
        AbsDelay(1);
    }
}

//------------------------------------------------------------------------------
// Interrupt Routine
//
void INT_1ms(void)
{
	decodeMorse();      				// Morse Decoder

    irqcnt = Irq_GetCount(INT_TIM1CMPA);// Interrupt Request Counter
}

//------------------------------------------------------------------------------


Optionen

Direkteingabe von Morse-Code

Morse-Code kann mit einer Morsetaste eingegeben werden. Bei jedem Drücken der Taste wird z.B. ein Kontakt gschlossen.

Typische Morsetaste (Junker) zum Geben von Morse-Code:

RP6 Morse-Taste

Eine Alternative zur Morsetaste ist der Morse-Keyer (oder Elbug oder Wabbler). Er unterscheidet sich von der Morsetaste durch das Bauprinzip: Er wird mit ein oder zwei Tasten ("Paddles") gebaut. Mit einer Taste wird z.B. von links der Punkt, von rechts der Strich gegeben. Mit zwei Tasten kann man je eine Taste für Punkte bzw. Striche nutzen,- zudem lassen sich durch Drücken beider Tasten gleichzeitig Punkt-Strich-Kombinationen geben. Der Vorteil der Keyer gegenüber den einfachen Morsetasten besteht in der wesentlich höheren Geschwindigkeit, mit der Morse-Code gegeben werden kann. Morsetasten und Keyer werden auch als "elektronische" Varianten gebaut. Sie können z.B. ungenaue Gebeweisen des Benutzers ausgleichen oder Texte speichern.

Wenn man das Morsen üben will, kann man an einen Morse-Decoder-Eingang eine Taste anschließen. Sie sollte keinen Druckpunkt haben und eine Finger-geeignete Druckfläche. Der Anschluß an den uC-Eingang erfolgt so, dass beim Drücken der Taste High-Pegel am Eingang anliegt. Bei einem Schließer (Kontakt geschlossen beim Drücken) wird die Taste zwischen VDD und dem uC-Eingang angeschlossen, zusätzlich noch ein Pulldown-Widerstand gegen GND. Die Library und die Decoder-Demo können so unverändert benutzt werden. Soll oder muss die Morsetaste gegen GND angeschlossen werden, ist dies auch möglich: Man aktiviert einfach INVERTDEC im Header der jeweiligen Library.

Nicht optimal,- aber man könnte es ja probieren: Die beiden Bumper der RP6Base könnten einen Keyer darstellen! Links gedrückt: Punkt! Rechts gedrückt: Strich! Dazu müßte man ein Programm schreiben, das die Tastendrücke (d.h. Punkte und Striche) zunächst speichert und dann mit Hilfe des Morse-Encoders in die korrekten Punkt-/Strich-/Pausenlängen des Morse-Codes umsetzt. Es gibt viel für euch zu tun ...

Morse-Code mit RP6 IRCOMM senden/empfangen

Die RP6Base verfügt ja über das IRCOMM, d.h. eine Möglichkeit, Informationen über Infrarot zu senden und zu empfangen. Mit dem IRCOMM kann man auch Morse-Code übertragen.

Für den Morse-IR-Sender aktiviert man im Header der RP6Base Morse Library IRCOMMENC. Damit sendet der Morse-Encoder Morse-Code mit den IRCOMM LEDs. Bitte dabei beachten, dass das ACS und die IRCOMM Sendefunktion IRCOMM_sendRC5() nicht gleichzeitig benutzt werden können! Man sollte deshalb vor dem Senden von Morse-Code mit den IRCOMM LEDs das ACS deaktivieren mit der Funktion disableACS(). Wenn kein Morse-Code mehr gesendet werden soll, kann das ACS mit enableACS() wieder aktiviert werden.

Wenn der Morse-IR-Empfänger genutzt werden soll, wählt man in der RP6Base Morse Library den "IR receiver" (IR-Empfänger an PINB2) als Eingang für den Morse-Decoder und aktiviert im Header der Library INVERTDEC. Auch für den Morse-IR-Empfang sollte man das ACS mit der Funktion disableACS() deaktivieren.

Da ich nur einen RP6 habe, mußte ich die Tests der IR-Funktion mit einer "Morse IR-Station" für die RP6Base machen. Das heißt: Der RP6 sendet endlos Morse-Code mit seinen IRCOMM LEDs, parallel erfolgt der Empfang der IR-Signale, deren Decodierung und Anzeige im Terminal.

makefile:

...
TARGET = RP6Base_Morse_IR-Station
...
SRC += $(RP6_LIB_PATH)/RP6base/RP6RobotBaseLib.c
SRC += $(RP6_LIB_PATH)/RP6common/RP6uart.c
SRC += $(RP6_LIB_PATH)/RP6base/RP6BaseMorseLib.c
...

Datei RP6Base_Morse_IR-Station.c:

/* 
 * ****************************************************************************
 * RP6 ROBOT SYSTEM - RP6 BASE TESTS
 * ****************************************************************************
 * Test: Morse IR-Station Test 1
 * Author(s): Dirk
 * ****************************************************************************
 * Description:
 * This is the Morse IR-Station test with the RP6 Base Morse Library for
 * the RP6.
 *
 * ****************************************************************************
 * ATTENTION: The 100us timer is used for the Morse decoder and encoder
 *            task! Please do not alter the variable "timer" elsewhere in
 *            your program!
 *
 * ############################################################################
 * 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!
 * ############################################################################
 * ****************************************************************************
 */

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

#include "RP6BaseMorseLib.h"		// The RP6 Base Morse Library.
// Changes in the RP6BaseMorseLib.h:
//  #define INVERTDEC
//  #define IRCOMMENC
//  //#define LIGHTDEC
//  //#define LIGHTENC
// Changes in the RP6BaseMorseLib.c:
//  #define MORSEDEC_PORT	PORTB
//  #define MORSEDEC_DDR	DDRB
//  #define MORSEDEC_PIN	PINB
//  #define MORSEDEC_IN		ACS

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

uint8_t idx_cnt = 26; 

/*****************************************************************************/
// Functions:

/**
 * Task Morse IR-Station
 *
 */
void task_MorseIRStation(void)
{
	task_MorseEnc();						// Morse encoder task
	storeMsIndex2EncBuffer(idx_cnt);
	if (morseenc_status == MORSE_BUFFER_OK) {
		idx_cnt++;
		if (idx_cnt > 79) {idx_cnt = 26;}
	}

	task_MorseDec();						// Morse decoder task
	if (getStopwatch1() > 70) {

#ifndef DEBUG
		writeMorse();
#else
		showDebugInfo();
#endif
		setStopwatch1(0);
	}
}

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

int main(void)
{  
	initRobotBase();	// Always call this first! The Processor will not
						// work correctly otherwise.

	// ---------------------------------------
	// Write messages to the Serial Interface
	// (here it is a RP6 text logo):
	writeString_P("\n\n   _______________________\n");
	writeString_P("   \\| RP6  ROBOT SYSTEM |/\n");
	writeString_P("    \\_-_-_-_-_-_-_-_-_-_/\n\n");

	writeString_P("################\n");
	writeString_P("<<RP6     Base>>\n");
	writeString_P("Morse-IR-Station\n");
	writeString_P("  Version 3.6w  \n");
	writeString_P("################\n\n");
	mSleep(2500);

	// Clear the four Status LEDs:
	setLEDs(0b0000);

/*****************************************************************************/
// Main test program:

	disableACS();							// ACS off
	powerON();								// Only for IR receiver
	initMorseDecoder();						// Init the Morse decoder
	initMorseEncoder();						// Init the Morse encoder

	startStopwatch1();						// Used for the test program

	while (true) {
		task_MorseIRStation();				// Morse IR-Station task
		// Other tasks in the main loop (max. 3ms @ 750 CpM):
		mSleep(1);
	}

/*****************************************************************************/
// End of main:

	return 0;
}

/******************************************************************************
 * Additional info
 * ****************************************************************************
 * Changelog:
 * - v. 3.6w 2012 by Dirk
 *
 * ****************************************************************************
 */

/*****************************************************************************/

Diese Demo sendet Morse-Code mit den IRCOMM LEDs der RP6Base und empfängt ihn sofort wieder mit dem IR-Empfänger (TSOP34836). Die Zeichen werden auf dem Terminal zeilenweise angezeigt.

Rundfunkempfang von Morse-Code

Es gibt nur noch wenige Amateurfunk-Stationen, die regelmäßig Morse-Code senden. In Deutschland, aber auch weltweit kann man ungerichtete Funkfeuer (NDBs) amplitudenmoduliert im Langwellenbereich empfangen. Der Frequenzbereich der NDBs liegt in Deutschland zwischen 200 kHz und 526,5 kHz; international zwischen 190 kHz und 1750 kHz. In der Liste der NDBs kann man nachsehen, ob es ein NDB in der Nähe des eigenen Wohnortes gibt. Mit einem Langwellen-Empfänger (bzw. Radio mit LW-Bereich) kann man meist so ein NDB in der Nähe empfangen. Es sendet in regelmäßigen Abständen seine Kennung (Rufzeichen) als Morse-Code. Der nachfolgende Schaltplan vom ham radio.cc zeigt eine Schaltung mit dem PLL-Tondecoder-IC NE567. Mit dieser Schaltung (aufgebaut z.B. auf einer Experimentierplatine) kann man die "Morse-Töne" aus dem Lautsprecher des Radios so aufbereiten, dass sie durch einen Eingangspin eines uCs ausgewertet werden können.

Morse Decoder Front-end Schaltplan, veröffentlicht von ham radio.cc:

RP6 Morse-Decoder Schaltplan

Wenn ihr in einer Region lebt, wo kein NDB zu empfangen ist: Macht nichts. Die RP6 CONTROL M32 oder CCPRO M128 kann ein NDB plus Langwellen-Empfänger "voll" ersetzen. Wenn man auf einer dieser Plattformen einen Morse-Sender programmiert, der endlos ein Rufzeichen "piepst" (SOUND in der Library aktivieren!), dann kann man mit der oben gezeigten Schaltung und einem daran angeschlossenen Morse-Empfänger (z.B. CCPRO M128 mit der o.g. Demo) fast den selben Effekt erreichen.

Morse-Funkstrecke

Wenn es einfach und kostengünstig sein soll, dann könnte man z.B. dieses 433 MHz Sende-Empfänger-Modulset oder das 868 MHz Sende-Empfänger-Modulset verwenden. Die Reichweite des 868 MHz Typs ist mit 200 m deutlich höher als die des 433 MHz Typs (30 m).

So könnte der Schaltplan mit diesem Sende-Empfänger-Set aussehen:

RP6 Funk868MHz Schaltplan


Im oberen Teil der Schaltung findet sich der Sender (868-TX) zusammen mit zwei Transistoren (BC556B, BC546B), über die die Stromversorgung von Sender und Empfänger geschaltet werden kann. Wer das nicht braucht, kann diese beiden Transistoren weglassen und JP1 schließen. Damit ist die Stromversorgung dauerhaft eingeschaltet. Mit einer grünen LED (abschaltbar durch Öffnen von JP3) kann angezeigt werden, ob die Stromversorgung von Sender und Empfänger eingeschaltet ist.

Im unteren Teil des Schaltplans ist der Empfänger (868-RX2) erkennbar. Sein Ausgang liegt über eine Treiberstufe (2x BC546B) an einem uC-Eingang. Vorgesehen ist der Anschluß von Sender und Empfänger über Jumper entweder an die RP6Base (XBUS: IT1, SCL, SDA) ODER an die CONTROL M32 (I/O-Stecker: PC5..7). Natürlich kann man auch andere Verbindungen zu den uCs herstellen.

Funktion RP6Base CONTROL M32
Power E_INT1 IO_PC7
Senden SCL IO_PC5
Empfangen SDA IO_PC6

Hier die Stückliste!

Man braucht folgende Bauteile (42,34€ ohne Versand CONRAD):

Anzahl Bestell-Nr. Bauteil-Bezeichnung:
1 191537 RP6 Experimentierplatine
1 190939 Sende-Empfänger-Modulset 868 MHz ODER
1 130428 Sende-Empfänger-Modulset 433 MHz
3 155004 Transistor BC 546B
1 155080 Transistor BC 556B
1 145971 LED grün 3mm low-current
1 403270 1/4-Watt-Kohleschichtwiderstand 1,5 kOhm
1 403296 1/4-Watt-Kohleschichtwiderstand 2,2 kOhm
1 403318 1/4-Watt-Kohleschichtwiderstand 3,3 kOhm
2 403334 1/4-Watt-Kohleschichtwiderstand 4,7 kOhm
1 403377 1/4-Watt-Kohleschichtwiderstand 10 kOhm
1 403415 1/4-Watt-Kohleschichtwiderstand 22 kOhm
1 460532 Elektrolyt-Kondensator 10 uF 35 V
2 453099 Keramik-Kondensator 0,1 uF 50 V
1 451666 Keramischer Scheibenkondensator 47 pF 100 V
1 741119 1-reihige Stiftleiste RM 2,54mm (36-polig)
1 741252 2-reihige Stiftleiste RM 2,54mm (2x25-polig)
1 742902 Codierbrücken Set (15 Stk.)

Falls gewünscht, kann man zum sicheren Anschluß der Funk-Platine an den I/O-Wannen-Stecker der RP6 CONTROL M32 noch folgende Teile bei Fa. Reichelt bestellen:

Anzahl Bestell-Nr. Bauteil-Bezeichnung:
1 WSL 10G Wannenstecker 10-polig gerade RM 2,54
2 PFL 10 Pfostensteckverbinder 10-polig f. Flachbandkabel
1 AWG 28-10G 3M Flachbandkabel grau 10-polig

Wenn man nur in eine Richtung "funken" möchte, muss man den Sender und Empfänger natürlich getrennt aufbauen.

Wenn man die Funkstrecke bidirektional (d.h. in beide Richtungen) betreiben möchte, muss man die oben gezeigte Schaltung zweimal aufbauen! Dann kann man zwar in beide Richtungen senden, aber nicht gleichzeitig, da die 868 MHz Module ja auf der selben Frequenz senden/empfangen. Möchte man gleichzeitig in beide Richtungen "funken", könnte man je ein Sender-Empfänger-Modulset mit 433 MHz und 868 MHz kaufen: Auf einer Experimentierplatine baut man dann z.B. den 433 MHz Sender zusammen mit dem 868 MHz Empfänger auf und auf der anderen Platine genau umgekehrt. Damit findet das "Funken" in eine Richtung mit 433 MHz, in die andere mit 868 MHz statt.

Auf der RP6 Experimentierplatine sieht eine der beiden Schaltungen dann z.B. so aus:

RP6 Funk868MHz

Ich hab's probiert: 200m sind bei 868 MHz locker drin, im Freifeld auch evtl. noch mehr. Welche Geschwindigkeit (BpM) ich dabei erreicht habe, bleibt mein Geheimnis ... ;-)

Viel Erfolg beim Löten!

Weiteres

... kann gerne ergänzt werden ...


Erfahrungsberichte, Weiterentwicklung

... kann gerne ergänzt werden ...


Siehe auch


Weblinks


Autoren

--Dirk 14:10, 22. Apr 2012 (CET)


LiFePO4 Speicher Test