Aus RN-Wissen.de
Wechseln zu: Navigation, Suche
Laderegler Test Tueftler Seite

(On-Board-Sensoren)
(Erweiterbare Sensoren)
Zeile 86: Zeile 86:
 
* DCF77-Funkuhrempfänger
 
* DCF77-Funkuhrempfänger
 
* GPS-Modul Navilock NL-552ETTL via UART  
 
* GPS-Modul Navilock NL-552ETTL via UART  
* Aufsteckbarer 2D-Kompass
+
* Aufsteckbarer 3D-Kompass "HDMM01" (Kompass mit 3fach-Beschleunigungssensor)
* Oder aufsteckbarer 9D-Kompass
+
* Oder aufsteckbarer 9D-Kompass "MinIMU-9 v2" (Kompass mit 3fach-Beschleunigungssensor und 3fach-Gyro)
* Aufsteckbarer Luftfeuchtigkeit- und Temperatur-Sensor
+
* Aufsteckbarer Luftfeuchtigkeit- und Temperatur-Sensor "HYT 221"
* Aufsteckbarer Luftdrucksensor
+
* Aufsteckbarer Luftdrucksensor "BMP085"
* Vier weitere SRF02
+
* Vier weitere Ultraschall-Abstandssensoren (z.B. "SRF02" )
 
* SnakeVision-Modul
 
* SnakeVision-Modul
  

Version vom 9. März 2013, 14:41 Uhr

Inhaltsverzeichnis

RP6 Multi IO Erweiterungsmodul

Das RP6-Multi-IO Erweiterungsmodul besteht aus fünf Platinen. Eine Hauptplatine, im üblichen RP6-Layout, enthält eine Vielzahl möglicher Sensoren und Aktoren wie Temperatursensor, Stromsensor, Berührungssensor, Servo-Ansteuerung, LEDs, Buzzer etc. An sie können die vier weiteren Platinen angesteckt werden. Diese sind eine Bumper-Platine zum Anbringen am Heck des RP6, eine Radio-Platine, eine Platine mit vier Tastern und eine mit einem Liniensensor-Array von fünf CNY70-Reflexoptokopplern.

Diese fünf Platinen können bei fabqu ( http://www.roboternetz.de/community/members/47148-fabqu oder fabqu@web.de ) bestellt werden. Sie sind mit Lötstopplack (schwarz) sowie beidseitig mit einem Bestückungsdruck (in weiß) versehen. Sie sind nicht aufgebaut, aber fabqu bietet an, die schwer einzulötenden SMD-ICs (und bei Bedarf auch alle anderen SMD-Bauteile) in einer einmaligen Sammelbestellung zu bestellen und einzulöten.


Features des Multi-IO-Moduls

On-Board-Sensoren

  • Externe Stromversorgung
    • Bis zu 10 Volt
    • Verpolungs- und kurzschlussicher
    • Netzgerät möglich
    • 5V- und 3,3V-Regler on Board
  • USRBUS
    • Pinherausführungen
  • Alle 14 Pins stehen zur freien Verfügung
  • XBUS
    • Nutzung des externen Akkus für RP6-Basiseinheit möglich
    • Nutzung des Akkus der RP6-Basiseinheit möglich
    • Pinherausführungen für I2C (5V- und 3,3V-Pegel) und Int1 (5V- und 3,3V-Pegel)
  • Temperatur-Sensor
    • TCN75 (gleicher Sensor ist bei M128 verbaut)
    • Adressbits A0 und A2 einstellbar
    • Sensor ist durch Jumper deaktivierbar
  • 16-fach PWM-Modulator via I2C PCA9685
    • schaltet 8 Servos
    • schaltet 4 LEDs
    • schaltet Versorgungsspannung der Servomotoren zu/ab
    • 3 freie Pins
    • Der PCA9685 ist direkt neben dem USRBUS angebracht, um hier eine Fortführung der Daten zu ermöglichen
  • Servo-Lib für RP6-Control-M32
  • Spannungsversorgung Servos
    • Eigene Spannungsversorgung für alle Servomotoren
    • Abgesichert durch 470uF-Kondensator
    • Verwendung drei verschiedener 5V-Regler möglich (7805, LT1084CP-5 oder LT1084CT-5)
    • Bei Verwendung eines LT…-5 ist die Spannung durch Poti im Bereich 5..7,5V einstellbar
  • Strom-Spannungs-Überwachung
    • LTC2990 überwacht via I2C Batteriespannung, Servospannung, Stromverbrauch der gesamten Platine sowie eigene Temperatur
    • Analoge Messung der 3,3V-Spannung
  • Echtzeit-Uhr DS1307
    • Via I2C
    • 5V sind durch Jumper deaktivierbar
    • StandBy durch 3V-Knopfzelle (20xx-Reihe) möglich
  • Berührungssensor
    • Timerbaustein NE555 registriert Berührung einer Antenne
    • Via ADC
  • Buzzer
  • Spannungsteiler
    • Vorbereitet
    • Anschlussmöglichkeit vieler eigener Sensoren
  • I2C-EEPROM
  • Anschlussmöglichkeit der IO- und ADC-Wannenstecker von RP6-Control-M32, RP6-CCPRO-M128 und M256-WiFi-Platine

Weitere Platinen

  • Jede hier beschriebene Platine besitzt einen vorkonfektionierten Anschluss auf der Hauptplatine
  • Taster-Board
    • Vier Taster
    • Widerstandskaskade für Messung mit einem ADC
  • Bumper-Board
    • Zwei Bumper mit LEDs
    • Zwei durch Transistor abschaltbare Sharp-GP2Dxx- oder Radar-Abstandssensoren (analog) oder zwei SRF02-Sensoren (digital via I2C)
  • Liniensucher-Board für Liniensensor
    • Bis zu 5 CNY70-Reflexoptokoppler
    • Durch Transistor abschaltbar
    • LED zeigt Status
    • Durch Jumper Wahl zwischen drei oder fünf CNY70-Reflexoptokopplern
  • Radio-Board
    • SI4735 digitaler Radio-Empfänger
    • TDA7050 Verstärker mit Stereo-Kopfhörerbuchse
    • Potentiometer zur Lautstärkeregulierung
    • AM und FM möglich
  • Anschlüsse
    • Taster-Board kann an Hauptplatine angesteckt oder aufgelötet werden
    • Anschlüsse für Bumper- und Liniensensor-Board

Erweiterbare Sensoren

  • DCF77-Funkuhrempfänger
  • GPS-Modul Navilock NL-552ETTL via UART
  • Aufsteckbarer 3D-Kompass "HDMM01" (Kompass mit 3fach-Beschleunigungssensor)
  • Oder aufsteckbarer 9D-Kompass "MinIMU-9 v2" (Kompass mit 3fach-Beschleunigungssensor und 3fach-Gyro)
  • Aufsteckbarer Luftfeuchtigkeit- und Temperatur-Sensor "HYT 221"
  • Aufsteckbarer Luftdrucksensor "BMP085"
  • Vier weitere Ultraschall-Abstandssensoren (z.B. "SRF02" )
  • SnakeVision-Modul

Software

Die Software wird von Dirk erstellt. Diese Bibliotheken sind natürlich nur ein Vorschlag und sollen nur zur Anregung eigener Projekte und eigener Bibliotheken dienen. Es ist geplant, eine Bibliothek mit allen fest installierten Sensoren und Aktoren aufzubauen. Darüber hinaus soll sich eine weitere Bibliothek mit Umwelt-Fragen beschäftigen (Luftdruck, Luftfeuchtigkeit, Temperatur) sowie eine mit den Sensoren für Lageerkennung (GPS, 2D- oder 9D-Kompass). Diese Bibliotheken liegen – wie das gesamte Projekt – als Open Source vor und werden den Usern zugänglich gemacht.

RP6 M256 WIFI

Die M256-WiFi-Platine (= "M256") kann über den I2C-Bus alle I2C-Sensoren und I2C-Aktoren ansteuern und hat mit ihren vielen freien Ressourcen (Portpins) natürlich optimale Voraussetzungen, um die weiteren Funktionen der Multi IO Platine zu nutzen. Dazu wird sie (wenn alle Funktionen gleichzeitig genutzt werden sollen) mit drei Steckverbindungen angeschlossen:

  • IO-Mxxx <-> IO_PWM/T2/T3
  • ADC-Mxxx <-> ADC_IO2/CMP
  • ADC-M256 <-> ADC_IO1

Dadurch ergeben sich umfangreiche Möglichkeiten, die Sensoren der Multi IO Platine auszulesen und Aktoren zu schalten. Die folgenden 3 Tabellen zeigen die Verbindungen:

Stecker IO-Mxxx:

Stecker-Pin M256-Port M256-Funktion Multi IO-Funktion I/O
1 PE7 ICP3 DCF77 I
2 GND
3 PE6 T3 SHARPS_PWR O
4 PE5 OC3C SNAKE_SWITCH O
5 PB4 OC2A BUZZER O
6 PK7 ADC15 (TX *)
7 PH6 OC2B SNAKE_KEY / (TX *) I
8 PK6 ADC14 (RX *)
9 PE4 OC3B LFS_PWR O
10 VDD

Zu *) UART nicht am IO_PWM/Tx/Ty Stecker der M256 vorhanden!

Stecker ADC-Mxxx:

Stecker-Pin M256-Port M256-Funktion Multi IO-Funktion I/O
1 PK0 ADC8 TOUCH / LFS_L I
2 GND
3 PK1 ADC9 3V3 / LFS_M I
4 PE3 OC3A/AIN1 BUMPER_L I/O *
5 PK2 ADC10 LFS_R I
6 GND
7 PK3 ADC11 BUTTONS I
8 PE2 XCK0/AIN0 BUMPER_R I/O *
9 PK4 ADC12 3V3 alt.1 I
10 VDD

Zu *) Eingang für Bumper-Taster, Ausgang für Bumper-LED!

Stecker ADC-M256:

Stecker-Pin M256-Port M256-Funktion Multi IO-Funktion I/O
1 PF1 ADC1 LDR1 I
2 GND GND
3 PF0 ADC0 LDR2 I
4 VDD
5 PF2 ADC2 LFS_R1 I
6 GND GND
7 PF3 ADC3 LFS_L1 I
8 GND GND
9 PF4 ADC4 SHARP_L I
10 GND GND
11 PF5 ADC5 SHARP_R I
12 PF6 ADC6 SNAKE_R I
13 PF7 ADC7 SNAKE_L I
14 GND GND

Multi IO Projekt Library

Diese Avr-gcc Library für das Multi IO Projekt Board (= "MultiIO") geht von folgenden Voraussetzungen aus:

  • Die RP6v2 M256 WiFi Platine (= "M256") wird für die Ansteuerung der MultiIO benutzt (1).
  • Die M256 ist der I2C-Bus Master.
  • Die I2C-Bus Geschwindigkeit beträgt 100 kHz.
  • Alle Hardware-Komponenten der MultiIO sind aufgebaut (2).
  • Alle Jumper auf der MultiIO sind in ihrer Standardstellung (3).
  • Die MultiIO und die M256 sind mit dem XBUS des RP6-Systems 1:1 verbunden.
  • Der Wannenstecker IO_Mxxx der MultiIO ist mit dem Wannenstecker IO_PWM/T2/T3 der M256 1:1 verbunden.
  • Der Wannenstecker ADC_Mxxx der MultiIO ist mit dem Wannenstecker ADC_IO2/CMP der M256 1:1 verbunden.
  • Der Wannenstecker ADC_M256 der MultiIO ist mit dem Wannenstecker ADC_IO1 der M256 1:1 verbunden.
Zu (1): Dies soll nur der 1. Schritt sein. Natürlich ist die MultiIO auch
        an die RP6 BASE, die M32 und die
        M128 des RP6-Systems und an praktisch
        alle anderen Microcontroller-Plattformen anschließbar!
Zu (2): Wenn nicht alle Komponenten aufgebaut sind, sind die zugehörigen
        Funktionen natürlich nicht funktionsfähig und können nicht benutzt
        werden.
Zu (3): Siehe Hardware-Teil!

Die Library (Software-Bibliothek) besteht aus drei Teilen:

Configuration Header

Datei RP6M256_MultiIO.h:

/* 
 * ****************************************************************************
 * RP6 ROBOT SYSTEM - RP6 CONTROL M256 Examples
 * ****************************************************************************
 * Example: RP6M256 MultiIO Library
 * Author(s): Dirk
 * ****************************************************************************
 * Description:
 * Configuration header file for new MultiIO Project Board library.
 *
 * ****************************************************************************
 */

#ifndef RP6M256_MULTIIO_H
#define RP6M256_MULTIIO_H


/*****************************************************************************/
// MultiIO hardwired components:
// - I2C Voltage & Current Sensor (LTC2990)
// - I2C Real Time Clock (RTC DS1307Z)
// - I2C Temperature Sensor (TCN75A)
// - I2C Servo Controller (PCA9685)
// - I2C EEPROM (24LCXXX)
// - 3V3 Voltage Sensor
// - Touch Sensor (with NE555)
// - Buttons
// - LEDs
// - Buzzer

/*****************************************************************************/
// I2C Voltage & Current Sensor (LTC2990):
#define I2C_MULTIIO_VCS_ADR				0x98	// ADR1/0 = 0/0
//#define I2C_MULTIIO_VCS_ADR				0x9a	// ADR1/0 = 0/1
//#define I2C_MULTIIO_VCS_ADR				0x9c	// ADR1/0 = 1/0
//#define I2C_MULTIIO_VCS_ADR				0x9e	// ADR1/0 = 1/1
//#define I2C_MULTIIO_VCS_ADR				0xee	// Global sync address

// (Voltage divider and shunt resistor!)
#define SHUNT_R							0.051		// 0.051 Ohm
#define V1_ADJUST						2.0			// (10+10)/10 kOhm
#define V2_ADJUST						2.0			// (10+10)/10 kOhm
#define VBAT_ADJUST						3.2			// (22+10)/10 kOhm
#define VSERVO_ADJUST					2.5			// (15+10)/10 kOhm

/*****************************************************************************/
// I2C Real Time Clock (RTC DS1307Z):
#define I2C_MULTIIO_RTC_ADR				0xD0	// Default

/*****************************************************************************/
// I2C Temperature Sensor (TCN75A):
// (A1 always 0!)
#define I2C_MULTIIO_TEMP_ADR			0x90	// A2/0 = 0/0
//#define I2C_MULTIIO_TEMP_ADR			0x92	// A2/0 = 0/1
//#define I2C_MULTIIO_TEMP_ADR			0x98	// A2/0 = 1/0
//#define I2C_MULTIIO_TEMP_ADR			0x9a	// A2/0 = 1/1

/*****************************************************************************/
// I2C Servo Controller (PCA9685):
// (A5, A4, A3, A2 always 0!)
#define I2C_MULTIIO_SERVO_ADR			0x80	// A1/0 = 0/0
//#define I2C_MULTIIO_SERVO_ADR			0x82	// A1/0 = 0/1
//#define I2C_MULTIIO_SERVO_ADR			0x84	// A1/0 = 1/0
//#define I2C_MULTIIO_SERVO_ADR			0x86	// A1/0 = 1/1
//#define I2C_MULTIIO_SERVO_ADR			0xe0	// ALLCALLADR

// (Servo power is connected to LED8 of the PCA9685!)
#define CHSERVOPWR						9

// Servo left touch (LT), right touch (RT), middle position (MP) constants:
// (Hints: - Servo impulse length [ms] = Servo position value / 204.8
//           (Formula only valid for a PWM of 50 Hz!)
//         - Min. servo impulse (0,7 ms) = Servo position 143
//         - Mid. servo impulse (1,5 ms) = Servo position 307
//         - Max. servo impulse (2,3 ms) = Servo position 471
//         - !!! You should NOT use servo position values < 143 or > 471 !!!)
#define SERVO1_LT						205		// Servo impulse ~1ms
#define SERVO1_RT						410		// Servo impulse ~2ms
#define SERVO1_MP						((SERVO1_RT - SERVO1_LT) / 2 + SERVO1_LT)
#define SERVO2_LT						205
#define SERVO2_RT						410
#define SERVO2_MP						((SERVO2_RT - SERVO2_LT) / 2 + SERVO2_LT)
#define SERVO3_LT						205
#define SERVO3_RT						410
#define SERVO3_MP						((SERVO3_RT - SERVO3_LT) / 2 + SERVO3_LT)
#define SERVO4_LT						205
#define SERVO4_RT						410
#define SERVO4_MP						((SERVO4_RT - SERVO4_LT) / 2 + SERVO4_LT)
#define SERVO5_LT						205
#define SERVO5_RT						410
#define SERVO5_MP						((SERVO5_RT - SERVO5_LT) / 2 + SERVO5_LT)
#define SERVO6_LT						205
#define SERVO6_RT						410
#define SERVO6_MP						((SERVO6_RT - SERVO6_LT) / 2 + SERVO6_LT)
#define SERVO7_LT						205
#define SERVO7_RT						410
#define SERVO7_MP						((SERVO7_RT - SERVO7_LT) / 2 + SERVO7_LT)
#define SERVO8_LT						205
#define SERVO8_RT						410
#define SERVO8_MP						((SERVO8_RT - SERVO8_LT) / 2 + SERVO8_LT)

/*****************************************************************************/
// I2C EEPROM (24LCXXX):
// (A2=1 not usable with 24LC1024-P!)
#define I2C_MULTIIO_EEPROM_ADR			0xA0	// A2/1/0 = 0/0/0
//#define I2C_MULTIIO_EEPROM_ADR			0xA2	// A2/1/0 = 0/0/1
//#define I2C_MULTIIO_EEPROM_ADR			0xA4	// A2/1/0 = 0/1/0
//#define I2C_MULTIIO_EEPROM_ADR			0xA6	// A2/1/0 = 0/1/1
//#define I2C_MULTIIO_EEPROM_ADR			0xA8	// A2/1/0 = 1/0/0
//#define I2C_MULTIIO_EEPROM_ADR			0xAA	// A2/1/0 = 1/0/1
//#define I2C_MULTIIO_EEPROM_ADR			0xAC	// A2/1/0 = 1/1/0
//#define I2C_MULTIIO_EEPROM_ADR			0xAE	// A2/1/0 = 1/1/1

// I2C-EEPROM storage capacity [kbit]:
#define I2C_EEPROM_KBIT					32		// 24LC32-P <== Default
//#define I2C_EEPROM_KBIT					64		// 24LC64-P
//#define I2C_EEPROM_KBIT					128		// 24LC128-P
//#define I2C_EEPROM_KBIT					256		// 24LC256-P
//#define I2C_EEPROM_KBIT					512		// 24LC512-P
//#define I2C_EEPROM_KBIT					1024	// 24LC1024-P

// I2C-EEPROM pagesize [byte]:
// ATTENTION: The pagesize must fit to the EEPROM type defined above!
#define I2C_EEPROM_PAGESIZE				32		// EEPROM 32 or 64 kbit
//#define I2C_EEPROM_PAGESIZE				64		// EEPROM 128 or 256 kbit
//#define I2C_EEPROM_PAGESIZE				128		// EEPROM 512 kbit
//#define I2C_EEPROM_PAGESIZE				256		// EEPROM 1024 kbit

/*****************************************************************************/
// 3V3 Voltage Sensor:
#define ADC_MULTIIO_3V3					ADC_9	// At ADC-Mxxx
//#define ADC_MULTIIO_3V3					ADC_12	// At ADC-Mxxx
//#define ADC_MULTIIO_3V3					ADC_4	// At ADC-M256

/*****************************************************************************/
// Touch Sensor (with NE555):
#define ADC_MULTIIO_TOUCH				ADC_8	// At ADC-Mxxx
//#define ADC_MULTIIO_TOUCH				ADC_5	// At ADC-M256

#define ADCVAL_NOTOUCH					14
#define ADCVAL_TOUCH					1022
#define ADCVAL_LIMIT_T					((ADCVAL_TOUCH - ADCVAL_NOTOUCH) / 2 + ADCVAL_NOTOUCH)

/*****************************************************************************/
// Buttons:
#define ADC_MULTIIO_BUTTONS				ADC_11	// At ADC-Mxxx

#define ADCVAL_BUTTON1					13
#define ADCVAL_BUTTON2					581
#define ADCVAL_BUTTON3					743
#define ADCVAL_BUTTON4					820
#define ADCVAL_LIMIT12					((ADCVAL_BUTTON2 - ADCVAL_BUTTON1) / 2 + ADCVAL_BUTTON1)
#define ADCVAL_LIMIT23					((ADCVAL_BUTTON3 - ADCVAL_BUTTON2) / 2 + ADCVAL_BUTTON2)
#define ADCVAL_LIMIT34					((ADCVAL_BUTTON4 - ADCVAL_BUTTON3) / 2 + ADCVAL_BUTTON3)
#define ADCVAL_LIMIT40					((1023 - ADCVAL_BUTTON4) / 2 + ADCVAL_BUTTON4)

/*****************************************************************************/
// LEDs:
// (Status LED1..LED4 are connected to LED15..LED12 of the PCA9685!)
#define CHLED1							16
#define CHLED2							15
#define CHLED3							14
#define CHLED4							13

/*****************************************************************************/
// Buzzer:
// (This library assumes that the buzzer is connected to OC2A_PI4 (PB4).
//  This is the case, if you connect IO-Mxxx with IO_PWM/T2/T3 of the M256.
//
//  Possible connections of the buzzer on the MultiIO Project Board:
//
//   M256 plug:    Portpin name:  Portpin:
//   IO_PWM/T2/T3  OC2A_PI4       PB4       <== Default of THIS library!
//   IO_PWM/T0/T1  IO_OC0B        PG5
//   UART_SPI1/T5  IO_PL3_OC5A    PL3
//   UART_SPI2/T4  IO_PH5_OC4C    PH5
//
//  You may of course use one of the other portpins (PG5, PL3, PH5) for the
//  buzzer, but then you will have to write your own buzzer functions!!!
//  Attention: Timer/Counter0 is used by the RP6M256 library, so you may NOT
//             use IO_OC0B (PG5) with hardware PWM!)

/*****************************************************************************/
// Other ADC channel definitions:
// (Depending on jumper settings on the MultiIO Project Board!)
#define ADC_MULTIIO_LDR2				ADC_0	// At ADC-M256
#define ADC_MULTIIO_LDR1				ADC_1	// At ADC-M256
#define ADC_MULTIIO_LFS_R1				ADC_2	// At ADC-M256
#define ADC_MULTIIO_LFS_L1				ADC_3	// At ADC-M256
#define ADC_MULTIIO_SHARP_L				ADC_4	// At ADC-M256
#define ADC_MULTIIO_SHARP_R				ADC_5	// At ADC-M256
#define ADC_MULTIIO_SNAKE_R				ADC_6	// At ADC-M256
#define ADC_MULTIIO_SNAKE_L				ADC_7	// At ADC-M256
#define ADC_MULTIIO_LFS_L				ADC_8	// At ADC-Mxxx
#define ADC_MULTIIO_LFS_M				ADC_9	// At ADC-Mxxx
#define ADC_MULTIIO_LFS_R				ADC_10	// At ADC-Mxxx

// Other IO portpin definitions:
// (Bumper/LEDs in-/outputs at the ADC-Mxxx plug!)
#define IO_MULTIIO_BUMPER_R_IN			IO_PE2_XCK0_AIN0 // At ADC-Mxxx
#define IO_MULTIIO_BUMPER_R_DDR			DDRE
#define IO_MULTIIO_BUMPER_R_PIN			PINE
#define IO_MULTIIO_BUMPER_R_PORT		PORTE

#define IO_MULTIIO_BUMPER_L_IN			IO_PE3_OC3A_AIN1 // At ADC-Mxxx
#define IO_MULTIIO_BUMPER_L_DDR			DDRE
#define IO_MULTIIO_BUMPER_L_PIN			PINE
#define IO_MULTIIO_BUMPER_L_PORT		PORTE

// Other IO portpin definitions:
// (Depending on the IO-Mxxx plug connection. Default: IO_PWM/T2/T3!)
#define IO_MULTIIO_LFS_PWR_IN			IO_PE4_OC3B_I4 // IO-Mxxx: IO_PWM/T2/T3
#define IO_MULTIIO_LFS_PWR_DDR			DDRE
#define IO_MULTIIO_LFS_PWR_PORT			PORTE
//#define IO_MULTIIO_LFS_PWR_IN			OC1B_PI6 // IO-Mxxx: IO_PWM/T0/T1
//#define IO_MULTIIO_LFS_PWR_DDR			DDRB
//#define IO_MULTIIO_LFS_PWR_PORT			PORTB
//#define IO_MULTIIO_LFS_PWR_IN			IO_PL4_OC5B // IO-Mxxx: UART_SPI1/T5
//#define IO_MULTIIO_LFS_PWR_DDR			DDRL
//#define IO_MULTIIO_LFS_PWR_PORT			PORTL
//#define IO_MULTIIO_LFS_PWR_IN			IO_PH3_OC4A // IO-Mxxx: UART_SPI2/T4
//#define IO_MULTIIO_LFS_PWR_DDR			DDRH
//#define IO_MULTIIO_LFS_PWR_PORT			PORTH

#define IO_MULTIIO_SHARPS_PWR_IN		IO_PE6_T3_I6 // IO-Mxxx: IO_PWM/T2/T3
#define IO_MULTIIO_SHARPS_PWR_DDR		DDRE
#define IO_MULTIIO_SHARPS_PWR_PORT		PORTE
//#define IO_MULTIIO_SHARPS_PWR_IN		IO_PD6_T1 // IO-Mxxx: IO_PWM/T0/T1
//#define IO_MULTIIO_SHARPS_PWR_DDR		DDRD
//#define IO_MULTIIO_SHARPS_PWR_PORT		PORTD
//#define IO_MULTIIO_SHARPS_PWR_IN		IO_PL2_T5 // IO-Mxxx: UART_SPI1/T5
//#define IO_MULTIIO_SHARPS_PWR_DDR		DDRL
//#define IO_MULTIIO_SHARPS_PWR_PORT		PORTL
//#define IO_MULTIIO_SHARPS_PWR_IN		IO_PH7_T4 // IO-Mxxx: UART_SPI2/T4
//#define IO_MULTIIO_SHARPS_PWR_DDR		DDRH
//#define IO_MULTIIO_SHARPS_PWR_PORT		PORTH

#define IO_MULTIIO_SNAKE_SWITCH_IN		IO_PE5_OC3C_I5 // IO-Mxxx: IO_PWM/T2/T3
#define IO_MULTIIO_SNAKE_SWITCH_DDR		DDRE
#define IO_MULTIIO_SNAKE_SWITCH_PORT	PORTE
//#define IO_MULTIIO_SNAKE_SWITCH_IN		OC0A_OCM_PI7 // IO-Mxxx: IO_PWM/T0/T1
//#define IO_MULTIIO_SNAKE_SWITCH_DDR		DDRB
//#define IO_MULTIIO_SNAKE_SWITCH_PORT		PORTB
//#define IO_MULTIIO_SNAKE_SWITCH_IN		IO_PD5_XCK1 // IO-Mxxx: UART_SPI1/T5
//#define IO_MULTIIO_SNAKE_SWITCH_DDR		DDRD
//#define IO_MULTIIO_SNAKE_SWITCH_PORT		PORTD
//#define IO_MULTIIO_SNAKE_SWITCH_IN		IO_PH2_XCK2 // IO-Mxxx: UART_SPI2/T4
//#define IO_MULTIIO_SNAKE_SWITCH_DDR		DDRH
//#define IO_MULTIIO_SNAKE_SWITCH_PORT		PORTH

#define IO_MULTIIO_SNAKE_KEY_IN			IO_PH6_OC2B // IO-Mxxx: IO_PWM/T2/T3
#define IO_MULTIIO_SNAKE_KEY_DDR		DDRH
#define IO_MULTIIO_SNAKE_KEY_PIN		PINH
//#define IO_MULTIIO_SNAKE_KEY_IN			OC1A_PI5 // IO-Mxxx: IO_PWM/T0/T1
//#define IO_MULTIIO_SNAKE_KEY_DDR		DDRB
//#define IO_MULTIIO_SNAKE_KEY_PIN		PINB
//#define IO_MULTIIO_SNAKE_KEY_IN			IO_PL5_OC5C // IO-Mxxx: UART_SPI1/T5
//#define IO_MULTIIO_SNAKE_KEY_DDR		DDRL
//#define IO_MULTIIO_SNAKE_KEY_PIN		PINL
//#define IO_MULTIIO_SNAKE_KEY_IN			IO_PH4_OC4B // IO-Mxxx: UART_SPI2/T4
//#define IO_MULTIIO_SNAKE_KEY_DDR		DDRH
//#define IO_MULTIIO_SNAKE_KEY_PIN		PINH

#define IO_MULTIIO_DCF77_IN				IO_PE7_ICP3_I7 // IO-Mxxx: IO_PWM/T2/T3
#define IO_MULTIIO_DCF77_DDR			DDRE
#define IO_MULTIIO_DCF77_PIN			PINE
//#define IO_MULTIIO_DCF77_IN				IO_PD4_ICP1 // IO-Mxxx: IO_PWM/T0/T1
//#define IO_MULTIIO_DCF77_DDR			DDRD
//#define IO_MULTIIO_DCF77_PIN			PIND
//#define IO_MULTIIO_DCF77_IN				IO_PL1_ICP5 // IO-Mxxx: UART_SPI1/T5
//#define IO_MULTIIO_DCF77_DDR			DDRL
//#define IO_MULTIIO_DCF77_PIN			PINL
//#define IO_MULTIIO_DCF77_IN				IO_PL0_ICP4 // IO-Mxxx: UART_SPI2/T4
//#define IO_MULTIIO_DCF77_DDR			DDRL
//#define IO_MULTIIO_DCF77_PIN			PINL

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

#endif

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

/*****************************************************************************/
// EOF
Library Header

Datei RP6M256_MultiIOLib.h:

/* 
 * ****************************************************************************
 * RP6 ROBOT SYSTEM - RP6 CONTROL M256 Examples
 * ****************************************************************************
 * Example: RP6M256 MultiIO Library
 * Author(s): Dirk
 * ****************************************************************************
 * Description:
 * Header file for new MultiIO Project Board library.
 *
 * ****************************************************************************
 */

#ifndef RP6M256_MULTIIOLIB_H
#define RP6M256_MULTIIOLIB_H


/*****************************************************************************/
// MultiIO hardwired components:
// - I2C Voltage & Current Sensor (LTC2990)
// - I2C Real Time Clock (RTC DS1307Z)
// - I2C Temperature Sensor (TCN75A)
// - I2C Servo Controller (PCA9685)
// - I2C EEPROM (24LCXXX)
// - 3V3 Voltage Sensor
// - Touch Sensor (with NE555)
// - Buttons
// - LEDs
// - Buzzer

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

#include "RP6M256Lib.h"
#include "RP6I2CmasterTWI.h"
#include "RP6M256_MultiIO.h"

/*****************************************************************************/
// I2C Voltage & Current Sensor (LTC2990):

// Registers:
#define LTC2990_STATUS					0
#define LTC2990_CONTROL					1
#define LTC2990_TRIGGER					2
#define LTC2990_TINT_MSB				4
#define LTC2990_TINT_LSB				5
#define LTC2990_V1_MSB					6
#define LTC2990_V1_LSB					7
#define LTC2990_V2_MSB					8
#define LTC2990_V2_LSB					9
#define LTC2990_V3_MSB					10
#define LTC2990_V3_LSB					11
#define LTC2990_V4_MSB					12
#define LTC2990_V4_LSB					13
#define LTC2990_VCC_MSB					14
#define LTC2990_VCC_LSB					15

// Status register bitmasks:
#define LTC2990_STATUS_DEFAULT			0
#define LTC2990_STATUS_BUSY				1
#define LTC2990_STATUS_TINT_READY		2
#define LTC2990_STATUS_V1V2_READY		4
#define LTC2990_STATUS_V2_READY			8
#define LTC2990_STATUS_V3V4_READY		16
#define LTC2990_STATUS_V4_READY			32
#define LTC2990_STATUS_VCC_READY		64

// Control register bitmasks:
#define LTC2990_CONTROL_DEFAULT			0
#define LTC2990_CONTROL_MULTIIO			0b01011010 // Mode V1-V2, V3, V4
												   // All measurements per mode
												   // Single acquisition
#define LTC2990_CONTROL_MODE02_DEFAULT	0
#define LTC2990_CONTROL_MODE34_DEFAULT	0
#define LTC2990_CONTROL_REPEAT_SINGLE	64
#define LTC2990_CONTROL_TEMP_FORMAT		128

extern double tint;
extern double cbat;
extern double vbat;
extern double vservo;
extern double vcc;

void LTC2990_write_cfg(uint8_t);
#define LTC2990_init() {LTC2990_write_cfg(LTC2990_CONTROL_MULTIIO);}
void LTC2990_run(void);
void LTC2990_read(void);
void LTC2990_calculate(void);
void LTC2990_measure(void);

/*****************************************************************************/
// I2C Real Time Clock (RTC DS1307Z):

// Registers:
#define DS1307_SECONDS					0
#define DS1307_MINUTES					1
#define DS1307_HOURS					2
#define DS1307_DAY						3
#define DS1307_DATE						4
#define DS1307_MONTH					5
#define DS1307_YEAR						6
#define DS1307_CONTROL					7
#define DS1307_RAM						8

// Control register bitmasks:
#define DS1307_CONTROL_DEFAULT			0
#define DS1307_CONTROL_RS0				1
#define DS1307_CONTROL_RS1				2
#define DS1307_CONTROL_SQWE				16
#define DS1307_CONTROL_OUT				128

enum RTCWEEKDAYS {
	R_MO = 1, R_TU, R_WE, R_TH, R_FR, R_SA, R_SU
};

typedef struct {
	uint16_t         year;				// Year
	uint8_t          month;				// Month   [1..12]
	enum RTCWEEKDAYS weekday;			// Weekday [1..7 = R_MO..R_SU]
	uint8_t          day;				// Day     [1..31]
} rtcdate_t;
rtcdate_t rtc_date;

typedef struct {
	uint8_t dst;						// Daylight-saving-time (time zone)
	uint8_t hour;						// Hour    [0..23]
	uint8_t minute;						// Minute  [0..59]
	uint8_t second;						// Second  [0..59]
} rtctime_t;
rtctime_t rtc_time;

uint8_t BCD2DEC(uint8_t);
uint8_t DEC2BCD(uint8_t);
void DS1307_write_cfg(uint8_t);
void DS1307_init(void);
#define CALC_DST						// Time zone will be calculated
void DS1307_read(void);
void DS1307_write(void);
uint8_t DS1307_readRAM(uint8_t);
void DS1307_writeRAM(uint8_t, uint8_t);

/*****************************************************************************/
// I2C Temperature Sensor (TCN75A):

// Registers:
#define TCN75_TEMP						0
#define TCN75_CONFIG					1
#define TCN75_HYST						2
#define TCN75_LIMIT						3

// Config register bitmasks:
#define TCN75_CONFIG_RUN				0		// Default
#define TCN75_CONFIG_SHUTDOWN			1
#define TCN75_CONFIG_COMP				0		// Default
#define TCN75_CONFIG_INT				2
#define TCN75_CONFIG_ALERT_LOW			0		// Default
#define TCN75_CONFIG_ALERT_HIGH			4
#define TCN75_CONFIG_FAULT_1			0		// Default
#define TCN75_CONFIG_FAULT_2			8
#define TCN75_CONFIG_FAULT_4			16
#define TCN75_CONFIG_FAULT_6			24

// Only for the TCN75A - high resolution and OneShot mode:
#define TCN75A_CONFIG_RES_9				0		// Default
#define TCN75A_CONFIG_RES_10			32		// 0b00100000
#define TCN75A_CONFIG_RES_11			64		// 0b01000000
#define TCN75A_CONFIG_RES_12			96		// 0b01100000
#define TCN75A_CONFIG_ONESHOT_DISABLED	0		// Default
#define TCN75A_CONFIG_ONESHOT			128		// 0b10000000

extern double temperature;

void TCN75_write_cfg(uint8_t);
#define TCN75_shutdown() {TCN75_write_cfg(TCN75_CONFIG_SHUTDOWN);}
#define TCN75_run(__CONFIG__) {TCN75_write_cfg(__CONFIG__);}
extern uint8_t temperature_low;
extern uint8_t temperature_high;
#define getTemperatureHigh() (temperature_high)
#define getTemperatureLow() (temperature_low)
void TCN75_read(void);
double TCN75_calculate(void);
double TCN75_measure(void);

/*****************************************************************************/
// I2C Servo Controller (PCA9685):

// Registers:
#define PCA9685_MODE1					0
#define PCA9685_MODE2					1
#define PCA9685_SUBADR1					2
#define PCA9685_SUBADR2					3
#define PCA9685_SUBADR3					4
#define PCA9685_ALLCALLADR				5
#define PCA9685_LED0_ON_L				6
#define PCA9685_LED0_ON_H				7
#define PCA9685_LED0_OFF_L				8
#define PCA9685_LED0_OFF_H				9
#define PCA9685_LED1_ON_L				10
#define PCA9685_LED1_ON_H				11
#define PCA9685_LED1_OFF_L				12
#define PCA9685_LED1_OFF_H				13
#define PCA9685_LED2_ON_L				14
#define PCA9685_LED2_ON_H				15
#define PCA9685_LED2_OFF_L				16
#define PCA9685_LED2_OFF_H				17
#define PCA9685_LED3_ON_L				18
#define PCA9685_LED3_ON_H				19
#define PCA9685_LED3_OFF_L				20
#define PCA9685_LED3_OFF_H				21
#define PCA9685_LED4_ON_L				22
#define PCA9685_LED4_ON_H				23
#define PCA9685_LED4_OFF_L				24
#define PCA9685_LED4_OFF_H				25
#define PCA9685_LED5_ON_L				26
#define PCA9685_LED5_ON_H				27
#define PCA9685_LED5_OFF_L				28
#define PCA9685_LED5_OFF_H				29
#define PCA9685_LED6_ON_L				30
#define PCA9685_LED6_ON_H				31
#define PCA9685_LED6_OFF_L				32
#define PCA9685_LED6_OFF_H				33
#define PCA9685_LED7_ON_L				34
#define PCA9685_LED7_ON_H				35
#define PCA9685_LED7_OFF_L				36
#define PCA9685_LED7_OFF_H				37
#define PCA9685_LED8_ON_L				38
#define PCA9685_LED8_ON_H				39
#define PCA9685_LED8_OFF_L				40
#define PCA9685_LED8_OFF_H				41
#define PCA9685_LED9_ON_L				42
#define PCA9685_LED9_ON_H				43
#define PCA9685_LED9_OFF_L				44
#define PCA9685_LED9_OFF_H				45
#define PCA9685_LED10_ON_L				46
#define PCA9685_LED10_ON_H				47
#define PCA9685_LED10_OFF_L				48
#define PCA9685_LED10_OFF_H				49
#define PCA9685_LED11_ON_L				50
#define PCA9685_LED11_ON_H				51
#define PCA9685_LED11_OFF_L				52
#define PCA9685_LED11_OFF_H				53
#define PCA9685_LED12_ON_L				54
#define PCA9685_LED12_ON_H				55
#define PCA9685_LED12_OFF_L				56
#define PCA9685_LED12_OFF_H				57
#define PCA9685_LED13_ON_L				58
#define PCA9685_LED13_ON_H				59
#define PCA9685_LED13_OFF_L				60
#define PCA9685_LED13_OFF_H				61
#define PCA9685_LED14_ON_L				62
#define PCA9685_LED14_ON_H				63
#define PCA9685_LED14_OFF_L				64
#define PCA9685_LED14_OFF_H				65
#define PCA9685_LED15_ON_L				66
#define PCA9685_LED15_ON_H				67
#define PCA9685_LED15_OFF_L				68
#define PCA9685_LED15_OFF_H				69
#define PCA9685_ALL_LED_ON_L			250
#define PCA9685_ALL_LED_ON_H			251
#define PCA9685_ALL_LED_OFF_L			252
#define PCA9685_ALL_LED_OFF_H			253
#define PCA9685_PRE_SCALE				254
#define PCA9685_TESTMODE				255

// Mode1 register bitmasks:
#define PCA9685_MODE1_ALLCALL			1
#define PCA9685_MODE1_SUB3				2
#define PCA9685_MODE1_SUB2				4
#define PCA9685_MODE1_SUB1				8
#define PCA9685_MODE1_SLEEP				16
#define PCA9685_MODE1_AI				32
#define PCA9685_MODE1_EXTCLK			64
#define PCA9685_MODE1_RESTART			128

// Mode2 register bitmasks:
#define PCA9685_MODE2_OUTNE01_DEFAULT	0
#define PCA9685_MODE2_OUTDRV			4
#define PCA9685_MODE2_OCH				8
#define PCA9685_MODE2_INVRT				16

#define F_PCA9685						25000000.0	// Int. Clock: 25 MHz

void PCA9685_init(uint16_t);
#define initServo(__FREQ__) {PCA9685_init(__FREQ__);}
void PCA9685_set(uint8_t, uint16_t);
#define setServo(__SERVO__,__POS__) {PCA9685_set(__SERVO__,__POS__);}
void PCA9685_shutdown(void);
void PCA9685_restart(void);
void setServoPower(uint8_t);

/*****************************************************************************/
// I2C EEPROM (24LCXXX):

uint8_t I2C_EEPROM_readByte(uint16_t memAddr);
void I2C_EEPROM_writeByte(uint16_t memAddr, uint8_t data);
void I2C_EEPROM_readBytes(uint16_t startAddr, uint8_t *buffer, uint8_t length);
void I2C_EEPROM_writeBytes(uint16_t startAddr, uint8_t *buffer, uint8_t length);

/*****************************************************************************/
// 3V3 Voltage Sensor:

extern uint16_t adc3v3;
extern double v3v3;

uint16_t get3V3Sensor(void);
double calculate3V3(void);
double measure3V3(void);

/*****************************************************************************/
// Touch Sensor (with NE555):

extern uint16_t adcTouch;
extern uint8_t touch;

uint8_t getTouch(void);

/*****************************************************************************/
// Buttons:

extern uint16_t adcButtons;
extern uint8_t releasedButtonNumber;
extern uint8_t pressedButtonNumber;

uint8_t getPressedButtonNumber(void);
uint8_t checkPressedButtonEvent(void);
uint8_t checkReleasedButtonEvent(void);

/*****************************************************************************/
// LEDs:

void setMultiIOLEDs(uint8_t leds);

void dimMultiIOLED(uint8_t led, uint16_t duty);
void setMultiIOLED1(uint8_t led);
void setMultiIOLED2(uint8_t led);
void setMultiIOLED3(uint8_t led);
void setMultiIOLED4(uint8_t led);

/*****************************************************************************/
// Buzzer:

// Define tone frequencies (well temperament):
// Great Octave
#define Tone_H      2       // 123Hz
// Small Octave
#define Tone_c      16      // 131Hz
#define Tone_cis    30      // 139Hz
#define Tone_d      42      // 147Hz
#define Tone_dis    54      // 156Hz
#define Tone_e      65      // 165Hz
#define Tone_f      76      // 175Hz
#define Tone_fis    86      // 185Hz
#define Tone_g      96      // 196Hz
#define Tone_gis    105     // 208Hz
#define Tone_a      113     // 220Hz
#define Tone_ais    121     // 233Hz
#define Tone_h      128     // 247Hz
// ' Octave
#define Tone_C1     136     // 262Hz
#define Tone_Cis1   142     // 277Hz
#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
// '' Octave
#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
// ''' Octave
#define Tone_C3     225     // 1047Hz
#define Tone_Cis3   227     // 1109Hz
#define Tone_D3     228     // 1175Hz
#define Tone_Dis3   230     // 1245Hz
#define Tone_E3     231     // 1319Hz
#define Tone_F3     233     // 1397Hz
#define Tone_Fis3   234     // 1480Hz
#define Tone_G3     235     // 1568Hz
#define Tone_Gis3   236     // 1661Hz
#define Tone_A3     237     // 1760Hz
#define Tone_Ais3   238     // 1865Hz
#define Tone_H3     239     // 1976Hz
// '''' Octave
#define Tone_C4     240     // 2093Hz
#define Tone_Cis4   241     // 2217Hz
#define Tone_D4     242     // 2349Hz
#define Tone_Dis4   242     // 2489Hz
#define Tone_E4     243     // 2637Hz
#define Tone_F4     244     // 2794Hz
#define Tone_Fis4   244     // 2960Hz
#define Tone_G4     245     // 3136Hz
#define Tone_Gis4   246     // 3322Hz
#define Tone_A4     246     // 3520Hz
#define Tone_Ais4   247     // 3729Hz
#define Tone_H4     247     // 3951Hz
// ''''' Octave
#define Tone_C5     248     // 4186Hz

void Buzzer_init(void);
void setBuzzerPitch(uint8_t);
void soundBuzzer(uint8_t, uint16_t, uint16_t);
#define buzzer(__PITCH__,__TIME__) {soundBuzzer(__PITCH__,__TIME__,0);}

/*****************************************************************************/
// MultiIO Project Board initialisation:

void multiio_init(void);

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

#endif

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

/*****************************************************************************/
// EOF
Library Source

Datei RP6M256_MultiIOLib.c:

/* 
 * ****************************************************************************
 * RP6 ROBOT SYSTEM - RP6 CONTROL M256 Examples
 * ****************************************************************************
 * Example: RP6M256 MultiIO Library
 * Author(s): Dirk
 * ****************************************************************************
 * Description:
 * 
 * This is our new Library that contains basic routines and functions for
 * accessing the hardwired components of the MultiIO Project Board.
 *
 * There are much more sensors, that may be connected to the MultiIO Project
 * Board: Line following sensors (5x CNY70), bumpers, "Snake Vision board",
 *        LDRs, I2C air pressure sensor, I2C humidity sensor, DCF77 module,
 *        I2C IMU, I2C ultrasonic distance sensors, GPS module and more
 *        sensors connected to free ADCs and IOs and to the I2C bus.
 * This library doesn't contain functions for these sensors, because they are
 * not HARDWIRED to the MultiIO Project Board and may be connected OPTIONALLY.
 *
 * ****************************************************************************
 */

/*****************************************************************************/
// MultiIO hardwired components:
// - I2C Voltage & Current Sensor (LTC2990)
// - I2C Real Time Clock (RTC DS1307Z)
// - I2C Temperature Sensor (TCN75A)
// - I2C Servo Controller (PCA9685)
// - I2C EEPROM (24LCXXX)
// - 3V3 Voltage Sensor
// - Touch Sensor (with NE555)
// - Buttons
// - LEDs
// - Buzzer

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

#include "RP6M256_MultiIOLib.h" 		

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

uint8_t registerBuf[13]; 

/*****************************************************************************/
// I2C Voltage & Current Sensor (LTC2990):

/**
 * Sends the configuration byte to a LTC2990.
 *
 * Input: Config byte for control register
 *
 * There is also a macro LTC2990_init(), which
 * initializes the sensor to work in V1-V2, V3,
 * V4 and Single Acquisition mode.
 *
 * Example:
 *   LTC2990_init();
 *
 */
void LTC2990_write_cfg(uint8_t config)
{
	I2CTWI_transmit2Bytes(I2C_MULTIIO_VCS_ADR, LTC2990_CONTROL, config);
}

uint8_t vcs_tint_low;
uint8_t vcs_tint_high;
uint8_t vcs_v1_low;
uint8_t vcs_v1_high;
uint8_t vcs_v2_low;
uint8_t vcs_v2_high;
uint8_t vcs_v3_low;
uint8_t vcs_v3_high;
uint8_t vcs_v4_low;
uint8_t vcs_v4_high;
uint8_t vcs_vcc_low;
uint8_t vcs_vcc_high;

/**
 * Starts a Single Acquisition measurement.
 */
void LTC2990_run(void)
{
	I2CTWI_transmit2Bytes(I2C_MULTIIO_VCS_ADR, LTC2990_TRIGGER, 0);
}

/**
 * Reads all data registers of the voltage & current
 * sensor (VCS).
 * They are stored in the variables defined above.
 */
void LTC2990_read(void)
{
	I2CTWI_transmitByte(I2C_MULTIIO_VCS_ADR, LTC2990_TINT_MSB);
	I2CTWI_readBytes(I2C_MULTIIO_VCS_ADR, registerBuf, 12);
	vcs_tint_high = registerBuf[0];
	vcs_tint_low = registerBuf[1];
	vcs_v1_high = registerBuf[2];
	vcs_v1_low = registerBuf[3];
	vcs_v2_high = registerBuf[4];
	vcs_v2_low = registerBuf[5];
	vcs_v3_high = registerBuf[6];
	vcs_v3_low = registerBuf[7];
	vcs_v4_high = registerBuf[8];
	vcs_v4_low = registerBuf[9];
	vcs_vcc_high = registerBuf[10];
	vcs_vcc_low = registerBuf[11];
}

double tint;							// Internal temperature
double cbat;							// Current at 9V
double vbat;							// Battery voltage 9V (BAT)
double vservo;							// Servo voltage 5 .. 7.5V
double vcc;								// Voltage 5V (VCC)

/**
 * Calculates the temperature, voltage and current
 * values by using the data read from the LTC2990
 * with the function LTC2990_read(). The sensor is
 * configured to work in V1-V2, V3, V4 and Single
 * Acquisition mode.
 * The result is stored in the double variables
 * defined above.
 */
void LTC2990_calculate(void)
{
	int16_t tmp, tmp2;
	double v1, v2;

	tmp = (((vcs_tint_high & 0x1f) << 8) + vcs_tint_low) << 3;
	tmp = tmp / 8;
	tint = tmp / 16.0;							// Internal temperature [°C]

	tmp = (((vcs_v1_high & 0x7f) << 8) + vcs_v1_low) << 1;
	tmp = tmp / 2;
	v1 = tmp * 0.01942;
	v1 *= V1_ADJUST;							// Voltage divider factor
	tmp2 = (((vcs_v2_high & 0x7f) << 8) + vcs_v2_low) << 1;
	tmp2 = tmp2 / 2;
	v2 = tmp * 0.01942;
	v2 *= V2_ADJUST;							// Voltage divider factor
	cbat = (v1 - v2) / SHUNT_R;				// Battery current [mA]

	tmp = ((vcs_v3_high & 0x3f) << 8) + vcs_v3_low;
	vbat = tmp * 0.00030518;					// Battery voltage [V]
	vbat *= VBAT_ADJUST;						// Voltage divider factor

	tmp = ((vcs_v4_high & 0x3f) << 8) + vcs_v4_low;
	vservo = tmp * 0.00030518;					// Servo voltage [V]
	vservo *= VSERVO_ADJUST;					// Voltage divider factor

	tmp = ((vcs_vcc_high & 0x3f) << 8) + vcs_vcc_low;
	vcc = 2.5 + tmp * 0.00030518;				// VCC [V]
}

/**
 * Performs a complete measurement with the sensor
 * configured to work in V1-V2, V3, V4 and Single
 * Acquisition mode.
 * The result is stored in the double variables
 * defined above.
 * This function is BLOCKING for about 200 ms!
 * If you don't want a blocking measurement, you
 * have to write your own function with a non
 * blocking pause between starting measurement
 * and reading the result or with another mode
 * of operation (Repeated Acquisitions).
 */
void LTC2990_measure(void)
{
	LTC2990_run();								// Start measurement
	mSleep(200);
	LTC2990_read();								// Read data
	LTC2990_calculate();						// Calculate values
}

/*****************************************************************************/
// I2C Real Time Clock (RTC DS1307Z):

/**
 * This function converts a BCD to a DEC value.
 *
 */
uint8_t BCD2DEC(uint8_t bcd)
{
	return ((bcd >> 4) * 10 + (bcd & 0x0f));
}

/**
 * This function converts a DEC to a BCD value.
 *
 */
uint8_t DEC2BCD(uint8_t dec)
{uint8_t units = dec % 10;
	if (dec /= 10) {
		return (units + (DEC2BCD(dec) << 4));
	}
	else {
		return units;
	}
}

/**
 * Sends the configuration byte to a DS1307.
 *
 * Input: Config byte for control register
 *
 */
void DS1307_write_cfg(uint8_t config)
{
	I2CTWI_transmit2Bytes(I2C_MULTIIO_RTC_ADR, DS1307_CONTROL, config);
}

/**
 * Initializes the DS1307 by resetting all registers.
 * Only use this function ONCE for a DS1307 without or
 * with empty backup battery!
 */
void DS1307_init(void)
{
	uint8_t i;

	for (i = 0; i < 8; i++) {
		registerBuf[i] = 0;
	}
	I2CTWI_transmitBytes(I2C_MULTIIO_RTC_ADR, &registerBuf[0], 8);
}

/**
 * Reads all data registers of the Real Time Clock (RTC).
 * They are stored in the time & date variables defined in
 * the library header.
 */
void DS1307_read(void)
{
	I2CTWI_transmitByte(I2C_MULTIIO_RTC_ADR, DS1307_SECONDS);
	I2CTWI_readBytes(I2C_MULTIIO_RTC_ADR, registerBuf, 7);
	rtc_time.second = BCD2DEC(registerBuf[0] & 0x7f);
	rtc_time.minute = BCD2DEC(registerBuf[1]);
	rtc_time.hour = BCD2DEC(registerBuf[2] & 0x3f);
	rtc_date.weekday = registerBuf[3];
	rtc_date.day = BCD2DEC(registerBuf[4]);
	rtc_date.month = BCD2DEC(registerBuf[5]);
	rtc_date.year = BCD2DEC(registerBuf[6]) + 2000;
	rtc_time.dst = 0;
#ifdef CALC_DST
	// Calculate MESZ (DST):
	uint8_t wday = rtc_date.weekday;			// Weekday [1..7 = R_MO..R_SU]
	if(wday == 7) wday = 0;
	if(rtc_date.month < 3 || rtc_date.month > 10) {
		return;
	}
	if((rtc_date.day - wday >= 25)
	 && (wday || rtc_time.hour >= 2)) {
		if(rtc_date.month == 10)
			return;
	}
	else {
		if(rtc_date.month == 3) {
			return;
		}
	}
	rtc_time.dst = 1;
#endif
}

/**
 * Writes the time & date infos in the variables defined in
 * the library header to the Real Time Clock (RTC).
 */
void DS1307_write(void)
{
	registerBuf[0] = DS1307_SECONDS;
	registerBuf[1] = DEC2BCD(rtc_time.second);
	registerBuf[2] = DEC2BCD(rtc_time.minute);
	registerBuf[3] = DEC2BCD(rtc_time.hour);
	registerBuf[4] = rtc_date.weekday;
	registerBuf[5] = DEC2BCD(rtc_date.day);
	registerBuf[6] = DEC2BCD(rtc_date.month);
	registerBuf[7] = DEC2BCD(rtc_date.year - 2000);
	I2CTWI_transmitBytes(I2C_MULTIIO_RTC_ADR, &registerBuf[0], 8);
}

/**
 * Reads and returns a data byte from the DS1307 RAM.
 *
 * Input: adr -> RAM address [0..55]
 *
 * Hints: - The real DS1307 RAM addresses are 8..63!
 *        - The RAM is nonvolatile. That means, that
 *          it keeps the data as long as the backup
 *          battery doesn't become weak!
 *
 */
uint8_t DS1307_readRAM(uint8_t adr)
{
	if (adr > 55) adr = 0;
	I2CTWI_transmitByte(I2C_MULTIIO_RTC_ADR, (DS1307_RAM + adr));
	return (I2CTWI_readByte(I2C_MULTIIO_RTC_ADR));
}

/**
 * Writes a data byte to the DS1307 RAM.
 *
 * Input: adr  -> RAM address [0..55]
 *        data -> Data byte [0..255]
 *
 * Hints: - The real DS1307 RAM addresses are 8..63!
 *        - The RAM is nonvolatile. That means, that
 *          it keeps the data as long as the backup
 *          battery doesn't become weak!
 *
 */
void DS1307_writeRAM(uint8_t adr, uint8_t data)
{
	if (adr > 55) adr = 0;
	I2CTWI_transmit2Bytes(I2C_MULTIIO_RTC_ADR, (DS1307_RAM + adr), data);
}

/*****************************************************************************/
// I2C Temperature Sensor (TCN75A):

/**
 * Sends the configuration byte to a TCN75A.
 *
 * Input: Config byte for config register
 *
 */
void TCN75_write_cfg(uint8_t config)
{
	I2CTWI_transmit2Bytes(I2C_MULTIIO_TEMP_ADR, TCN75_CONFIG, config);
}

uint8_t temperature_low;
uint8_t temperature_high;

/**
 * Reads the two data registers of the temperature
 * sensor.
 * They are stored in the variables temperature_low
 * and _high.
 *
 * Hint: Depending on the sensor configuration the
 *       data are located different in the two bytes
 *       - have a look at the datasheet!
 *
 */
void TCN75_read(void)
{
	I2CTWI_transmitByte(I2C_MULTIIO_TEMP_ADR, TCN75_TEMP);
	I2CTWI_readBytes(I2C_MULTIIO_TEMP_ADR, registerBuf, 2);
	temperature_low = registerBuf[0];
	temperature_high = registerBuf[1];
}

double temperature;						// Temperature [°C]

/**
 * Calculates and returns the temperature value
 * by using the data read from the TCN75A with
 * the function TCN75_read(). The sensor is
 * configured to Single Conversion and 12 bit
 * measurement.
 */
double TCN75_calculate(void)
{
	uint8_t templow;
	double temp;

	templow = getTemperatureLow();
	if (templow & 128)							// Calculate temperature
		templow = (templow & 63) - 127;
	else
		templow = templow & 63;
	temp = templow + (0.0625 * (getTemperatureHigh() >> 4));
	return temp;
}

/**
 * Performs a 12 bit measurement and returns the
 * temperature [°C].
 * This function is BLOCKING for about 250 ms!
 * If you don't want a blocking measurement, you
 * have to write your own function with a non
 * blocking pause between starting measurement
 * and reading the result or with another mode
 * of operation (Continuous Conversion).
 */
double TCN75_measure(void)
{
	TCN75_run(TCN75A_CONFIG_RES_12);			// Start measurement
	mSleep(250);
	TCN75_shutdown();							// Stop measurement
	TCN75_read();								// Read data
	return (TCN75_calculate());					// Calculate value
}

/*****************************************************************************/
// I2C Servo Controller (PCA9685):

/**
 * Call this once before using the servo function.
 *
 * Input: PWM frequency [40..1000 Hz]
 *
 * Hints: - Default servo frequency is 50 Hz!
 *        - The servo power is NOT switched on by
 *          this function!
 *
 * There is also a macro initServo(freq), which
 * does exactly the same as this function.
 *
 * Example:
 *   initServo(50);
 *
 */
void PCA9685_init(uint16_t freq)
{
	if ((freq < 40) || (freq > 1000)) freq = 50;
	I2CTWI_transmitByte(I2C_MULTIIO_SERVO_ADR, PCA9685_MODE2);
	uint8_t last_mode = I2CTWI_readByte(I2C_MULTIIO_SERVO_ADR);
	last_mode &= ~PCA9685_MODE2_INVRT;			// Clear INVRT bit
	last_mode |= PCA9685_MODE2_OUTDRV;			// Set OUTDRV bit
	I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_MODE2, last_mode);
	I2CTWI_transmitByte(I2C_MULTIIO_SERVO_ADR, PCA9685_MODE1);
	last_mode = I2CTWI_readByte(I2C_MULTIIO_SERVO_ADR);
	last_mode |= PCA9685_MODE1_AI;				// Set AI bit
	uint8_t mode1 = last_mode;
	mode1 |= PCA9685_MODE1_SLEEP;				// Set SLEEP bit
	I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_MODE1, mode1);
	uint8_t prescale = (uint8_t) (F_PCA9685 / 4096 / freq - 0.5);
	I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_PRE_SCALE, prescale);
	last_mode &= ~PCA9685_MODE1_SLEEP;			// Clear SLEEP bit
	I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_MODE1, last_mode);
	mSleep(1);
	last_mode |= PCA9685_MODE1_RESTART;			// Clear RESTART bit
	I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_MODE1, last_mode);
	I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_LED8_ON_H, 0x10);
	return;
}

/**
 * This is the servo position set function.
 *
 * Input: servo -> Servo number [1..8, 10..16]
 *        pos   -> Servo position [SERVOx_LT..SERVOx_RT]
 *
 * Hints: - Servo number 9 cannot be set by this function!
 *          Please use setServoPower() function instead!
 *        - A servo position of 205 means 1 ms servo impulse,
 *          a position of 410 means a 2 ms servo impulse!
 *          You may calculate the servo impulse length by:
 *          ==> Impulse [ms] = servo position / 204.8 <==
 *          (Formula only valid for a PWM of 50 Hz!)
 *
 * There is also a macro setServo(servo, pos), which
 * does exactly the same as this function.
 *
 * Example:
 *   setServo(2,300);
 *
 */
void PCA9685_set(uint8_t servo, uint16_t pos)
{
	if ((servo == 0) || (servo == CHSERVOPWR) || (servo > 16))
		return;
	uint8_t reg = servo * 4 + 4;				// Register LEDx_OFF_L
	I2CTWI_transmit3Bytes(I2C_MULTIIO_SERVO_ADR, reg, (pos & 0x00ff), (pos >> 8));
}

/**
 * If the servos are not moving for a while, the
 * servo function can be stopped with this
 * function (PCA9685 set to sleep mode).
 *
 * Hint: The servo power is NOT switched off by
 *       this function!
 *
 */
void PCA9685_shutdown(void)
{
	I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_ALL_LED_OFF_H, 0x10);
	I2CTWI_transmitByte(I2C_MULTIIO_SERVO_ADR, PCA9685_MODE1);
	uint8_t mode1 = I2CTWI_readByte(I2C_MULTIIO_SERVO_ADR);
	mode1 |= PCA9685_MODE1_SLEEP;				// Set SLEEP bit
	I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_MODE1, mode1);
}

/**
 * If the servo function was stopped with the
 * function PCA9685_shutdown() before, it can be
 * (re)started again with this function.
 *
 * Hint: The servo power is NOT switched on by
 *       this function!
 *
 */
void PCA9685_restart(void)
{
	I2CTWI_transmitByte(I2C_MULTIIO_SERVO_ADR, PCA9685_MODE1);
	uint8_t mode1 = I2CTWI_readByte(I2C_MULTIIO_SERVO_ADR);
	if (mode1 & PCA9685_MODE1_RESTART) {		// RESTART bit set?
		mode1 &= ~PCA9685_MODE1_SLEEP;			// Clear SLEEP bit
		I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_MODE1, mode1);
		mSleep(1);
		mode1 |= PCA9685_MODE1_RESTART;			// Clear RESTART bit
		I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_MODE1, mode1);
		I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_ALL_LED_OFF_H, 0);
	}
}

/** 
 * With this function you can switch the servo
 * power on or off, if the servo power jumper on
 * the board enables this feature.
 *
 * Input: pwr -> 0 (false) = servo power off
 *               >0 (true) = servo power on
 *
 * Hints: - If connected servos are not used, you
 *          should always switch the servo power off
 *          to save energy!
 *        - The PCA9685 is NOT restarted or put into
 *          shutdown mode by this function!
 *
 */
void setServoPower(uint8_t pwr)
{
	if (pwr > 0)
		I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_LED8_OFF_H, 0);
	else
		I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_LED8_OFF_H, 0x10);
}	

/*****************************************************************************/
// I2C EEPROM (24LCXXX):

// The following EEPROM types may be used:
//  EEPROM Size:  Chip              Pagesize
//  -   32 kbit:  ST24LC32A            32
//  -   64 kbit:  ST24LC64             32
//  -  128 kbit:  ST24LC128            64
//  -  256 kbit:  ST24LC256            64
//  -  512 kbit:  ST24LC512           128
//  - 1024 kbit:  AT24LC1024          256
// ! You may choose the EEPROM type in the I2C EEPROM !
// ! section of the RP6M256_MultiIO.h file!           !

/**
 * Reads a single Byte from the EEPROM.
 */
uint8_t I2C_EEPROM_readByte(uint16_t memAddr)
{
	uint8_t data;
	I2CTWI_transmit2Bytes(I2C_MULTIIO_EEPROM_ADR, (memAddr >> 8), memAddr);
	data = I2CTWI_readByte(I2C_MULTIIO_EEPROM_ADR);
	return data;
}

/**
 * Write a single data byte to the specified EEPROM address.
 */
void I2C_EEPROM_writeByte(uint16_t memAddr, uint8_t data)
{
	I2CTWI_transmit3Bytes(I2C_MULTIIO_EEPROM_ADR, (memAddr >> 8), memAddr, data);
	mSleep(5);
}

/**
 * Reads "length" Bytes into the Buffer "buffer" from startAddr on. 
 * You can read the complete EEPROM into a buffer at once - if it is large enough. 
 * (But you only have 8KB SRAM on a MEGA2560 ;) )
 * If "length" is higher than I2CTWI_BUFFER_REC_SIZE defined in RP6I2CmasterTWI.h,
 * you have to adapt I2CTWI_BUFFER_REC_SIZE to the highest used "length" value!
 */
void I2C_EEPROM_readBytes(uint16_t startAddr, uint8_t *buffer, uint8_t length)
{
	I2CTWI_transmit2Bytes(I2C_MULTIIO_EEPROM_ADR, (startAddr >> 8), startAddr);
	I2CTWI_readBytes(I2C_MULTIIO_EEPROM_ADR, &buffer[0], length);
}

/**
 * Write "length" Bytes from the Buffer to the EEPROM. 
 * YOU CAN ONLY WRITE MAXIMAL [I2C_EEPROM_PAGESIZE] BYTES AT ONCE!!!
 * This is the Pagesize!
 * You can NOT cross a page boundary!
 * If (length + 2) is higher than I2CTWI_BUFFER_SIZE defined in RP6I2CmasterTWI.h,
 * you have to adapt I2CTWI_BUFFER_SIZE to the highest used (length + 2) value!
 */
void I2C_EEPROM_writeBytes(uint16_t startAddr, uint8_t *buffer, uint8_t length)
{
	uint8_t i, addrbuffer[length + 2];
	addrbuffer[0] = (startAddr >> 8);
	addrbuffer[1] = startAddr;
	for(i = 0; i < length; i++) {
		addrbuffer[i + 2] = buffer[i];
	}
	I2CTWI_transmitBytes(I2C_MULTIIO_EEPROM_ADR, &addrbuffer[0], (length + 2));
	mSleep(5);
}

/*****************************************************************************/
// 3V3 Voltage Sensor:

uint16_t adc3v3;						// 3V3 voltage sensor ADC value

/**
 * This function reads and returns the ADC value of
 * the 3V3 voltage sensor. The value is also stored
 * in adc3v3.
 *
 */
uint16_t get3V3Sensor(void)
{
	adc3v3 = readADC(ADC_MULTIIO_3V3);
	return adc3v3;
}

double v3v3;							// 3V3 voltage [V]

/**
 * Calculates and returns the 3.3V voltage value
 * by using the data read from the 3V3 voltage
 * sensor with the function get3V3Sensor().
 *
 */
double calculate3V3(void)
{
	return (5.0 / 1024.0 * adc3v3);
}

/**
 * Measures and returns the 3.3V voltage value.
 * The ADC value of the 3V3 voltage sensor is also
 * stored in adc3v3.
 *
 */
double measure3V3(void)
{
	adc3v3 = readADC(ADC_MULTIIO_3V3);
	return (5.0 / 1024.0 * adc3v3);
}

/*****************************************************************************/
// Touch Sensor (with NE555):

uint16_t adcTouch;						// Touch sensor ADC value
uint8_t touch = 0;						// True (1), if touched

/**
 * Checks if the touch sensor antenna is touched - returns 1,
 * if touched or 0, if the antenna is NOT touched.
 *
 */
uint8_t getTouch(void)
{
	adcTouch = readADC(ADC_MULTIIO_TOUCH);
	if (adcTouch > ADCVAL_LIMIT_T) return 1;
	else return 0;
}

/*****************************************************************************/
// Buttons:

uint16_t adcButtons;					// Keypad ADC value
uint8_t releasedButtonNumber;			// Released (last pressed) button
uint8_t pressedButtonNumber;			// Actually pressed button

/**
 * Checks which button is pressed - returns the button number,
 * or 0, if no button is pressed.
 * Maybe the values of ADCVAL_LIMITxx have to change because
 * of variations in the resistors of the keypad! This is done
 * in RP6M256_MultiIO.h, if you define other ADC values for
 * your 4 buttons in ADCVAL_BUTTON1..ADCVAL_BUTTON4.
 *
 */
uint8_t getPressedButtonNumber(void)
{
	adcButtons = readADC(ADC_MULTIIO_BUTTONS);
	if(adcButtons < 1020) {
		nop();
		nop();
		nop();
		adcButtons += readADC(ADC_MULTIIO_BUTTONS);
		adcButtons >>= 1;
	}
	if(adcButtons < ADCVAL_LIMIT12)
		return 1;
	if(adcButtons < ADCVAL_LIMIT23)
		return 2;
	if(adcButtons < ADCVAL_LIMIT34)
		return 3;
	if(adcButtons < ADCVAL_LIMIT40)
		return 4;
	return 0;
}

/**
 * This function has to be called frequently out of the
 * main loop and checks if a button is pressed! It only returns 
 * the button number a single time, DIRECTLY when the button is
 * pressed.
 * 
 * This is useful for non-blocking keyboard check in the
 * main loop. You don't need something like 
 * "while(getPressedButtonNumber());" to wait for the button
 * to be released again!
 */
uint8_t checkPressedButtonEvent(void)
{
	static uint8_t pressed_button = 0;
	if(pressed_button) {
		if(!getPressedButtonNumber()) 
			pressed_button = 0;
	}
	else {
		pressed_button = getPressedButtonNumber();
		if(pressed_button)
			return pressed_button;
	}
	return 0;
}

/**
 * This function has to be called frequently out of
 * the main loop and checks if a button is pressed AND
 * released. It only returns the button number a single
 * time, AFTER the button has been released.
 * 
 * This is useful for non-blocking keyboard check in the
 * main loop. You don't need something like 
 * "while(getPressedButtonNumber());" to wait for the button
 * to be released again!
 */
uint8_t checkReleasedButtonEvent(void)
{
	static uint8_t released_button = 0;
	if(released_button) {
		if(!getPressedButtonNumber()) {
			uint8_t tmp = released_button;
			released_button = 0;
			return tmp;
		}
	}
	else
		released_button = getPressedButtonNumber();
	return 0;
}

/*****************************************************************************/
// LEDs:

/** 
 * Set the 4 status LEDs of the MultiIO.
 *
 * Example:
 *			setMultiIOLEDs(0b1010);
 *			// this clears LEDs 1 and 3
 *          // and sets LEDs 2 and 4!
 *
 */
void setMultiIOLEDs(uint8_t leds)
{
	if (leds & 0b00000001) PCA9685_set(CHLED1, 4095);
	else PCA9685_set(CHLED1, 0);
	if (leds & 0b00000010) PCA9685_set(CHLED2, 4095);
	else PCA9685_set(CHLED2, 0);
	if (leds & 0b00000100) PCA9685_set(CHLED3, 4095);
	else PCA9685_set(CHLED3, 0);
	if (leds & 0b00001000) PCA9685_set(CHLED4, 4095);
	else PCA9685_set(CHLED4, 0);
}

/** 
 * Dim the 4 status LEDs of the MultiIO.
 *
 * Input: led  -> LED number [1..4]
 *        duty -> Duty cycle [0..4095]
 *
 * Example:
 *			dimMultiIOLED(2,2048);
 *			// this dims LED2 with a
 *          // duty cycle of 50% !
 *
 */
void dimMultiIOLED(uint8_t led, uint16_t duty)
{
	if (led == 1) PCA9685_set(CHLED1, duty);
	if (led == 2) PCA9685_set(CHLED2, duty);
	if (led == 3) PCA9685_set(CHLED3, duty);
	if (led == 4) PCA9685_set(CHLED4, duty);
}

/** 
 * Set ONLY LED1, don't change anything for the other LEDs.
 *
 * Input: led -> 0 (false) = LED off
 *               >0 (true) = LED on
 *
 */
void setMultiIOLED1(uint8_t led)
{
	if (led > 0) PCA9685_set(CHLED1, 4095); 
	else PCA9685_set(CHLED1, 0);	
}	

/** 
 * Set ONLY LED2, don't change anything for the other LEDs.
 */
void setMultiIOLED2(uint8_t led)
{
	if (led > 0) PCA9685_set(CHLED2, 4095); 
	else PCA9685_set(CHLED2, 0);	
}	

/** 
 * Set ONLY LED3, don't change anything for the other LEDs.
 */
void setMultiIOLED3(uint8_t led)
{
	if (led > 0) PCA9685_set(CHLED3, 4095); 
	else PCA9685_set(CHLED3, 0);	
}	

/** 
 * Set ONLY LED4, don't change anything for the other LEDs.
 */
void setMultiIOLED4(uint8_t led)
{
	if (led > 0) PCA9685_set(CHLED4, 4095); 
	else PCA9685_set(CHLED4, 0);	
}

/*****************************************************************************/
// Buzzer:

/**
 * Call this once before using the buzzer.
 *
 */
void Buzzer_init(void)
{
	DDRB |= OC2A_PI4;							// Portpin: output
 	TCCR2A = 0;									
	TCCR2B = 0;									// Sound off
	PORTB &= ~OC2A_PI4;							// Portpin low
}

/**
 * This function has no timing stuff. It only sets the pitch
 * and this can be used to generate tone sequences which
 * would sound bad if the beeper turns of for a very short time
 * in between - such as alarm tones or special melodies etc.
 * 
 * Input: pitch -> 0 =   sound off
 *                 1 =   lowest frequency
 *                 255 = higest frequency
 *
 */
void setBuzzerPitch(uint8_t pitch)
{
	OCR2A = 255 - pitch;
	if(pitch) {
		TCCR2A = (1 << WGM21) | (1 << COM2A0);
		TCCR2B = (1 << CS21) | (1 << CS22);
	}
	else {
		TCCR2A = 0;
		TCCR2B = 0;								// Normal port operation
		PORTB &= ~OC2A_PI4;						// Portpin low
	}
}

/**
 * You can use this function to make the buzzer beep ;) 
 * This function is BLOCKING and generates a delay for the
 * sound and a delay between two sounds.
 *
 * Input: pitch -> 0 = sound off
 *                 1 = lowest frequency
 *                 255 = higest frequency
 *        time  -> sound length [ms]
 *        delay -> pause after the sound [ms]
 *
 * Example:
 *   soundBuzzer(150,50,25);
 *   soundBuzzer(200,50,25);
 *
 * There is also a macro buzzer(pitch, time). You may use
 * it for sounds without a pause after the sound. The macro
 * is BLOCKING during the sound length.
 *
 * Example:
 *   buzzer(150,50);
 *
 */
void soundBuzzer(uint8_t pitch, uint16_t time, uint16_t delay)
{
	setBuzzerPitch(pitch);
	if (!pitch) return;
	mSleep(time);
	setBuzzerPitch(0);							// Sound off
	if (!delay) return;
	mSleep(delay);
}

/*****************************************************************************/
/*****************************************************************************/
// MultiIO Project Board initialisation:

/**
 * You MUST call this function at the beginning of a
 * main program, that uses the MultiIO Project Board. 
 *
 */
void multiio_init(void)
{
	// Voltage & current sensor:
	LTC2990_init();								// Init VCS
	// Servo Controller:
	PCA9685_init(50);							// Init PWM 50 Hz
	// Servo power:
	setServoPower(0);							// Servo power off
	// Buzzer:
	Buzzer_init();								// Init buzzer
}

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

/******************************************************************************
 * Additional info
 * ****************************************************************************
 * Changelog:
 * - v. 2.0 (release for board V3) 17.02.2013 by Dirk
 * - v. 1.0 (initial release) 21.01.2013 by Dirk
 *
 * ****************************************************************************
 */

/*****************************************************************************/
// EOF
Erklärung

... BAUSTELLE ... BAUSTELLE ... BAUSTELLE ...

Demo

makefile:

...
TARGET = RP6M256_MultiIO
...
SRC += RP6M256_MultiIOLib.c
...

Datei RP6M256_MultiIO.c:

/* 
 * ****************************************************************************
 * RP6 ROBOT SYSTEM - RP6 CONTROL M256 Examples
 * ****************************************************************************
 * Example: RP6M256 MultiIO
 * Author(s): Dirk
 * ****************************************************************************
 * Description:
 * In this example we show a first test for the MultiIO Project Board.
 * 
 * ############################################################################
 * The Robot does NOT move in this example! You can simply put it on a table
 * next to your PC and you should connect it to the PC via the USB Interface!
 * You should also connect to it via WIFI.
 * ############################################################################
 * ****************************************************************************
 */

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

#include "RP6M256Lib.h" 				// The RP6 M256 Library. 
										// Always needs to be included!
#include "RP6I2CmasterTWI.h"			// Include the I2C-Bus Master Library

/*****************************************************************************/
/*****************************************************************************/
// Include our new "RP6M256 MultiIO library":
// (This is the library for accessing the MultiIO Project Board!)

#include "RP6M256_MultiIOLib.h"

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

/**
 * Write a floating point number to the WIFI.
 *
 * Example:
 *
 *			// Write a floating point number to the WIFI (no exponent):
 *			writeDouble_WIFI(1234567.890, 11, 3);
 *
 * The value of prec (precision) defines the number of decimal places.
 * For 32 bit floating point variables (float, double ...) 6 is
 * the max. value for prec (7 relevant digits).
 * The value of width defines the overall number of characters in the
 * floating point number including the decimal point. The number of
 * pre-decimal positions is: (width - prec - 1).
 */
void writeDouble_WIFI(double number, uint8_t width, uint8_t prec)
{char buffer[width + 1];
	dtostrf(number, width, prec, &buffer[0]);
	writeString_WIFI(&buffer[0]);
}

/*****************************************************************************/
// I2C Error handler

/**
 * This function gets called automatically if there was an I2C Error like
 * the slave sent a "not acknowledge" (NACK, error codes e.g. 0x20 or 0x30).
 *
 */
void I2C_transmissionError(uint8_t errorState)
{
	writeString_P_WIFI("\nI2C ERROR - TWI STATE: 0x");
	writeInteger_WIFI(errorState, HEX);
	writeChar_WIFI('\n');
}

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

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

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

	setLEDs(0b1111);
	mSleep(500);
	setLEDs(0b0000);

	writeString_P_WIFI("\n\nRP6M256 Multi IO Selftest 1!\n"); 

	// IMPORTANT:
	I2CTWI_initMaster(100); // Initialize the TWI Module for Master operation
							// with 100kHz SCL Frequency


	// Register the event handler:
	I2CTWI_setTransmissionErrorHandler(I2C_transmissionError);

	setLEDs(0b1111);

	// Write a text message to the LCD:
	showScreenLCD("################", "################");
	mSleep(1500);
	showScreenLCD("RP6v2-M256-WIFI ", "Example Program");
	mSleep(2500); 
	showScreenLCD("RP6M256 Multi IO", "   Selftest 1");
	mSleep(2500);
	clearLCD();

	setLEDs(0b0000);

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

	uint8_t onoff = 0;
	uint16_t servopos = SERVO1_LT;

	startStopwatch1();

	// IMPORTANT:
	multiio_init();								// MultiIO init!!!
	//setServoPower(1);							// Servo power ON!

	// ----------------------------------------------
	// Set RTC once (battery empty or not existing:
	rtc_time.second = 0;
	rtc_time.minute = 0;
	rtc_time.hour = 12;				// 12:00
	rtc_date.weekday = R_TH;
	rtc_date.day = 10;
	rtc_date.month = 1;
	rtc_date.year = 2013;			// Do, 10.1.2013
	DS1307_write();
	// Remove this, if RTC is set and running!!!
	// ----------------------------------------------

	// EEPROM test:
	writeString_P_WIFI("\nWriting 128 to EEPROM address 5:\n");
	I2C_EEPROM_writeByte(5, 128);
	mSleep(500);
	writeString_P_WIFI("Done!\n"); 
	writeString_P_WIFI("\nReading EEPROM address 5:\n");
	uint8_t tmp = I2C_EEPROM_readByte(5);
	mSleep(500);
	I2C_EEPROM_writeByte(5, 0);
	writeString_P_WIFI("Done!\n"); 
	writeString_P_WIFI("EEPROM address 5 content: ");
	writeInteger_WIFI(tmp, DEC);
	writeString_P_WIFI("\n"); 

	// Buzzer test:
    soundBuzzer(Tone_Cis2, 300, 200);
    soundBuzzer(Tone_Fis2, 200, 100);
    soundBuzzer(Tone_Ais2, 100, 100);
    soundBuzzer(Tone_Dis3, 50, 100);
	mSleep(1000);
    soundBuzzer(Tone_Dis3, 300, 200);
    soundBuzzer(Tone_Ais2, 200, 100);
    soundBuzzer(Tone_Fis2, 100, 100);
    soundBuzzer(Tone_Cis2, 50, 100);

	while(true) 
	{
		if(getStopwatch1() > 1000) // 1s
		{
			if (onoff) onoff = 0;
			else onoff = 1;

			// Buttons ADC test:
			clearLCD();
			pressedButtonNumber = getPressedButtonNumber();
			setCursorPosLCD(0, 0);
			writeStringLCD("Button: ");
			writeIntegerLCD(pressedButtonNumber, DEC);
			setCursorPosLCD(1, 0);
			writeStringLCD("ADC: ");
			writeIntegerLCD(adcButtons, DEC);

			// 3V3 voltage sensor ADC test:
			v3v3 = measure3V3();
			writeString_WIFI("\n3V3 Voltage: ");
			writeDouble_WIFI(v3v3, 4, 1);
			writeString_WIFI("V\nADC 3V3: ");
			writeInteger_WIFI(adc3v3, DEC);

			// Touch sensor ADC test:
			touch = getTouch();
			if (touch) writeString_WIFI("\nTOUCHED!!!");
			else writeString_WIFI("\nNOT touched.");
			writeString_WIFI("\nADC Touch: ");
			writeInteger_WIFI(adcTouch, DEC);

			// Temperature sensor test:
			temperature = TCN75_measure();		// Measure
			writeString_WIFI("\nTemperature: ");
			writeDouble_WIFI(temperature, 5, 1);
			writeString_WIFI("°\n");

			// Servo controller test:
			//   LEDs:
			if (onoff) {
				setMultiIOLED1(1);
				setMultiIOLED2(0);
				setMultiIOLED3(0);
				setMultiIOLED4(1);
			}
			else
				setMultiIOLEDs(0b0110);
			//   Servo 1:
			setServo(1, servopos);
			servopos += 10;
			if (servopos > SERVO1_RT) servopos = SERVO1_LT;

			// RTC test:
			DS1307_read();
			writeString_WIFI("RTC: ");
			writeIntegerLength_WIFI(rtc_time.hour, DEC, 2);
			writeString_WIFI(":");
			writeIntegerLength_WIFI(rtc_time.minute, DEC, 2);
			writeString_WIFI(":");
			writeIntegerLength_WIFI(rtc_time.second, DEC, 2);
			writeString_WIFI("  ");
			writeIntegerLength_WIFI(rtc_date.day, DEC, 2);
			writeString_WIFI(".");
			writeIntegerLength_WIFI(rtc_date.month, DEC, 2);
			writeString_WIFI(".");
			writeIntegerLength_WIFI(rtc_date.year, DEC, 4);
			writeString_WIFI("\n");

			// Voltage & current sensor test:
			LTC2990_measure();
			writeString_WIFI("Temperature: ");
			writeDouble_WIFI(tint, 5, 1);
			writeString_WIFI("°\n");
			writeString_WIFI("BAT Current: ");
			writeDouble_WIFI(cbat, 6, 1);
			writeString_WIFI("mA\nBAT Voltage: ");
			writeDouble_WIFI(vbat, 4, 1);
			writeString_WIFI( "V\nSERVO Volt.: ");
			writeDouble_WIFI(vservo, 4, 1);
			writeString_WIFI( "V\nVCC Voltage: ");
			writeDouble_WIFI(vcc, 4, 1);
			writeString_WIFI("V\n");

			setStopwatch1(0);
		}

		task_I2CTWI();
	}

	return 0;
}
Erklärung

Linienfolger Board Software

... BETA ...

Demo
Erklärung

Bumper Board Software

... BETA ...

Demo
Erklärung

Radio Board Software

... BAUSTELLE ... BAUSTELLE ... BAUSTELLE ...

Demo
Erklärung

Library für die Messung von Umweltdaten

... BAUSTELLE ... BAUSTELLE ... BAUSTELLE ...

Library Header
Library Source
Erklärung
Demo
Erklärung

Library für die Orientierung im Raum

... BAUSTELLE ... BAUSTELLE ... BAUSTELLE ...

Library Header
Library Source
Erklärung
Demo
Erklärung

DCF77-Library

... BAUSTELLE ... BAUSTELLE ... BAUSTELLE ...

RP6 CCPRO M128

Die RP6-CCPRO-M128 (= "M128") kann über den I2C-Bus alle I2C-Sensoren und I2C-Aktoren ansteuern und hat mit ihren freien Ressourcen (Portpins) gute Voraussetzungen, um die weiteren Funktionen der Multi IO Platine zu nutzen. Dazu wird sie (wenn alle Funktionen gleichzeitig genutzt werden sollen) mit zwei Steckverbindungen angeschlossen:

  • IO-Mxxx <-> I/O
  • ADC-Mxxx <-> ADC

Dadurch ergeben sich umfangreiche Möglichkeiten, die Sensoren der Multi IO Platine auszulesen und Aktoren zu schalten. Die folgenden 2 Tabellen zeigen die Verbindungen:

Stecker IO-Mxxx:

Stecker-Pin M128-Port M128-Funktion Port-Bit Multi IO-Funktion I/O
1 PB5 OC1A 13 DCF77 I
2 PD7 T2 31 LFS_PWR O
3 PB6 OC1B 14 SHARPS_PWR O
4 PD6 T1 30 SNAKE_SWITCH O
5 PE3 ** OC3A/AIN1 35 BUZZER O
6 PD4 ICP1 28 (TX *)
7 PD3 TXD1/INT3 27 SNAKE_KEY / TX I/O
8 PD2 RXD1/INT2 26 RX I
9 GND
10 VDD

Zu *) TX nicht an Pin 6 des I/O Steckers der M128 vorhanden!

Zu **) Auf der M128 ist hier ebenfalls der Piezo-Signalgeber (SND) angeschlossen! Es ist nur möglich, den Signalgeber auf der Multi IO Platine zu nutzen, wenn SND auf der M128 deaktiviert wurde (Jumper EN_SND auf der M128 abziehen)!

Stecker ADC-Mxxx:

Stecker-Pin M128-Port M128-Funktion Port-Bit Multi IO-Funktion I/O
1 PF1 ADC1 41 TOUCH / LFS_L I
2 PF7 ADC7 47 3V3 alt.2 I
3 PF3 ADC3 43 3V3 / LFS_M I
4 PF0 ADC0 40 BUMPER_L I/O *
5 PF5 ADC5 45 LFS_R I
6 PF2 ADC2 42 n.c.
7 PF6 ADC6 46 BUTTONS I
8 PF4 ADC4 44 BUMPER_R I/O *
9 GND
10 VDD

Zu *) Eingang für Bumper-Taster, Ausgang für Bumper-LED!

Library

Demo

... BAUSTELLE ... BAUSTELLE ... BAUSTELLE ...

RP6 CONTROL M32

Die RP6-Control-M32 (= "M32") kann über den I2C-Bus alle I2C-Sensoren und I2C-Aktoren ansteuern und hat mit ihren freien Ressourcen (Portpins) gute Voraussetzungen, um die weiteren Funktionen der Multi IO Platine zu nutzen. Dazu wird sie (wenn alle Funktionen gleichzeitig genutzt werden sollen) mit zwei Steckverbindungen angeschlossen:

  • IO-Mxxx <-> I/O
  • ADC-Mxxx <-> ADC

Dadurch ergeben sich umfangreiche Möglichkeiten, die Sensoren der Multi IO Platine auszulesen und Aktoren zu schalten. Die folgenden 2 Tabellen zeigen die Verbindungen:

Stecker IO-Mxxx:

Stecker-Pin M32-Port M32-Funktion Multi IO-Funktion I/O
1 PC7 TOSC2 DCF77 I
2 GND
3 PC5 TDI SHARPS_PWR O
4 PC6 TOSC1 SNAKE_SWITCH O
5 PC3 TMS BUZZER O
6 PC4 TDO (TX *)
7 PC2 TCK SNAKE_KEY / (TX *) I
8 PD6 ICP (RX *)
9 PD5 OC1A LFS_PWR O
10 VDD

Zu *) UART nicht am I/O Stecker der M32 vorhanden!

Stecker ADC-Mxxx:

Stecker-Pin M32-Port M32-Funktion Multi IO-Funktion I/O
1 PA3 ADC3 TOUCH / LFS_L I
2 PA2 ADC2 3V3 alt.2 I
3 PA4 ADC4 3V3 / LFS_M I
4 GND
5 PA5 ADC5 LFS_R I
6 GND
7 PA6 ADC6 BUTTONS I
8 GND
9 PA7 ADC7 3V3 alt.1 I
10 VDD

Multi IO Projekt Library

Diese Avr-gcc Library für das Multi IO Projekt Board (= "MultiIO") geht von folgenden Voraussetzungen aus:

  • Die RP6-Control-M32 (= "M32") wird für die Ansteuerung der MultiIO benutzt.
  • Die M32 ist der I2C-Bus Master.
  • Die I2C-Bus Geschwindigkeit beträgt 100 kHz.
  • Alle Hardware-Komponenten der MultiIO sind aufgebaut (1).
  • Alle Jumper auf der MultiIO sind in ihrer Standardstellung (2).
  • Die MultiIO und die M32 sind mit dem XBUS des RP6-Systems 1:1 verbunden.
  • Der Wannenstecker IO_Mxxx der MultiIO ist mit dem Wannenstecker I/O der M32 1:1 verbunden.
  • Der Wannenstecker ADC_Mxxx der MultiIO ist mit dem Wannenstecker ADC der M32 1:1 verbunden.
Zu (1): Wenn nicht alle Komponenten aufgebaut sind, sind die zugehörigen
        Funktionen natürlich nicht funktionsfähig und können nicht benutzt
        werden.
Zu (2): Siehe Hardware-Teil!

Die Library (Software-Bibliothek) besteht aus drei Teilen:

Configuration Header

Datei: RP6Control_MultiIO.h:

/* 
 * ****************************************************************************
 * RP6 ROBOT SYSTEM - RP6 CONTROL M32 Examples
 * ****************************************************************************
 * Example: RP6Control MultiIO Library
 * Author(s): Dirk
 * ****************************************************************************
 * Description:
 * Configuration header file for new MultiIO Project Board library.
 *
 * ****************************************************************************
 */

#ifndef RP6CONTROL_MULTIIO_H
#define RP6CONTROL_MULTIIO_H


/*****************************************************************************/
// MultiIO hardwired components:
// - I2C Voltage & Current Sensor (LTC2990)
// - I2C Real Time Clock (RTC DS1307Z)
// - I2C Temperature Sensor (TCN75A)
// - I2C Servo Controller (PCA9685)
// - I2C EEPROM (24LCXXX)
// - 3V3 Voltage Sensor
// - Touch Sensor (with NE555)
// - Buttons
// - LEDs
// - Buzzer

/*****************************************************************************/
// I2C Voltage & Current Sensor (LTC2990):
#define I2C_MULTIIO_VCS_ADR				0x98	// ADR1/0 = 0/0
//#define I2C_MULTIIO_VCS_ADR				0x9a	// ADR1/0 = 0/1
//#define I2C_MULTIIO_VCS_ADR				0x9c	// ADR1/0 = 1/0
//#define I2C_MULTIIO_VCS_ADR				0x9e	// ADR1/0 = 1/1
//#define I2C_MULTIIO_VCS_ADR				0xee	// Global sync address

// (Voltage divider and shunt resistor!)
#define SHUNT_R							0.051		// 0.051 Ohm
#define V1_ADJUST						2.0			// (10+10)/10 kOhm
#define V2_ADJUST						2.0			// (10+10)/10 kOhm
#define VBAT_ADJUST						3.2			// (22+10)/10 kOhm
#define VSERVO_ADJUST					2.5			// (15+10)/10 kOhm

/*****************************************************************************/
// I2C Real Time Clock (RTC DS1307Z):
#define I2C_MULTIIO_RTC_ADR				0xD0	// Default

/*****************************************************************************/
// I2C Temperature Sensor (TCN75A):
// (A1 always 0!)
#define I2C_MULTIIO_TEMP_ADR			0x90	// A2/0 = 0/0
//#define I2C_MULTIIO_TEMP_ADR			0x92	// A2/0 = 0/1
//#define I2C_MULTIIO_TEMP_ADR			0x98	// A2/0 = 1/0
//#define I2C_MULTIIO_TEMP_ADR			0x9a	// A2/0 = 1/1

/*****************************************************************************/
// I2C Servo Controller (PCA9685):
// (A5, A4, A3, A2 always 0!)
#define I2C_MULTIIO_SERVO_ADR			0x80	// A1/0 = 0/0
//#define I2C_MULTIIO_SERVO_ADR			0x82	// A1/0 = 0/1
//#define I2C_MULTIIO_SERVO_ADR			0x84	// A1/0 = 1/0
//#define I2C_MULTIIO_SERVO_ADR			0x86	// A1/0 = 1/1
//#define I2C_MULTIIO_SERVO_ADR			0xe0	// ALLCALLADR

// (Servo power is connected to LED8 of the PCA9685!)
#define CHSERVOPWR						9

// Servo left touch (LT), right touch (RT), middle position (MP) constants:
// (Hints: - Servo impulse length [ms] = Servo position value / 204.8
//           (Formula only valid for a PWM of 50 Hz!)
//         - Min. servo impulse (0,7 ms) = Servo position 143
//         - Mid. servo impulse (1,5 ms) = Servo position 307
//         - Max. servo impulse (2,3 ms) = Servo position 471
//         - !!! You should NOT use servo position values < 143 or > 471 !!!)
#define SERVO1_LT						205		// Servo impulse ~1ms
#define SERVO1_RT						410		// Servo impulse ~2ms
#define SERVO1_MP						((SERVO1_RT - SERVO1_LT) / 2 + SERVO1_LT)
#define SERVO2_LT						205
#define SERVO2_RT						410
#define SERVO2_MP						((SERVO2_RT - SERVO2_LT) / 2 + SERVO2_LT)
#define SERVO3_LT						205
#define SERVO3_RT						410
#define SERVO3_MP						((SERVO3_RT - SERVO3_LT) / 2 + SERVO3_LT)
#define SERVO4_LT						205
#define SERVO4_RT						410
#define SERVO4_MP						((SERVO4_RT - SERVO4_LT) / 2 + SERVO4_LT)
#define SERVO5_LT						205
#define SERVO5_RT						410
#define SERVO5_MP						((SERVO5_RT - SERVO5_LT) / 2 + SERVO5_LT)
#define SERVO6_LT						205
#define SERVO6_RT						410
#define SERVO6_MP						((SERVO6_RT - SERVO6_LT) / 2 + SERVO6_LT)
#define SERVO7_LT						205
#define SERVO7_RT						410
#define SERVO7_MP						((SERVO7_RT - SERVO7_LT) / 2 + SERVO7_LT)
#define SERVO8_LT						205
#define SERVO8_RT						410
#define SERVO8_MP						((SERVO8_RT - SERVO8_LT) / 2 + SERVO8_LT)

/*****************************************************************************/
// I2C EEPROM (24LCXXX):
// (A2=1 not usable with 24LC1024-P!)
#define I2C_MULTIIO_EEPROM_ADR			0xA0	// A2/1/0 = 0/0/0
//#define I2C_MULTIIO_EEPROM_ADR			0xA2	// A2/1/0 = 0/0/1
//#define I2C_MULTIIO_EEPROM_ADR			0xA4	// A2/1/0 = 0/1/0
//#define I2C_MULTIIO_EEPROM_ADR			0xA6	// A2/1/0 = 0/1/1
//#define I2C_MULTIIO_EEPROM_ADR			0xA8	// A2/1/0 = 1/0/0
//#define I2C_MULTIIO_EEPROM_ADR			0xAA	// A2/1/0 = 1/0/1
//#define I2C_MULTIIO_EEPROM_ADR			0xAC	// A2/1/0 = 1/1/0
//#define I2C_MULTIIO_EEPROM_ADR			0xAE	// A2/1/0 = 1/1/1

// I2C-EEPROM storage capacity [kbit]:
#define I2C_EEPROM_KBIT					32		// 24LC32-P <== Default
//#define I2C_EEPROM_KBIT					64		// 24LC64-P
//#define I2C_EEPROM_KBIT					128		// 24LC128-P
//#define I2C_EEPROM_KBIT					256		// 24LC256-P
//#define I2C_EEPROM_KBIT					512		// 24LC512-P
//#define I2C_EEPROM_KBIT					1024	// 24LC1024-P

// I2C-EEPROM pagesize [byte]:
// ATTENTION: The pagesize must fit to the EEPROM type defined above!
#define I2C_EEPROM_PAGESIZE				32		// EEPROM 32 or 64 kbit
//#define I2C_EEPROM_PAGESIZE				64		// EEPROM 128 or 256 kbit
//#define I2C_EEPROM_PAGESIZE				128		// EEPROM 512 kbit
//#define I2C_EEPROM_PAGESIZE				256		// EEPROM 1024 kbit

/*****************************************************************************/
// 3V3 Voltage Sensor:
#define ADC_MULTIIO_3V3					ADC_4	// ADC-Mxxx: ADC
//#define ADC_MULTIIO_3V3					ADC_7	// ADC-Mxxx: ADC
//#define ADC_MULTIIO_3V3					ADC_2	// ADC-Mxxx: ADC

/*****************************************************************************/
// Touch Sensor (with NE555):
#define ADC_MULTIIO_TOUCH				ADC_3	// ADC-Mxxx: ADC

#define ADCVAL_NOTOUCH					14
#define ADCVAL_TOUCH					1022
#define ADCVAL_LIMIT_T					((ADCVAL_TOUCH - ADCVAL_NOTOUCH) / 2 + ADCVAL_NOTOUCH)

/*****************************************************************************/
// Buttons:
#define ADC_MULTIIO_BUTTONS				ADC_6	// ADC-Mxxx: ADC

#define ADCVAL_BUTTON1					13
#define ADCVAL_BUTTON2					581
#define ADCVAL_BUTTON3					743
#define ADCVAL_BUTTON4					820
#define ADCVAL_LIMIT12					((ADCVAL_BUTTON2 - ADCVAL_BUTTON1) / 2 + ADCVAL_BUTTON1)
#define ADCVAL_LIMIT23					((ADCVAL_BUTTON3 - ADCVAL_BUTTON2) / 2 + ADCVAL_BUTTON2)
#define ADCVAL_LIMIT34					((ADCVAL_BUTTON4 - ADCVAL_BUTTON3) / 2 + ADCVAL_BUTTON3)
#define ADCVAL_LIMIT40					((1023 - ADCVAL_BUTTON4) / 2 + ADCVAL_BUTTON4)

/*****************************************************************************/
// LEDs:
// (Status LED1..LED4 are connected to LED15..LED12 of the PCA9685!)
#define CHLED1							16
#define CHLED2							15
#define CHLED3							14
#define CHLED4							13

/*****************************************************************************/
// Buzzer:
// (The IO-Mxxx plug is connected to the M32 I/O plug!)
#define IO_MULTIIO_BUZZER_IN			IO_PC3	// IO-Mxxx: I/O
#define IO_MULTIIO_BUZZER_DDR			DDRC
#define IO_MULTIIO_BUZZER_PORT			PORTC

/*****************************************************************************/
// Other ADC channel definitions:
// (Depending on jumper settings on the MultiIO Project Board!)
// (The ADC-Mxxx plug is connected to the M32 ADC plug!)
#define ADC_MULTIIO_LFS_L				ADC_3	// ADC-Mxxx: ADC
#define ADC_MULTIIO_LFS_M				ADC_4	// ADC-Mxxx: ADC
#define ADC_MULTIIO_LFS_R				ADC_5	// ADC-Mxxx: ADC

// Other IO portpin definitions:
// (The IO-Mxxx plug is connected to the M32 I/O plug!)
#define IO_MULTIIO_LFS_PWR_IN			IO_PD5	// IO-Mxxx: I/O
#define IO_MULTIIO_LFS_PWR_DDR			DDRD
#define IO_MULTIIO_LFS_PWR_PORT			PORTD

#define IO_MULTIIO_SHARPS_PWR_IN		IO_PC5	// IO-Mxxx: I/O
#define IO_MULTIIO_SHARPS_PWR_DDR		DDRC
#define IO_MULTIIO_SHARPS_PWR_PORT		PORTC

#define IO_MULTIIO_SNAKE_SWITCH_IN		IO_PC6	// IO-Mxxx: I/O
#define IO_MULTIIO_SNAKE_SWITCH_DDR		DDRC
#define IO_MULTIIO_SNAKE_SWITCH_PORT	PORTC

#define IO_MULTIIO_SNAKE_KEY_IN			IO_PC2	// IO-Mxxx: I/O
#define IO_MULTIIO_SNAKE_KEY_DDR		DDRC
#define IO_MULTIIO_SNAKE_KEY_PIN		PINC

#define IO_MULTIIO_DCF77_IN				IO_PC7	// IO-Mxxx: I/O
#define IO_MULTIIO_DCF77_DDR			DDRC
#define IO_MULTIIO_DCF77_PIN			PINC

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

#endif

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

/*****************************************************************************/
// EOF
Library Header

Datei RP6Control_MultiIOLib.h:

/* 
 * ****************************************************************************
 * RP6 ROBOT SYSTEM - RP6 CONTROL M32 Examples
 * ****************************************************************************
 * Example: RP6Control MultiIO Library
 * Author(s): Dirk
 * ****************************************************************************
 * Description:
 * Header file for new MultiIO Project Board library.
 *
 * ****************************************************************************
 */

#ifndef RP6CONTROL_MULTIIOLIB_H
#define RP6CONTROL_MULTIIOLIB_H


/*****************************************************************************/
// MultiIO hardwired components:
// - I2C Voltage & Current Sensor (LTC2990)
// - I2C Real Time Clock (RTC DS1307Z)
// - I2C Temperature Sensor (TCN75A)
// - I2C Servo Controller (PCA9685)
// - I2C EEPROM (24LCXXX)
// - 3V3 Voltage Sensor
// - Touch Sensor (with NE555)
// - Buttons
// - LEDs
// - Buzzer

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

#include "RP6ControlLib.h"
#include "RP6I2CmasterTWI.h"
#include "RP6Control_MultiIO.h"

/*****************************************************************************/
// I2C Voltage & Current Sensor (LTC2990):

// Registers:
#define LTC2990_STATUS					0
#define LTC2990_CONTROL					1
#define LTC2990_TRIGGER					2
#define LTC2990_TINT_MSB				4
#define LTC2990_TINT_LSB				5
#define LTC2990_V1_MSB					6
#define LTC2990_V1_LSB					7
#define LTC2990_V2_MSB					8
#define LTC2990_V2_LSB					9
#define LTC2990_V3_MSB					10
#define LTC2990_V3_LSB					11
#define LTC2990_V4_MSB					12
#define LTC2990_V4_LSB					13
#define LTC2990_VCC_MSB					14
#define LTC2990_VCC_LSB					15

// Status register bitmasks:
#define LTC2990_STATUS_DEFAULT			0
#define LTC2990_STATUS_BUSY				1
#define LTC2990_STATUS_TINT_READY		2
#define LTC2990_STATUS_V1V2_READY		4
#define LTC2990_STATUS_V2_READY			8
#define LTC2990_STATUS_V3V4_READY		16
#define LTC2990_STATUS_V4_READY			32
#define LTC2990_STATUS_VCC_READY		64

// Control register bitmasks:
#define LTC2990_CONTROL_DEFAULT			0
#define LTC2990_CONTROL_MULTIIO			0b01011010 // Mode V1-V2, V3, V4
												   // All measurements per mode
												   // Single acquisition
#define LTC2990_CONTROL_MODE02_DEFAULT	0
#define LTC2990_CONTROL_MODE34_DEFAULT	0
#define LTC2990_CONTROL_REPEAT_SINGLE	64
#define LTC2990_CONTROL_TEMP_FORMAT		128

extern double tint;
extern double cbat;
extern double vbat;
extern double vservo;
extern double vcc;

void LTC2990_write_cfg(uint8_t);
#define LTC2990_init() {LTC2990_write_cfg(LTC2990_CONTROL_MULTIIO);}
void LTC2990_run(void);
void LTC2990_read(void);
void LTC2990_calculate(void);
void LTC2990_measure(void);

/*****************************************************************************/
// I2C Real Time Clock (RTC DS1307Z):

// Registers:
#define DS1307_SECONDS					0
#define DS1307_MINUTES					1
#define DS1307_HOURS					2
#define DS1307_DAY						3
#define DS1307_DATE						4
#define DS1307_MONTH					5
#define DS1307_YEAR						6
#define DS1307_CONTROL					7
#define DS1307_RAM						8

// Control register bitmasks:
#define DS1307_CONTROL_DEFAULT			0
#define DS1307_CONTROL_RS0				1
#define DS1307_CONTROL_RS1				2
#define DS1307_CONTROL_SQWE				16
#define DS1307_CONTROL_OUT				128

enum RTCWEEKDAYS {
	R_MO = 1, R_TU, R_WE, R_TH, R_FR, R_SA, R_SU
};

typedef struct {
	uint16_t         year;				// Year
	uint8_t          month;				// Month   [1..12]
	enum RTCWEEKDAYS weekday;			// Weekday [1..7 = R_MO..R_SU]
	uint8_t          day;				// Day     [1..31]
} rtcdate_t;
rtcdate_t rtc_date;

typedef struct {
	uint8_t dst;						// Daylight-saving-time (time zone)
	uint8_t hour;						// Hour    [0..23]
	uint8_t minute;						// Minute  [0..59]
	uint8_t second;						// Second  [0..59]
} rtctime_t;
rtctime_t rtc_time;

uint8_t BCD2DEC(uint8_t);
uint8_t DEC2BCD(uint8_t);
void DS1307_write_cfg(uint8_t);
void DS1307_init(void);
#define CALC_DST						// Time zone will be calculated
void DS1307_read(void);
void DS1307_write(void);
uint8_t DS1307_readRAM(uint8_t);
void DS1307_writeRAM(uint8_t, uint8_t);

/*****************************************************************************/
// I2C Temperature Sensor (TCN75A):

// Registers:
#define TCN75_TEMP						0
#define TCN75_CONFIG					1
#define TCN75_HYST						2
#define TCN75_LIMIT						3

// Config register bitmasks:
#define TCN75_CONFIG_RUN				0		// Default
#define TCN75_CONFIG_SHUTDOWN			1
#define TCN75_CONFIG_COMP				0		// Default
#define TCN75_CONFIG_INT				2
#define TCN75_CONFIG_ALERT_LOW			0		// Default
#define TCN75_CONFIG_ALERT_HIGH			4
#define TCN75_CONFIG_FAULT_1			0		// Default
#define TCN75_CONFIG_FAULT_2			8
#define TCN75_CONFIG_FAULT_4			16
#define TCN75_CONFIG_FAULT_6			24

// Only for the TCN75A - high resolution and OneShot mode:
#define TCN75A_CONFIG_RES_9				0		// Default
#define TCN75A_CONFIG_RES_10			32		// 0b00100000
#define TCN75A_CONFIG_RES_11			64		// 0b01000000
#define TCN75A_CONFIG_RES_12			96		// 0b01100000
#define TCN75A_CONFIG_ONESHOT_DISABLED	0		// Default
#define TCN75A_CONFIG_ONESHOT			128		// 0b10000000

extern double temperature;

void TCN75_write_cfg(uint8_t);
#define TCN75_shutdown() {TCN75_write_cfg(TCN75_CONFIG_SHUTDOWN);}
#define TCN75_run(__CONFIG__) {TCN75_write_cfg(__CONFIG__);}
extern uint8_t temperature_low;
extern uint8_t temperature_high;
#define getTemperatureHigh() (temperature_high)
#define getTemperatureLow() (temperature_low)
void TCN75_read(void);
double TCN75_calculate(void);
double TCN75_measure(void);

/*****************************************************************************/
// I2C Servo Controller (PCA9685):

// Registers:
#define PCA9685_MODE1					0
#define PCA9685_MODE2					1
#define PCA9685_SUBADR1					2
#define PCA9685_SUBADR2					3
#define PCA9685_SUBADR3					4
#define PCA9685_ALLCALLADR				5
#define PCA9685_LED0_ON_L				6
#define PCA9685_LED0_ON_H				7
#define PCA9685_LED0_OFF_L				8
#define PCA9685_LED0_OFF_H				9
#define PCA9685_LED1_ON_L				10
#define PCA9685_LED1_ON_H				11
#define PCA9685_LED1_OFF_L				12
#define PCA9685_LED1_OFF_H				13
#define PCA9685_LED2_ON_L				14
#define PCA9685_LED2_ON_H				15
#define PCA9685_LED2_OFF_L				16
#define PCA9685_LED2_OFF_H				17
#define PCA9685_LED3_ON_L				18
#define PCA9685_LED3_ON_H				19
#define PCA9685_LED3_OFF_L				20
#define PCA9685_LED3_OFF_H				21
#define PCA9685_LED4_ON_L				22
#define PCA9685_LED4_ON_H				23
#define PCA9685_LED4_OFF_L				24
#define PCA9685_LED4_OFF_H				25
#define PCA9685_LED5_ON_L				26
#define PCA9685_LED5_ON_H				27
#define PCA9685_LED5_OFF_L				28
#define PCA9685_LED5_OFF_H				29
#define PCA9685_LED6_ON_L				30
#define PCA9685_LED6_ON_H				31
#define PCA9685_LED6_OFF_L				32
#define PCA9685_LED6_OFF_H				33
#define PCA9685_LED7_ON_L				34
#define PCA9685_LED7_ON_H				35
#define PCA9685_LED7_OFF_L				36
#define PCA9685_LED7_OFF_H				37
#define PCA9685_LED8_ON_L				38
#define PCA9685_LED8_ON_H				39
#define PCA9685_LED8_OFF_L				40
#define PCA9685_LED8_OFF_H				41
#define PCA9685_LED9_ON_L				42
#define PCA9685_LED9_ON_H				43
#define PCA9685_LED9_OFF_L				44
#define PCA9685_LED9_OFF_H				45
#define PCA9685_LED10_ON_L				46
#define PCA9685_LED10_ON_H				47
#define PCA9685_LED10_OFF_L				48
#define PCA9685_LED10_OFF_H				49
#define PCA9685_LED11_ON_L				50
#define PCA9685_LED11_ON_H				51
#define PCA9685_LED11_OFF_L				52
#define PCA9685_LED11_OFF_H				53
#define PCA9685_LED12_ON_L				54
#define PCA9685_LED12_ON_H				55
#define PCA9685_LED12_OFF_L				56
#define PCA9685_LED12_OFF_H				57
#define PCA9685_LED13_ON_L				58
#define PCA9685_LED13_ON_H				59
#define PCA9685_LED13_OFF_L				60
#define PCA9685_LED13_OFF_H				61
#define PCA9685_LED14_ON_L				62
#define PCA9685_LED14_ON_H				63
#define PCA9685_LED14_OFF_L				64
#define PCA9685_LED14_OFF_H				65
#define PCA9685_LED15_ON_L				66
#define PCA9685_LED15_ON_H				67
#define PCA9685_LED15_OFF_L				68
#define PCA9685_LED15_OFF_H				69
#define PCA9685_ALL_LED_ON_L			250
#define PCA9685_ALL_LED_ON_H			251
#define PCA9685_ALL_LED_OFF_L			252
#define PCA9685_ALL_LED_OFF_H			253
#define PCA9685_PRE_SCALE				254
#define PCA9685_TESTMODE				255

// Mode1 register bitmasks:
#define PCA9685_MODE1_ALLCALL			1
#define PCA9685_MODE1_SUB3				2
#define PCA9685_MODE1_SUB2				4
#define PCA9685_MODE1_SUB1				8
#define PCA9685_MODE1_SLEEP				16
#define PCA9685_MODE1_AI				32
#define PCA9685_MODE1_EXTCLK			64
#define PCA9685_MODE1_RESTART			128

// Mode2 register bitmasks:
#define PCA9685_MODE2_OUTNE01_DEFAULT	0
#define PCA9685_MODE2_OUTDRV			4
#define PCA9685_MODE2_OCH				8
#define PCA9685_MODE2_INVRT				16

#define F_PCA9685						25000000.0	// Int. Clock: 25 MHz

void PCA9685_init(uint16_t);
#define initServo(__FREQ__) {PCA9685_init(__FREQ__);}
void PCA9685_set(uint8_t, uint16_t);
#define setServo(__SERVO__,__POS__) {PCA9685_set(__SERVO__,__POS__);}
void PCA9685_shutdown(void);
void PCA9685_restart(void);
void setServoPower(uint8_t);

/*****************************************************************************/
// I2C EEPROM (24LCXXX):

uint8_t I2C_EEPROM_readByte(uint16_t memAddr);
void I2C_EEPROM_writeByte(uint16_t memAddr, uint8_t data);
void I2C_EEPROM_readBytes(uint16_t startAddr, uint8_t *buffer, uint8_t length);
void I2C_EEPROM_writeBytes(uint16_t startAddr, uint8_t *buffer, uint8_t length);

/*****************************************************************************/
// 3V3 Voltage Sensor:

extern uint16_t adc3v3;
extern double v3v3;

uint16_t get3V3Sensor(void);
double calculate3V3(void);
double measure3V3(void);

/*****************************************************************************/
// Touch Sensor (with NE555):

extern uint16_t adcTouch;
extern uint8_t touch;

uint8_t getTouch(void);

/*****************************************************************************/
// Buttons:

extern uint16_t adcButtons;
extern uint8_t releasedMultiIOButtonNumber;
extern uint8_t pressedMultiIOButtonNumber;

uint8_t getMultiIOPressedButtonNumber(void);
uint8_t checkMultiIOPressedButtonEvent(void);
uint8_t checkMultiIOReleasedButtonEvent(void);

/*****************************************************************************/
// LEDs:

void setMultiIOLEDs(uint8_t leds);

void dimMultiIOLED(uint8_t led, uint16_t duty);
void setMultiIOLED1(uint8_t led);
void setMultiIOLED2(uint8_t led);
void setMultiIOLED3(uint8_t led);
void setMultiIOLED4(uint8_t led);

/*****************************************************************************/
// Buzzer:

void Buzzer_init(void);
void buzzer(uint16_t);

/*****************************************************************************/
// MultiIO Project Board initialisation:

void multiio_init(void);

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

#endif

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

/*****************************************************************************/
// EOF
Library Source

Datei RP6Control_MultiIOLib.c:

/* 
 * ****************************************************************************
 * RP6 ROBOT SYSTEM - RP6 CONTROL M32 Examples
 * ****************************************************************************
 * Example: RP6Control MultiIO Library
 * Author(s): Dirk
 * ****************************************************************************
 * Description:
 * 
 * This is our new Library that contains basic routines and functions for
 * accessing the hardwired components of the MultiIO Project Board.
 *
 * There are much more sensors, that may be connected to the MultiIO Project
 * Board: Line following sensors (5x CNY70), bumpers, "Snake Vision board",
 *        LDRs, I2C air pressure sensor, I2C humidity sensor, DCF77 module,
 *        I2C IMU, I2C ultrasonic distance sensors, GPS module and more
 *        sensors connected to free ADCs and IOs and to the I2C bus.
 * This library doesn't contain functions for these sensors, because they are
 * not HARDWIRED to the MultiIO Project Board and may be connected OPTIONALLY.
 *
 * ****************************************************************************
 */

/*****************************************************************************/
// MultiIO hardwired components:
// - I2C Voltage & Current Sensor (LTC2990)
// - I2C Real Time Clock (RTC DS1307Z)
// - I2C Temperature Sensor (TCN75A)
// - I2C Servo Controller (PCA9685)
// - I2C EEPROM (24LCXXX)
// - 3V3 Voltage Sensor
// - Touch Sensor (with NE555)
// - Buttons
// - LEDs
// - Buzzer

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

#include "RP6Control_MultiIOLib.h" 		

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

uint8_t registerBuf[13]; 

/*****************************************************************************/
// I2C Voltage & Current Sensor (LTC2990):

/**
 * Sends the configuration byte to a LTC2990.
 *
 * Input: Config byte for control register
 *
 * There is also a macro LTC2990_init(), which
 * initializes the sensor to work in V1-V2, V3,
 * V4 and Single Acquisition mode.
 *
 * Example:
 *   LTC2990_init();
 *
 */
void LTC2990_write_cfg(uint8_t config)
{
	I2CTWI_transmit2Bytes(I2C_MULTIIO_VCS_ADR, LTC2990_CONTROL, config);
}

uint8_t vcs_tint_low;
uint8_t vcs_tint_high;
uint8_t vcs_v1_low;
uint8_t vcs_v1_high;
uint8_t vcs_v2_low;
uint8_t vcs_v2_high;
uint8_t vcs_v3_low;
uint8_t vcs_v3_high;
uint8_t vcs_v4_low;
uint8_t vcs_v4_high;
uint8_t vcs_vcc_low;
uint8_t vcs_vcc_high;

/**
 * Starts a Single Acquisition measurement.
 */
void LTC2990_run(void)
{
	I2CTWI_transmit2Bytes(I2C_MULTIIO_VCS_ADR, LTC2990_TRIGGER, 0);
}

/**
 * Reads all data registers of the voltage & current
 * sensor (VCS).
 * They are stored in the variables defined above.
 */
void LTC2990_read(void)
{
	I2CTWI_transmitByte(I2C_MULTIIO_VCS_ADR, LTC2990_TINT_MSB);
	I2CTWI_readBytes(I2C_MULTIIO_VCS_ADR, registerBuf, 12);
	vcs_tint_high = registerBuf[0];
	vcs_tint_low = registerBuf[1];
	vcs_v1_high = registerBuf[2];
	vcs_v1_low = registerBuf[3];
	vcs_v2_high = registerBuf[4];
	vcs_v2_low = registerBuf[5];
	vcs_v3_high = registerBuf[6];
	vcs_v3_low = registerBuf[7];
	vcs_v4_high = registerBuf[8];
	vcs_v4_low = registerBuf[9];
	vcs_vcc_high = registerBuf[10];
	vcs_vcc_low = registerBuf[11];
}

double tint;							// Internal temperature
double cbat;							// Current at 9V
double vbat;							// Battery voltage 9V (BAT)
double vservo;							// Servo voltage 5 .. 7.5V
double vcc;								// Voltage 5V (VCC)

/**
 * Calculates the temperature, voltage and current
 * values by using the data read from the LTC2990
 * with the function LTC2990_read(). The sensor is
 * configured to work in V1-V2, V3, V4 and Single
 * Acquisition mode.
 * The result is stored in the double variables
 * defined above.
 */
void LTC2990_calculate(void)
{
	int16_t tmp, tmp2;
	double v1, v2;

	tmp = (((vcs_tint_high & 0x1f) << 8) + vcs_tint_low) << 3;
	tmp = tmp / 8;
	tint = tmp / 16.0;							// Internal temperature [°C]

	tmp = (((vcs_v1_high & 0x7f) << 8) + vcs_v1_low) << 1;
	tmp = tmp / 2;
	v1 = tmp * 0.01942;
	v1 *= V1_ADJUST;							// Voltage divider factor
	tmp2 = (((vcs_v2_high & 0x7f) << 8) + vcs_v2_low) << 1;
	tmp2 = tmp2 / 2;
	v2 = tmp * 0.01942;
	v2 *= V2_ADJUST;							// Voltage divider factor
	cbat = (v1 - v2) / SHUNT_R;				// Battery current [mA]

	tmp = ((vcs_v3_high & 0x3f) << 8) + vcs_v3_low;
	vbat = tmp * 0.00030518;					// Battery voltage [V]
	vbat *= VBAT_ADJUST;						// Voltage divider factor

	tmp = ((vcs_v4_high & 0x3f) << 8) + vcs_v4_low;
	vservo = tmp * 0.00030518;					// Servo voltage [V]
	vservo *= VSERVO_ADJUST;					// Voltage divider factor

	tmp = ((vcs_vcc_high & 0x3f) << 8) + vcs_vcc_low;
	vcc = 2.5 + tmp * 0.00030518;				// VCC [V]
}

/**
 * Performs a complete measurement with the sensor
 * configured to work in V1-V2, V3, V4 and Single
 * Acquisition mode.
 * The result is stored in the double variables
 * defined above.
 * This function is BLOCKING for about 200 ms!
 * If you don't want a blocking measurement, you
 * have to write your own function with a non
 * blocking pause between starting measurement
 * and reading the result or with another mode
 * of operation (Repeated Acquisitions).
 */
void LTC2990_measure(void)
{
	LTC2990_run();								// Start measurement
	mSleep(200);
	LTC2990_read();								// Read data
	LTC2990_calculate();						// Calculate values
}

/*****************************************************************************/
// I2C Real Time Clock (RTC DS1307Z):

/**
 * This function converts a BCD to a DEC value.
 *
 */
uint8_t BCD2DEC(uint8_t bcd)
{
	return ((bcd >> 4) * 10 + (bcd & 0x0f));
}

/**
 * This function converts a DEC to a BCD value.
 *
 */
uint8_t DEC2BCD(uint8_t dec)
{uint8_t units = dec % 10;
	if (dec /= 10) {
		return (units + (DEC2BCD(dec) << 4));
	}
	else {
		return units;
	}
}

/**
 * Sends the configuration byte to a DS1307.
 *
 * Input: Config byte for control register
 *
 */
void DS1307_write_cfg(uint8_t config)
{
	I2CTWI_transmit2Bytes(I2C_MULTIIO_RTC_ADR, DS1307_CONTROL, config);
}

/**
 * Initializes the DS1307 by resetting all registers.
 * Only use this function ONCE for a DS1307 without or
 * with empty backup battery!
 */
void DS1307_init(void)
{
	uint8_t i;

	for (i = 0; i < 8; i++) {
		registerBuf[i] = 0;
	}
	I2CTWI_transmitBytes(I2C_MULTIIO_RTC_ADR, &registerBuf[0], 8);
}

/**
 * Reads all data registers of the Real Time Clock (RTC).
 * They are stored in the time & date variables defined in
 * the library header.
 */
void DS1307_read(void)
{
	I2CTWI_transmitByte(I2C_MULTIIO_RTC_ADR, DS1307_SECONDS);
	I2CTWI_readBytes(I2C_MULTIIO_RTC_ADR, registerBuf, 7);
	rtc_time.second = BCD2DEC(registerBuf[0] & 0x7f);
	rtc_time.minute = BCD2DEC(registerBuf[1]);
	rtc_time.hour = BCD2DEC(registerBuf[2] & 0x3f);
	rtc_date.weekday = registerBuf[3];
	rtc_date.day = BCD2DEC(registerBuf[4]);
	rtc_date.month = BCD2DEC(registerBuf[5]);
	rtc_date.year = BCD2DEC(registerBuf[6]) + 2000;
	rtc_time.dst = 0;
#ifdef CALC_DST
	// Calculate MESZ (DST):
	uint8_t wday = rtc_date.weekday;			// Weekday [1..7 = R_MO..R_SU]
	if(wday == 7) wday = 0;
	if(rtc_date.month < 3 || rtc_date.month > 10) {
		return;
	}
	if((rtc_date.day - wday >= 25)
	 && (wday || rtc_time.hour >= 2)) {
		if(rtc_date.month == 10)
			return;
	}
	else {
		if(rtc_date.month == 3) {
			return;
		}
	}
	rtc_time.dst = 1;
#endif
}

/**
 * Writes the time & date infos in the variables defined in
 * the library header to the Real Time Clock (RTC).
 */
void DS1307_write(void)
{
	registerBuf[0] = DS1307_SECONDS;
	registerBuf[1] = DEC2BCD(rtc_time.second);
	registerBuf[2] = DEC2BCD(rtc_time.minute);
	registerBuf[3] = DEC2BCD(rtc_time.hour);
	registerBuf[4] = rtc_date.weekday;
	registerBuf[5] = DEC2BCD(rtc_date.day);
	registerBuf[6] = DEC2BCD(rtc_date.month);
	registerBuf[7] = DEC2BCD(rtc_date.year - 2000);
	I2CTWI_transmitBytes(I2C_MULTIIO_RTC_ADR, &registerBuf[0], 8);
}

/**
 * Reads and returns a data byte from the DS1307 RAM.
 *
 * Input: adr -> RAM address [0..55]
 *
 * Hints: - The real DS1307 RAM addresses are 8..63!
 *        - The RAM is nonvolatile. That means, that
 *          it keeps the data as long as the backup
 *          battery doesn't become weak!
 *
 */
uint8_t DS1307_readRAM(uint8_t adr)
{
	if (adr > 55) adr = 0;
	I2CTWI_transmitByte(I2C_MULTIIO_RTC_ADR, (DS1307_RAM + adr));
	return (I2CTWI_readByte(I2C_MULTIIO_RTC_ADR));
}

/**
 * Writes a data byte to the DS1307 RAM.
 *
 * Input: adr  -> RAM address [0..55]
 *        data -> Data byte [0..255]
 *
 * Hints: - The real DS1307 RAM addresses are 8..63!
 *        - The RAM is nonvolatile. That means, that
 *          it keeps the data as long as the backup
 *          battery doesn't become weak!
 *
 */
void DS1307_writeRAM(uint8_t adr, uint8_t data)
{
	if (adr > 55) adr = 0;
	I2CTWI_transmit2Bytes(I2C_MULTIIO_RTC_ADR, (DS1307_RAM + adr), data);
}

/*****************************************************************************/
// I2C Temperature Sensor (TCN75A):

/**
 * Sends the configuration byte to a TCN75A.
 *
 * Input: Config byte for config register
 *
 */
void TCN75_write_cfg(uint8_t config)
{
	I2CTWI_transmit2Bytes(I2C_MULTIIO_TEMP_ADR, TCN75_CONFIG, config);
}

uint8_t temperature_low;
uint8_t temperature_high;

/**
 * Reads the two data registers of the temperature
 * sensor.
 * They are stored in the variables temperature_low
 * and _high.
 *
 * Hint: Depending on the sensor configuration the
 *       data are located different in the two bytes
 *       - have a look at the datasheet!
 *
 */
void TCN75_read(void)
{
	I2CTWI_transmitByte(I2C_MULTIIO_TEMP_ADR, TCN75_TEMP);
	I2CTWI_readBytes(I2C_MULTIIO_TEMP_ADR, registerBuf, 2);
	temperature_low = registerBuf[0];
	temperature_high = registerBuf[1];
}

double temperature;						// Temperature [°C]

/**
 * Calculates and returns the temperature value
 * by using the data read from the TCN75A with
 * the function TCN75_read(). The sensor is
 * configured to Single Conversion and 12 bit
 * measurement.
 */
double TCN75_calculate(void)
{
	uint8_t templow;
	double temp;

	templow = getTemperatureLow();
	if (templow & 128)							// Calculate temperature
		templow = (templow & 63) - 127;
	else
		templow = templow & 63;
	temp = templow + (0.0625 * (getTemperatureHigh() >> 4));
	return temp;
}

/**
 * Performs a 12 bit measurement and returns the
 * temperature [°C].
 * This function is BLOCKING for about 250 ms!
 * If you don't want a blocking measurement, you
 * have to write your own function with a non
 * blocking pause between starting measurement
 * and reading the result or with another mode
 * of operation (Continuous Conversion).
 */
double TCN75_measure(void)
{
	TCN75_run(TCN75A_CONFIG_RES_12);			// Start measurement
	mSleep(250);
	TCN75_shutdown();							// Stop measurement
	TCN75_read();								// Read data
	return (TCN75_calculate());					// Calculate value
}

/*****************************************************************************/
// I2C Servo Controller (PCA9685):

/**
 * Call this once before using the servo function.
 *
 * Input: PWM frequency [40..1000 Hz]
 *
 * Hints: - Default servo frequency is 50 Hz!
 *        - The servo power is NOT switched on by
 *          this function!
 *
 * There is also a macro initServo(freq), which
 * does exactly the same as this function.
 *
 * Example:
 *   initServo(50);
 *
 */
void PCA9685_init(uint16_t freq)
{
	if ((freq < 40) || (freq > 1000)) freq = 50;
	I2CTWI_transmitByte(I2C_MULTIIO_SERVO_ADR, PCA9685_MODE2);
	uint8_t last_mode = I2CTWI_readByte(I2C_MULTIIO_SERVO_ADR);
	last_mode &= ~PCA9685_MODE2_INVRT;			// Clear INVRT bit
	last_mode |= PCA9685_MODE2_OUTDRV;			// Set OUTDRV bit
	I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_MODE2, last_mode);
	I2CTWI_transmitByte(I2C_MULTIIO_SERVO_ADR, PCA9685_MODE1);
	last_mode = I2CTWI_readByte(I2C_MULTIIO_SERVO_ADR);
	last_mode |= PCA9685_MODE1_AI;				// Set AI bit
	uint8_t mode1 = last_mode;
	mode1 |= PCA9685_MODE1_SLEEP;				// Set SLEEP bit
	I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_MODE1, mode1);
	uint8_t prescale = (uint8_t) (F_PCA9685 / 4096 / freq - 0.5);
	I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_PRE_SCALE, prescale);
	last_mode &= ~PCA9685_MODE1_SLEEP;			// Clear SLEEP bit
	I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_MODE1, last_mode);
	mSleep(1);
	last_mode |= PCA9685_MODE1_RESTART;			// Clear RESTART bit
	I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_MODE1, last_mode);
	I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_LED8_ON_H, 0x10);
	return;
}

/**
 * This is the servo position set function.
 *
 * Input: servo -> Servo number [1..8, 10..16]
 *        pos   -> Servo position [SERVOx_LT..SERVOx_RT]
 *
 * Hints: - Servo number 9 cannot be set by this function!
 *          Please use setServoPower() function instead!
 *        - A servo position of 205 means 1 ms servo impulse,
 *          a position of 410 means a 2 ms servo impulse!
 *          You may calculate the servo impulse length by:
 *          ==> Impulse [ms] = servo position / 204.8 <==
 *          (Formula only valid for a PWM of 50 Hz!)
 *
 * There is also a macro setServo(servo, pos), which
 * does exactly the same as this function.
 *
 * Example:
 *   setServo(2,300);
 *
 */
void PCA9685_set(uint8_t servo, uint16_t pos)
{
	if ((servo == 0) || (servo == CHSERVOPWR) || (servo > 16))
		return;
	uint8_t reg = servo * 4 + 4;				// Register LEDx_OFF_L
	I2CTWI_transmit3Bytes(I2C_MULTIIO_SERVO_ADR, reg, (pos & 0x00ff), (pos >> 8));
}

/**
 * If the servos are not moving for a while, the
 * servo function can be stopped with this
 * function (PCA9685 set to sleep mode).
 *
 * Hint: The servo power is NOT switched off by
 *       this function!
 *
 */
void PCA9685_shutdown(void)
{
	I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_ALL_LED_OFF_H, 0x10);
	I2CTWI_transmitByte(I2C_MULTIIO_SERVO_ADR, PCA9685_MODE1);
	uint8_t mode1 = I2CTWI_readByte(I2C_MULTIIO_SERVO_ADR);
	mode1 |= PCA9685_MODE1_SLEEP;				// Set SLEEP bit
	I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_MODE1, mode1);
}

/**
 * If the servo function was stopped with the
 * function PCA9685_shutdown() before, it can be
 * (re)started again with this function.
 *
 * Hint: The servo power is NOT switched on by
 *       this function!
 *
 */
void PCA9685_restart(void)
{
	I2CTWI_transmitByte(I2C_MULTIIO_SERVO_ADR, PCA9685_MODE1);
	uint8_t mode1 = I2CTWI_readByte(I2C_MULTIIO_SERVO_ADR);
	if (mode1 & PCA9685_MODE1_RESTART) {		// RESTART bit set?
		mode1 &= ~PCA9685_MODE1_SLEEP;			// Clear SLEEP bit
		I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_MODE1, mode1);
		mSleep(1);
		mode1 |= PCA9685_MODE1_RESTART;			// Clear RESTART bit
		I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_MODE1, mode1);
		I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_ALL_LED_OFF_H, 0);
	}
}

/** 
 * With this function you can switch the servo
 * power on or off, if the servo power jumper on
 * the board enables this feature.
 *
 * Input: pwr -> 0 (false) = servo power off
 *               >0 (true) = servo power on
 *
 * Hints: - If connected servos are not used, you
 *          should always switch the servo power off
 *          to save energy!
 *        - The PCA9685 is NOT restarted or put into
 *          shutdown mode by this function!
 *
 */
void setServoPower(uint8_t pwr)
{
	if (pwr > 0)
		I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_LED8_OFF_H, 0);
	else
		I2CTWI_transmit2Bytes(I2C_MULTIIO_SERVO_ADR, PCA9685_LED8_OFF_H, 0x10);
}	

/*****************************************************************************/
// I2C EEPROM (24LCXXX):

// The following EEPROM types may be used:
//  EEPROM Size:  Chip              Pagesize
//  -   32 kbit:  ST24LC32A            32
//  -   64 kbit:  ST24LC64             32
//  -  128 kbit:  ST24LC128            64
//  -  256 kbit:  ST24LC256            64
//  -  512 kbit:  ST24LC512           128
//  - 1024 kbit:  AT24LC1024          256
// ! You may choose the EEPROM type in the I2C EEPROM !
// ! section of the RP6Control_MultiIO.h file!           !

/**
 * Reads a single Byte from the EEPROM.
 */
uint8_t I2C_EEPROM_readByte(uint16_t memAddr)
{
	uint8_t data;
	I2CTWI_transmit2Bytes(I2C_MULTIIO_EEPROM_ADR, (memAddr >> 8), memAddr);
	data = I2CTWI_readByte(I2C_MULTIIO_EEPROM_ADR);
	return data;
}

/**
 * Write a single data byte to the specified EEPROM address.
 */
void I2C_EEPROM_writeByte(uint16_t memAddr, uint8_t data)
{
	I2CTWI_transmit3Bytes(I2C_MULTIIO_EEPROM_ADR, (memAddr >> 8), memAddr, data);
	mSleep(5);
}

/**
 * Reads "length" Bytes into the Buffer "buffer" from startAddr on. 
 * You can read the complete EEPROM into a buffer at once - if it is large enough. 
 * (But you only have 2KB SRAM on a MEGA32 ;) )
 * If "length" is higher than I2CTWI_BUFFER_REC_SIZE defined in RP6I2CmasterTWI.h,
 * you have to adapt I2CTWI_BUFFER_REC_SIZE to the highest used "length" value!
 */
void I2C_EEPROM_readBytes(uint16_t startAddr, uint8_t *buffer, uint8_t length)
{
	I2CTWI_transmit2Bytes(I2C_MULTIIO_EEPROM_ADR, (startAddr >> 8), startAddr);
	I2CTWI_readBytes(I2C_MULTIIO_EEPROM_ADR, &buffer[0], length);
}

/**
 * Write "length" Bytes from the Buffer to the EEPROM. 
 * YOU CAN ONLY WRITE MAXIMAL [I2C_EEPROM_PAGESIZE] BYTES AT ONCE!!!
 * This is the Pagesize!
 * You can NOT cross a page boundary!
 * If (length + 2) is higher than I2CTWI_BUFFER_SIZE defined in RP6I2CmasterTWI.h,
 * you have to adapt I2CTWI_BUFFER_SIZE to the highest used (length + 2) value!
 */
void I2C_EEPROM_writeBytes(uint16_t startAddr, uint8_t *buffer, uint8_t length)
{
	uint8_t i, addrbuffer[length + 2];
	addrbuffer[0] = (startAddr >> 8);
	addrbuffer[1] = startAddr;
	for(i = 0; i < length; i++) {
		addrbuffer[i + 2] = buffer[i];
	}
	I2CTWI_transmitBytes(I2C_MULTIIO_EEPROM_ADR, &addrbuffer[0], (length + 2));
	mSleep(5);
}

/*****************************************************************************/
// 3V3 Voltage Sensor:

uint16_t adc3v3;						// 3V3 voltage sensor ADC value

/**
 * This function reads and returns the ADC value of
 * the 3V3 voltage sensor. The value is also stored
 * in adc3v3.
 *
 */
uint16_t get3V3Sensor(void)
{
	adc3v3 = readADC(ADC_MULTIIO_3V3);
	return adc3v3;
}

double v3v3;							// 3V3 voltage [V]

/**
 * Calculates and returns the 3.3V voltage value
 * by using the data read from the 3V3 voltage
 * sensor with the function get3V3Sensor().
 *
 */
double calculate3V3(void)
{
	return (5.0 / 1024.0 * adc3v3);
}

/**
 * Measures and returns the 3.3V voltage value.
 * The ADC value of the 3V3 voltage sensor is also
 * stored in adc3v3.
 *
 */
double measure3V3(void)
{
	adc3v3 = readADC(ADC_MULTIIO_3V3);
	return (5.0 / 1024.0 * adc3v3);
}

/*****************************************************************************/
// Touch Sensor (with NE555):

uint16_t adcTouch;						// Touch sensor ADC value
uint8_t touch = 0;						// True (1), if touched

/**
 * Checks if the touch sensor antenna is touched - returns 1,
 * if touched or 0, if the antenna is NOT touched.
 *
 */
uint8_t getTouch(void)
{
	adcTouch = readADC(ADC_MULTIIO_TOUCH);
	if (adcTouch > ADCVAL_LIMIT_T) return 1;
	else return 0;
}

/*****************************************************************************/
// Buttons:

uint16_t adcButtons;					// Keypad ADC value
uint8_t releasedMultiIOButtonNumber;	// Released (last pressed) button
uint8_t pressedMultiIOButtonNumber;		// Actually pressed button

/**
 * Checks which button is pressed - returns the button number,
 * or 0, if no button is pressed.
 * Maybe the values of ADCVAL_LIMITxx have to change because
 * of variations in the resistors of the keypad! This is done
 * in RP6Control_MultiIO.h, if you define other ADC values for
 * your 4 buttons in ADCVAL_BUTTON1..ADCVAL_BUTTON4.
 *
 */
uint8_t getMultiIOPressedButtonNumber(void)
{
	adcButtons = readADC(ADC_MULTIIO_BUTTONS);
	if(adcButtons < 1020) {
		nop();
		nop();
		nop();
		adcButtons += readADC(ADC_MULTIIO_BUTTONS);
		adcButtons >>= 1;
	}
	if(adcButtons < ADCVAL_LIMIT12)
		return 1;
	if(adcButtons < ADCVAL_LIMIT23)
		return 2;
	if(adcButtons < ADCVAL_LIMIT34)
		return 3;
	if(adcButtons < ADCVAL_LIMIT40)
		return 4;
	return 0;
}

/**
 * This function has to be called frequently out of the
 * main loop and checks if a button is pressed! It only returns 
 * the button number a single time, DIRECTLY when the button is
 * pressed.
 * 
 * This is useful for non-blocking keyboard check in the
 * main loop. You don't need something like 
 * "while(getMultiIOPressedButtonNumber());" to wait for the
 * button to be released again!
 */
uint8_t checkMultiIOPressedButtonEvent(void)
{
	static uint8_t pressed_button = 0;
	if(pressed_button) {
		if(!getMultiIOPressedButtonNumber()) 
			pressed_button = 0;
	}
	else {
		pressed_button = getMultiIOPressedButtonNumber();
		if(pressed_button)
			return pressed_button;
	}
	return 0;
}

/**
 * This function has to be called frequently out of
 * the main loop and checks if a button is pressed AND
 * released. It only returns the button number a single
 * time, AFTER the button has been released.
 * 
 * This is useful for non-blocking keyboard check in the
 * main loop. You don't need something like 
 * "while(getMultiIOPressedButtonNumber());" to wait for the
 * button to be released again!
 */
uint8_t checkMultiIOReleasedButtonEvent(void)
{
	static uint8_t released_button = 0;
	if(released_button) {
		if(!getMultiIOPressedButtonNumber()) {
			uint8_t tmp = released_button;
			released_button = 0;
			return tmp;
		}
	}
	else
		released_button = getMultiIOPressedButtonNumber();
	return 0;
}

/*****************************************************************************/
// LEDs:

/** 
 * Set the 4 status LEDs of the MultiIO.
 *
 * Example:
 *			setMultiIOLEDs(0b1010);
 *			// this clears LEDs 1 and 3
 *          // and sets LEDs 2 and 4!
 *
 */
void setMultiIOLEDs(uint8_t leds)
{
	if (leds & 0b00000001) PCA9685_set(CHLED1, 4095);
	else PCA9685_set(CHLED1, 0);
	if (leds & 0b00000010) PCA9685_set(CHLED2, 4095);
	else PCA9685_set(CHLED2, 0);
	if (leds & 0b00000100) PCA9685_set(CHLED3, 4095);
	else PCA9685_set(CHLED3, 0);
	if (leds & 0b00001000) PCA9685_set(CHLED4, 4095);
	else PCA9685_set(CHLED4, 0);
}

/** 
 * Dim the 4 status LEDs of the MultiIO.
 *
 * Input: led  -> LED number [1..4]
 *        duty -> Duty cycle [0..4095]
 *
 * Example:
 *			dimMultiIOLED(2,2048);
 *			// this dims LED2 with a
 *          // duty cycle of 50% !
 *
 */
void dimMultiIOLED(uint8_t led, uint16_t duty)
{
	if (led == 1) PCA9685_set(CHLED1, duty);
	if (led == 2) PCA9685_set(CHLED2, duty);
	if (led == 3) PCA9685_set(CHLED3, duty);
	if (led == 4) PCA9685_set(CHLED4, duty);
}

/** 
 * Set ONLY LED1, don't change anything for the other LEDs.
 *
 * Input: led -> 0 (false) = LED off
 *               >0 (true) = LED on
 *
 */
void setMultiIOLED1(uint8_t led)
{
	if (led > 0) PCA9685_set(CHLED1, 4095); 
	else PCA9685_set(CHLED1, 0);	
}	

/** 
 * Set ONLY LED2, don't change anything for the other LEDs.
 */
void setMultiIOLED2(uint8_t led)
{
	if (led > 0) PCA9685_set(CHLED2, 4095); 
	else PCA9685_set(CHLED2, 0);	
}	

/** 
 * Set ONLY LED3, don't change anything for the other LEDs.
 */
void setMultiIOLED3(uint8_t led)
{
	if (led > 0) PCA9685_set(CHLED3, 4095); 
	else PCA9685_set(CHLED3, 0);	
}	

/** 
 * Set ONLY LED4, don't change anything for the other LEDs.
 */
void setMultiIOLED4(uint8_t led)
{
	if (led > 0) PCA9685_set(CHLED4, 4095); 
	else PCA9685_set(CHLED4, 0);	
}

/*****************************************************************************/
// Buzzer:

/**
 * Call this once before using the buzzer.
 *
 */
void Buzzer_init(void)
{
	IO_MULTIIO_BUZZER_DDR |= IO_MULTIIO_BUZZER_IN;
	IO_MULTIIO_BUZZER_PORT &= ~IO_MULTIIO_BUZZER_IN;
}

/**
 * You can use this function to make the buzzer beep ;)
 * with a frequency of about 1000 Hz.
 * This function is BLOCKING and generates a delay for the
 * sound.
 *
 * Input: time  -> sound length [ms]
 *
 * Example:
 *   buzzer(150);
 *
 */
void buzzer(uint16_t time)
{
	if (!time) return;
	while (time--) {
		IO_MULTIIO_BUZZER_PORT |= IO_MULTIIO_BUZZER_IN;
		sleep(5);
		IO_MULTIIO_BUZZER_PORT &= ~IO_MULTIIO_BUZZER_IN;
		sleep(5);
	}
}

/*****************************************************************************/
/*****************************************************************************/
// MultiIO Project Board initialisation:

/**
 * You MUST call this function at the beginning of a
 * main program, that uses the MultiIO Project Board. 
 *
 */
void multiio_init(void)
{
	// Voltage & current sensor:
	LTC2990_init();								// Init VCS
	// Servo Controller:
	PCA9685_init(50);							// Init PWM 50 Hz
	// Servo power:
	setServoPower(0);							// Servo power off
	// Buzzer:
	Buzzer_init();								// Init buzzer
}

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

/******************************************************************************
 * Additional info
 * ****************************************************************************
 * Changelog:
 * - v. 1.0 (initial release) 23.02.2013 by Dirk
 *
 * ****************************************************************************
 */

/*****************************************************************************/
// EOF
Erklärung
Demo

makefile:

...
TARGET = TARGET = RP6Control_MultiIO
...
SRC += RP6Control_MultiIOLib.c
...

Datei RP6Control_MultiIO.c:

/* 
 * ****************************************************************************
 * RP6 ROBOT SYSTEM - RP6 CONTROL M32 Examples
 * ****************************************************************************
 * Example: RP6Control MultiIO
 * Author(s): Dirk
 * ****************************************************************************
 * Description:
 * In this example we show a first test for the MultiIO Project Board.
 * 
 * ############################################################################
 * 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 "RP6ControlLib.h" 				// The RP6 Control Library. 
										// Always needs to be included!
#include "RP6I2CmasterTWI.h"			// Include the I2C-Bus Master Library

/*****************************************************************************/
/*****************************************************************************/
// Include our new "RP6Control MultiIO library":
// (This is the library for accessing the MultiIO Project Board!)

#include "RP6Control_MultiIOLib.h"

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

/**
 * Write a floating point number to the UART.
 *
 * Example:
 *
 *			// Write a floating point number to the UART (no exponent):
 *			writeDouble(1234567.890, 11, 3);
 *
 * The value of prec (precision) defines the number of decimal places.
 * For 32 bit floating point variables (float, double ...) 6 is
 * the max. value for prec (7 relevant digits).
 * The value of width defines the overall number of characters in the
 * floating point number including the decimal point. The number of
 * pre-decimal positions is: (width - prec - 1).
 */
void writeDouble(double number, uint8_t width, uint8_t prec)
{char buffer[width + 1];
	dtostrf(number, width, prec, &buffer[0]);
	writeString(&buffer[0]);
}

/*****************************************************************************/
// I2C Error handler

/**
 * This function gets called automatically if there was an I2C Error like
 * the slave sent a "not acknowledge" (NACK, error codes e.g. 0x20 or 0x30).
 * The most common mistakes are: 
 *   - using the wrong address for the slave
 *   - slave not active or not connected to the I2C-Bus
 *   - too fast requests for a slower slave
 * Be sure to check this if you get I2C errors!
 */
void I2C_transmissionError(uint8_t errorState)
{
	writeString_P("\nI2C ERROR --> TWI STATE IS: 0x");
	writeInteger(errorState, HEX);
	writeChar('\n');
}

/*****************************************************************************/
// 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!

	setLEDs(0b1111);
	mSleep(500);
	setLEDs(0b0000);

	writeString_P("\n\nRP6Control Multi IO Selftest 1!\n"); 

	// IMPORTANT:
	I2CTWI_initMaster(100); // Initialize the TWI Module for Master operation
							// with 100kHz SCL Frequency


	// Register the event handler:
	I2CTWI_setTransmissionErrorHandler(I2C_transmissionError);

	setLEDs(0b1111);

	// Write a text message to the LCD:
	showScreenLCD("################", "################");
	mSleep(1500);
	showScreenLCD(" RP6Control M32", "Example Program");
	mSleep(2500); 
	showScreenLCD("  RP6 Multi IO", "   Selftest 1");
	mSleep(2500);
	clearLCD();

	setLEDs(0b0000);

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

	uint8_t onoff = 0;
	uint16_t servopos = SERVO1_LT;

	startStopwatch1();

	// IMPORTANT:
	multiio_init();								// MultiIO init!!!
	//setServoPower(1);							// Servo power ON!

	// ----------------------------------------------
	// Set RTC once (battery empty or not existing:
	rtc_time.second = 0;
	rtc_time.minute = 0;
	rtc_time.hour = 12;				// 12:00
	rtc_date.weekday = R_TH;
	rtc_date.day = 10;
	rtc_date.month = 1;
	rtc_date.year = 2013;			// Do, 10.1.2013
	DS1307_write();
	// Remove this, if RTC is set and running!!!
	// ----------------------------------------------

	// EEPROM test:
	writeString_P("\nWriting 128 to EEPROM address 5:\n");
	I2C_EEPROM_writeByte(5, 128);
	mSleep(500);
	writeString_P("Done!\n"); 
	writeString_P("\nReading EEPROM address 5:\n");
	uint8_t tmp = I2C_EEPROM_readByte(5);
	mSleep(500);
	I2C_EEPROM_writeByte(5, 0);
	writeString_P("Done!\n"); 
	writeString_P("EEPROM address 5 content: ");
	writeInteger(tmp, DEC);
	writeString_P("\n"); 

	// Buzzer test:
    buzzer(330);
	mSleep(200);
    buzzer(330);
	mSleep(200);
    buzzer(330);
	mSleep(1000);
    buzzer(330);
	mSleep(200);
    buzzer(330);
	mSleep(200);
    buzzer(330);

	while(true) 
	{
		if(getStopwatch1() > 1000) // 1s
		{
			if (onoff) onoff = 0;
			else onoff = 1;

			// Buttons ADC test:
			clearLCD();
			pressedMultiIOButtonNumber = getMultiIOPressedButtonNumber();
			setCursorPosLCD(0, 0);
			writeStringLCD("Button: ");
			writeIntegerLCD(pressedMultiIOButtonNumber, DEC);
			setCursorPosLCD(1, 0);
			writeStringLCD("ADC: ");
			writeIntegerLCD(adcButtons, DEC);

			// 3V3 voltage sensor ADC test:
			v3v3 = measure3V3();
			writeString("\n3V3 Voltage: ");
			writeDouble(v3v3, 4, 1);
			writeString("V\nADC 3V3: ");
			writeInteger(adc3v3, DEC);

			// Touch sensor ADC test:
			touch = getTouch();
			if (touch) writeString("\nTOUCHED!!!");
			else writeString("\nNOT touched.");
			writeString("\nADC Touch: ");
			writeInteger(adcTouch, DEC);

			// Temperature sensor test:
			temperature = TCN75_measure();		// Measure
			writeString("\nTemperature: ");
			writeDouble(temperature, 5, 1);
			writeString("°\n");

			// Servo controller test:
			//   LEDs:
			if (onoff) {
				setMultiIOLED1(1);
				setMultiIOLED2(0);
				setMultiIOLED3(0);
				setMultiIOLED4(1);
			}
			else
				setMultiIOLEDs(0b0110);
			//   Servo 1:
			setServo(1, servopos);
			servopos += 10;
			if (servopos > SERVO1_RT) servopos = SERVO1_LT;

			// RTC test:
			DS1307_read();
			writeString("RTC: ");
			writeIntegerLength(rtc_time.hour, DEC, 2);
			writeString(":");
			writeIntegerLength(rtc_time.minute, DEC, 2);
			writeString(":");
			writeIntegerLength(rtc_time.second, DEC, 2);
			writeString("  ");
			writeIntegerLength(rtc_date.day, DEC, 2);
			writeString(".");
			writeIntegerLength(rtc_date.month, DEC, 2);
			writeString(".");
			writeIntegerLength(rtc_date.year, DEC, 4);
			writeString("\n");

			// Voltage & current sensor test:
			LTC2990_measure();
			writeString("Temperature: ");
			writeDouble(tint, 5, 1);
			writeString("°\n");
			writeString("BAT Current: ");
			writeDouble(cbat, 6, 1);
			writeString("mA\nBAT Voltage: ");
			writeDouble(vbat, 4, 1);
			writeString( "V\nSERVO Volt.: ");
			writeDouble(vservo, 4, 1);
			writeString( "V\nVCC Voltage: ");
			writeDouble(vcc, 4, 1);
			writeString("V\n");

			setStopwatch1(0);
		}

		task_I2CTWI();
	}

	return 0;
}
Erklärung

Servo-Library

RP6 BASE

Die RP6(v2) BASE (= "RP6") kann über den I2C-Bus alle I2C-Sensoren und I2C-Aktoren ansteuern. Da der RP6 nur über wenige freie Portpins verfügt, muss man eine Auswahl treffen, welche weiteren Funktionen man nutzen will.

Es gibt auf dem RP6 auch keine passenden Wannenstecker (wie auf der M32, M128 und M256), um auf einfache Weise eine mehrpolige Verbindung zu den IO-Mxxx, ADC-Mxxx oder ADC-M256 Steckern der Multi IO Platine herzustellen. Stattdessen kann man einzelne Portpins des RP6 mit der Multi IO Platine verbinden. Die folgende Tabelle zeigt mögliche Verbindungen:

RP6-Port RP6-Funktion RP6-Stecker:Pin I/O Bemerkungen Z.B. für Multi IO-Funktion
PA0 ADC0 ADC0:3 I/O Freier ADC oder IO BUTTONS, TOUCH, SHARPS_L/R, 3V3 ...
PA1 ADC1 ADC1:3 I/O Freier ADC oder IO LFS_L/M/R, SNAKE_L/R, LDR1/2 ...
PA4 ADC4 XBUS:8 I/O XBUS INT1! Falls nicht für den I2C-Bus benutzt: freier IO * SNAKE_SWITCH, SNAKE_KEY ...
PB1 T1 IO4 *** I Status LED5! Zusätzlich als Input z.B. für Taster nutzbar * BUMPER_L/R ...
PB7 SCK IO3 **, ISP:7 I Status LED4! Zusätzlich als Input z.B. für Taster nutzbar * BUMPER_L/R ...
PC4 TDO IO1 I Status LED1! Zusätzlich als Input z.B. für Taster nutzbar * SNAKE_KEY ...
PC5 TDI IO2 I Status LED2! Zusätzlich als Input z.B. für Taster nutzbar * DCF77 ...
PD0 RXD PRG/U:2 I/O UART RX! Nutzbar NUR, wenn USB-Interface abgezogen, als UART RX oder freier IO RX, SHARPS_PWR ...
PD1 TXD PRG/U:3 I/O UART TX! Nutzbar NUR, wenn USB-Interface abgezogen, als UART TX oder freier IO TX, LFS_PWR ...

Zu *) ACHTUNG: Bestimmte Beschaltung erforderlich! Sollte nur genutzt werden, wenn man sich gut mit dem RP6 auskennt!

Zu **) RP6v2: IO4!

Zu ***) RP6v2: IO5!

... BAUSTELLE ... BAUSTELLE ... BAUSTELLE ...

Hardware

Die Hardware des Multi-IO-Moduls muss erst verlötet werden. Bitte lese dafür eine ausführliche Lötanleitung! Diese finden sich u.a. im Netz: Löt-Tutorial Du musst nicht alle Komponenten einbauen! Du kannst diejenigen einbauen, welche du benötigst oder ausprobieren möchtest. Die Platine ist jederzeit erweiterbar. Nach dem Löten kann es sinnvoll sein, die Lötstellen durch „Plastik 70“-Spray vor Korrosion zu schützen.

Anschluß anderer Module

An den 10-poligen Wannensteckern IO_Mxxx (SV_IO_Mxxx ) und ADC_Mxxx (SV_ADC_Mxxx) an der Rückseite des Multi-IO-Moduls können IO- und ADC-Wannenstecker der Module RP6-Control-M32, RP6-CCPRO-M128 und M256-WiFi-Platine angesteckt werden. Der 10-polige IO-Wannenstecker „SV_SERVOSM32“ der M32 kann zusätzlich für acht Servos genutzt werden. Für die M256-WiFi-Platine steht ein zusätzlicher, 14-poliger Wannenstecker (SV_ADC_M256) zur Verfügung.

Benötigte Teile

Artikel Wofür Anzahl
10-poliges Flachbandkabel, ca. 20cm Für IO_Mxxx und ADC_Mxxx 2
10-poliger Wannenstecker Für IO_Mxxx und ADC_Mxxx 4
14-poliges Flachbandkabel, ca. 10cm Für XBUS und USRBUS 2
14-poliges Flachbandkabel, ca. 20cm Für ADC_M256 1
14-poliger Wannenstecker Für ADC_M256, XBUS und USRBUS 6
Evtl. 10-poliges Flachbandkabel, ca. 20cm Für Servos der M32 1
Evtl. 10-poliger Wannenstecker Für Servos der M32 2

Taster-Board

Das Taster-Board kann an der Vorderseite der Hauptplatine befestigt werden.

Benötigte Teile

Artikel Name Anzahl
Taster T1-T4 4
Widerstand SMD, 1206-Package, 10kΩ R20, 21, 34, 35 4
Evtl. 1x1 Buchse, RM2,54 P_T1, 2, 3, 4 4
Evtl. 1x1 Pin 90°, RM2,54 P_T1, 2, 3, 4 4

Beschreibung

Die vier Taster schalten eine Widerstandkaskade, welche als Spannungsteiler fungiert. Dadurch können sie – analog zu den Tastern der RP6-Control-M32 – mit nur einem ADC-Kanal gemessen werden. Das Board kann entweder mit den vier Lötpunkten am vorderen, linken Rand des Multi-IO-Moduls angelötet werden, oder mittels vier rechtwinkliger Pins in vier Buchsen dort eingesteckt werden.

Bumper-Board

Die Schraublöcher sind so angepasst, dass das Bumper-Board am Heck des RP6 angebracht werden kann.

Benötigte Teile

Artikel Name Anzahl
Bumper 2
Widerstand SMD, 1206-Package, 750Ω R30, 31 2
Widerstand SMD, 1206-Package, 270Ω R23, 24 2
LED SMD, 1206, low-current, rot LED7, 8 2
Pinreihe 1x7, RM2,54, stehend oder 90° P_BUMPER 1
Evtl. Pinreihe 1x4, RM2,54 P_BUMPER1, 2 2
Verwendung der Sharp-Sensoren
Artikel Name Anzahl
Transistor BC807, SOT23-Package Q1 1
Kondensator SMD, 1206-Package, 100nF C36 1
Kondensator SMD, EIA3528- od. 1206-Package, 10uF C37 1
Widerstand SMD, 1206-Package, 1kΩ R4 1
Jumper 1x2, RM2,54, stehend oder 90° J_SHARP-ON 1
Evtl. Pinreihe 1x3, RM2,54, für Sharp-Sensoren P_SHARP1, 2 2
Verwendung von Radarsensoren RSM1650
Artikel Name Anzahl
Transistor BC807, SOT23-Package Q1 1
Kondensator SMD, 1206-Package, 100nF C36 1
Kondensator SMD, EIA3528- od. 1206-Package, 10uF C37 1
Widerstand SMD, 1206-Package, 1kΩ R4 1
Jumper 1x2, RM2,54, stehend oder 90° J_SHARP-ON 1
Evtl. Pinreihe 1x3, RM2,54, für Sharp-Sensoren P_RADAR1, 2 2
Verwendung der SRF02
Artikel Name Anzahl
Kondensator SMD, 1206-Package, 100nF C3, 4 2
Pinreihe 1x5, RM2,54, für SRF02 P_SRF__1, 2 2

Beschreibung

Die Bumper-Taster haben drei Pins: Eingang (5V), Ausgang wenn gedrückt, Ausgang wenn nicht gedrückt. Hier werden nur der Eingang und der Ausgang im gedrückten Fall verwendet. Dieser schaltet dann auf die LEDs und die Pins 2 (rechts) und 3 (links) von P_BUMPER durch. Die LEDs können zusätzlich über den IO-Kanal angesprochen, also geschaltet werden (analog zur RP6(v2) BASE) . Es können zwei Sharp-Abstandssensoren angebracht werden, zwei Radar-Abstandssensoren oder zwei SRF02. Es werden dann nur die jeweiligen Kondensatoren und Pinreihen benötigt.

Verwendung der Sharp-Sensoren GP2Dxx

Werden die Sharp-Sensoren verwendet, sind die Kondensatoren C36 (100nF) und C37 (10uF) anzubringen sowie der Transistor Q1 (BC807) und der zugehörige Widerstand R4 (1kΩ). Die Sensoren können an den 1x3-Pinreihen P_SHARP1 und 2 angesteckt oder angelötet werden. Die Sharps können durch Jumper J_SHARP-ON oder durch den Transistor geschaltet werden.

Verwendung von Radar-Sensoren RSM1650

Werden die Radar-Sensoren verwendet, sind die Kondensatoren C36 (100nF) und C37 (10uF) anzubringen sowie der Transistor Q1 (BC807) und der zugehörige Widerstand R4 (1kΩ). Die Sensoren können an den 1x3-Pinreihen P_Radar1 und 2 angesteckt oder angelötet werden. Die Radarsensoren können durch Jumper J_SHARP-ON oder durch den Transistor geschaltet werden. Die dreipoligen Stiftleisten für die Radarsensoren haben leider eine etwas andere Belegung (VCC-Signal-GND) als die Sharp-Sensoren (VCC-GND-Signal) .

Verwendung der SRF02

Werden die SRF02 verwendet, können diese an P_SRF__1 und 2 angesteckt oder angelötet werden. Die Kondensatoren C3 und 4 (100nF) sind zu verwenden.

Anschluß auf Hauptplatine

Das Board kann mit einem 7-poligen Flachbandkabel am Multi-IO-Modul angesteckt werden. Dort kann via Jumper JP1 und JP2 gewählt werden, ob digitale (SRF02 via I2C) oder analoge Sensoren (SharpGP2D via ADC) benutzt werden. Die Verwendung von analogen Sensoren geht nur mit dem Modul M256-WiFi-Platine, da hier die ADC-Kanäle PF3 und PF4 des 14-poligen ADC-Wannensteckers verwendet werden.

Befestigt werden kann das Board mit zwei M3-Schrauben am Heck des RP6. Dafür benötigst du noch zwei Distanzbolzen mit M3-Gewinde und zugehörige Muttern (analog zur Befestigung des originalen Bumper-Boards auf der Vorderseite des Rp6). Diese kannst du von Innen am RP6 befestigen und danach das Bumper-Board anbringen.

Liniensucher-Board

Benötigte Teile

Für Verwendung von 3 Sensoren
Artikel Name Anzahl
CNY70 von Vishay IC8-10 3
Widerstand SMD, 1206-Package, 15kΩ R45, 46, 18 3
Widerstand SMD, 1206-Package, 15Ω R57 1
Widerstand SMD, 1206-Package, 240Ω R15 1
Widerstand SMD, 1206-Package, 47kΩ R47 1
LED SMD, 1206, gelb LED9 1
Kondensator SMD, 1206-Package, 100nF C28, 29, 30 3
Transistor BUZ172, SO220-Package Q9 1
Pinreihe 1x8, RM2,54, stehend oder 90° P_CNY_ALL1 1
Zusätzlich für die Verwendung von 5 Sensoren
Artikel Name Anzahl
CNY70 von Vishay IC11-12 2
Widerstand SMD, 1206-Package, 15kΩ R19, 43 2
Widerstand SMD, 1206-Package, 68Ω R56 1
Kondensator SMD, 1206-Package, 100nF C6, 7 2
Jumper 1x2, RM2,54, stehend oder 90° J_CNY 1

Beschreibung

Das Board besitzt drei CNY70 (L, M, R = IC8-10) sowie zwei weitere, durch Jumper zuschaltbare (L1 = IC11, R1 = IC 12). Die Spannungsversorgung (5V) kann durch einen Transistor (Q9) geschaltet werden. Eine LED (LED9) zeigt den Status On/Off an.

Die Reflexoptokoppler CNY70 können gut zur Linienerkennung (hell/dunkel) eigesetzt werden. Siehe dazu CNY70.

Anschluß auf Hauptplatine

Das Board kann durch ein 8-poliges Flachbandkabel auf dem Multi-IO-Modul angesteckt werden. Die Sensoren R1 und L1 können dabei nur mit dem M256-Modul verschaltet werden (freie ADC-Kanäle PF2 und PF3). Die Sensoren L, M und R können durch Jumper JP4 auf die ADC-Pins ADC_1, ADC_3 und ADC_5 gelegt werden (Pins 1, 3 und 5 des 10-poligen ADC_Mxxx-Wannensteckers).

Radio-Board

Benötigte Teile

Artikel Name Anzahl
SI4735 im SSOP24-Package U2 1
3,5mm Stereo-Buchse X2 1
Quarz, 32.768kHz, TC26H-Package Q5 1
TDA7050-NF-Amplifier, DIL8-Package IC4 1
Kondensator SMD, EIA3528- od. 1206-Package, 10uF C16, 25, 32 3
Kondensator SMD, EIA3528- od. 1206-Package, 47uF C40, 42 2
Spule SMD, C0402-Package, 180nH L1 1
Spule SMD, C0402-Package, 4,7uH L2 1
Kondensator SMD, 0402-Package, 220nF C8 1
Kondensator SMD, 0402-Package, 33pF C20 1
Kondensator SMD, 0402-Package, 18pF C19 1
Kondensator SMD, 0402-Package, 470nF C23 1
Kondensator SMD, 0402-Package, 22pF 18 1
Kondensator SMD, 0402-Package, 100nF 24 1
Widerstand SMD, 0402-Package, 22kΩ R29 1
Potentiometer SMD, 3223G-Package, 22kΩ R27, 28 2
Widerstand SMD, 1206-Package, 240Ω R37 1
LED SMD, 1206-Package LED2 1
Pinreihe 1x4, RM2,54 P_RADIO 1
Jumper 1x2, RM2,54 L-R-OUT, J_F-ANT, J_AM, P_GPIO 4
Jumper 1x1, RM2,54 P_ANT 1

Beschreibung

Das Radio-Board besitzt einen digitalen I2C-Radioempfänger (auf 3,3V-Pegel!!! ) U1 und einen Verstärker IC4. Eine Stab- oder Draht-Antenne kann an P_ANT angesteckt werden. Diese Antenne dient dann hauptsächlich dem FM-Empfang (UKW). Wird Jumper J_AM geschlossen, kann diese Antenne auch für den AM-Empfang (LW, MW, KW) mit genutzt werden.

Man kann aber für die AM-Bereiche auch eine separate Ferrit-Antenne an J_F-ANT anschließen. Dann muss der Jumper J_AM offen bleiben.

An der Buchse X2 können 3,5mm-Stereo-Kopfhörer (oder Lautsprecher) eingesteckt werden. An den Potentiometern R27 und 28 können die Lautstärken links und rechts eingestellt werden.

An den beiden Pins der Pinreihe P_GPIO können die beiden GPIOs 1 und 2 (3,3V-Pegel!) des Empfängers U1 genutzt werden.

An den Pins der Pinreihe L-R-OUT können die Signale für rechts und links abgegriffen werden.


Über die mit „0“ und „1“ bezeichneten Pads kann das I2C-Adressbit des SEN-Ausgangs des Empfängers gewählt werden. Hier einfach eine Überbrückung zu „0“ oder „1“ einlöten, wenn gewünscht.

Stromversorgung

Benötigte Teile

Artikel Name Anzahl
Sicherungshalter 20x5mm F1 1
Sicherung 20x5mm F1 1
Schalter S1 1
Schalter oder Jumper, 2x1 Pins, RM2,54 S2 1
2x2-Jumper, RM2,54 P_UB 1
Buchse 2mm/2,5mm B1 1
5V-Regler 78x5, TO220- oder TO92-Package U1 1
LED low current, 3mm LED1 1
Widerstand SMD, 1206-Package, 820 Ohm R1 1
Diode D1 1
Bei Bedarf: Jumper, 2x1 Pins, RM2,54 J_UB, J_UB2, J_VCC 3

Beschreibung

Ein externer Akku kann an die Pins P_UB angeschlossen werden (auf Polung achten!). Um ihn zu laden, kann ein Ladegerät an Buchse B1 angeschlossen werden, wobei dafür automatisch die Platine vom Akku getrennt wird.

Es ist auch möglich, einen Akku oder ein Netzgerät an B1 anzuschließen. Um dafür die genannte Trennung der Platine zu überbrücken, kann der Schalter S2 bzw. der dort angebrachte Jumper diese Verbindung herstellen.

Der Schalter S1 schaltet die Batteriespannung entweder des externen Akkus oder des RP6-Eigenen Akkus zum 5V-Regler U1 (jeder Regler der Baureihe 78x5 ist möglich) durch. Möchte man den Akku des RP6 verwenden, muss hierfür Jumper J_UB2 gesteckt sein.

Die LED LED1 zeigt an, ob der 5V-Regler U1 in Betrieb ist.

ACHTUNG: Es ist auch möglich, den RP6 mit dem am Multi-IO-Modul angeschlossenen externen Akku zu betreiben. Dafür muss Jumper J_UB gesteckt sein und es darf kein Akku im RP6 verbaut sein! Ansonsten können Bauteile und Akkus Schaden nehmen!

Des Weiteren können die meisten Bereiche (NICHT der Servobereich) mit der 5V-Versorgung des RP6 versorgt werden. Dafür den Jumper J_VCC einstecken, ein weiterer 5V-Regler auf dem Multi-IO-Modul ist dann nicht notwendig. Jedoch wird empfohlen, diesen Jumper nicht zu setzen, sondern einen eigenen 5V-Regler für dieses Modul zu verwenden.

Die Sicherung F1 sollte mindestens 3A zulassen (je nach Anforderung: werden keine Servomotoren verwendet, kann auch eine kleinere Sicherung verwendet werden).

Die Diode D1 lässt einen Stromfluss erst zu, wenn ein Akku falsch gepolt eingesteckt wird. Dann kommt es durch die Diode zum Kurzschluss und die Sicherung F1 verhindert Schäden an der Hardware.

USRBUS

Benötigte Teile

Artikel Name Anzahl
14polige Wannenbuchse SV_USRBUS1,2 2

Beschreibung

Die 14 Pins des USRBUS sind nicht belegt und stehen zur freien Verfügung. Durch sie kann man Signale des Multi-IO-Moduls mit anderen Modulen austauschen.

XBUS

Benötigte Teile

Artikel Name Anzahl
14polige Wannenbuchse SV_XBUS1,2 2

Beschreibung

Die Leitungen des XBUS sind analog zu den anderen RP6-Modulen. Es werden lediglich die I2C-Leitungen, der Int1, GND und (bei Bedarf) die Batteriespannung verwendet.

Es sind diverse Pinherausführungen für die I2C-Leitungen auf dem Multi-IO-Modul vorhanden.

Der 3,3V-I2C-Bus

Benötigte Teile

Artikel Name Anzahl
BSN20, SOT-23-Package Q6, 11 2
Widerstand SMD, 1206-Package, 4,7kΩ R67, 68, 70 3
Widerstand SMD, 1206-Package, 2,2kΩ R71 1
Widerstand SMD, 1206-Package, 10kΩ R69 1
Widerstand SMD, 1206-Package, 470Ω 36 1
Kondensator SMD, 1206-Package, 100nF C13, 14 2
Kondensator SMD, 1206-Package, 470pF C12 1
3,3V-Regler MIC5219-3.3BM5 , SOT23-5-Package IC2 1
2x1-Jumper, RM2,54 J_INT_ON, J3_I5, J3_SDA, J3_I3, J_3VON 5

Beschreibung

Die Widerstände und Feldeffekttransistoren dienen als Pegelwandler für die Leitungen des I2C (SDA und SCL) und der Interruptleitung (Int1). Die Kondensatoren dienen der Abschirmung. Es muss darauf geachtet werden, dass der 3,3V-Regler MIC5219-3.3BM5 verwendet wird (oder ein identischer).

Der Jumper J_3VON schaltet den 3,3V-Regler an.

Der Jumper J_INT_ON verbindet die Interrupt-Leitungen im 3,3V-Pegel mit der Int1-Leitung des XBUS.

Der Jumper J3_I5 schaltet einen Pullup-Widerstand (R71) zur Interrupt-Leitung auf der 5V-Seite zu.

Der Jumper J3_I3 schaltet einen Pullup-Widerstand (R67) zur Interrupt-Leitung auf der 3,3V-Seite zu.

Der Jumper J3_SDA schaltet einen Pullup-Widerstand für die SDA-Leitung zu.

Nähere Erläuterungen finden sich im Netz, siehe Weblinks.

Temperatursensor

Benötigte Teile

Artikel Name Anzahl
TCN75-Temperatursensor, MSOP8-Package U26 1
Kondensator SMD, 1206-Package, 100nF C39 1
2x3-Jumper, RM2,54 J_TCN_ADR 1
2x1-Jumper, RM2,54 J_TCN 1

Beschreibung

Der Temperatursensor TCN75 kommt auch bei der RP6-CCPRO-M128 zum Einsatz. Er sendet seine Daten via I2C. Die Adressleitungen A0 und A2 können am Jumper J_TCN_ADR eingestellt werden. Das Adressbit A1 ist 0. Der Jumper J_TCN schaltet VCC an/aus.

16-facher PWM-Modulator

Benötigte Teile

Artikel Name Anzahl
PCA9685, TSSOP28-Package U7 1
Kondensator SMD, 0805-Package, 10uF C10 1
Widerstand SMD, 0805-Package, 220Ω R48-R55 8
LED low current, 3mm SL1-4 4
Widerstand SMD, 1206-Package, 820Ω R5-R8 4
1x3-Jumper, RM2,54 J_S1 bis J_S8 8
1x8-Jumper, RM2,54 P_PWM 1
2x3-Jumper, RM2,54 JP_PWM_ADR 1

Beschreibung

Der PCA9685 ist ein 16-facher PWM-Modulator via I2C. Seine Adressbits A0 und A1 sind am Jumper JP_PWM_ADR einstellbar, alle anderen Adressbits sind 0.

Acht Pins (PWM0 bis 7) sind für Servos reserviert. PWM8 schaltet die Servospannung an/aus. PWM12 bis PWM15 sind für die Status-LEDs SL1 bis SL4 reserviert. PWM9 bis PWM11 sind frei.

Servos der M32

Benötigte Teile

Artikel Name Anzahl
10-polige Wannenbuchse SV_SERVOSM32 1
1x1-Jumper, RM2,54 P_S_M32_5 1
3x8-Jumper, RM2,54 P_S_M32_1-4 1

Beschreibung

Es ist möglich, mit Hilfe der Servolib (siehe Weblinks unten) acht Servos durch die RP6-Control-M32 anzusteuern. Hierfür den 10-poligen Wannenstecker der M32 in SV_SERVOSM32 einstecken.

Spannungsversorgung für Servomotoren

Benötigte Teile

Artikel Name Anzahl
BUZ11 Transistor, TO220-Package Q4 1
Widerstand SMD, 1206-Package, 100kΩ R11 1
Widerstand SMD, 1206-Package, 10kΩ R17 1
Widerstand SMD, 1206-Package, 240Ω R25 1
LED SMD, 1206, grün LED10 1
Kondensator, E3,5-8-Package, 470uF C11 1
1x2-Jumper, RM2,54 J_SERVOS_GND 1
Kondensator SMD, EIA3528- od. 1206-Package, 10uF C50 1
Kühlrippen für ICs - 2
Verwendung eines LT1084CP-5 oder eines LT1084CT-5 als 5V-Regler
Artikel Name Anzahl
LT1084CP-5 im TO247-3-Package oder LT1084CT-5 im TO220-Package IC1 1
Kondensator SMD, EIA3528- od. 1206-Package, 10uF C49 1
Kondensator SMD, EIA3528- od. 1206-Package, 470uF C51 1
Potentiometer, PT-10-Package, 500Ω, liegend oder stehend R26 1
Verwendung eines 78x5 als 5V-Regler
Artikel Name Anzahl
78x5, TO220-Package IC6 1
Kondensator SMD, 1206-Package, 100nF C49, 51 2

Beschreibung

Die Servospannung ist über den BUZ11 (Q4) schaltbar. Wird ein LT1084CP-5 oder ein LT1084CT-5 als 5V-Regler verwendet, müssen größere Kondensatoren eingebaut werden. Zusätzlich wird ein 500Ω-Potentiometer benötigt, über welche die Spannung im Bereich von etwa 5V bis 7,5V eingestellt werden kann.

Bei Verwendung eines einfachen 78x5 Reglers werden weniger Teile benötigt. Die Kondensatoren C49 und C51 können nur 100nF betragen. Außerdem sind Regler der 78x5-Reihe bedeutend billiger.

Nachteile der 78x5er-Reihe sind die bedeutend geringere Leistungsumsetzung und die Servospannung kann hier nicht justiert werden.

Strom-Spannungs-Temperatur-Sensor

Benötigte Teile

Artikel Name Anzahl
LTC2990, MSOP10-Package U10 1
Widerstand SMD, 1206-Package, 10kΩ R2, 3, 9, 12, 14, 22 6
Widerstand SMD, 1206-Package, 15kΩ R32 1
Widerstand SMD, 1206-Package, 22kΩ R13 1
Kondensator SMD, 1206-Package, 100nF C41 1
Shuntwiderstand, 0,05Ω, 5Watt R10 1
2x3-Jumper, RM2,54 J_CURRENT_ADR 1

Beschreibung

Der Sensor U10 überwacht durch den Shunt-Widerstand (R10) den gesamten, von der Platine benötigten Strom, die Batteriespannung und die Versorgungsspannung der Servos. Darüber hinaus misst er seine eigene Temperatur.

Über den Jumper J_CURRENT_ADR sind die Adressbits A0 und A1 einstellbar.

Echtzeit-Uhr

Benötigte Teile

Artikel Name Anzahl
DS1307, SOIC8-Package IC3 1
Kondensator SMD, 1206-Package, 100nF C38 1
Quarz, 32.768 kHz, TC26H-Package Q3 1
Knopfzellenhalter, SN2032 BAT1 1
1x2-Jumper, RM2,54 JP_RTC 1

Beschreibung

Diese Uhr (Real-Time-Clock, RTC) kann durch Jumper JP_RTC von VCC getrennt werden. Dann übernimmt die 3V-Knopfzelle für den Stand-By-Betrieb. Sie kann via I2C ausgelesen und gestellt werden.

Berührungssensor

Benötigte Teile

Artikel Name Anzahl
NE555, SO8-Package IC14 1
Widerstand SMD, 1206-Package, 1MΩ R58, 59 2
BC847, SOT23-Package Q13, 14 2
Kondensator SMD, 1206-Package, 10uF C31 1
1x1-Jumper, RM2,54 J_NE 1

Beschreibung

Bei Berührung einer Antenne schaltet der Timerbaustein (IC14) den Output auf etwa 3V. Dies kann an einem ADC gemessen werden. Der Berührungssensor kann entweder auf PF3 des ADC_M256-Wannensteckers oder auf ADC1 (Pin 1) des ADC_Mxxx-Wannensteckers gemessen werden.

Buzzer

Benötigte Teile

Artikel Name Anzahl
Buzzer BMT1205XH7.5 SG2 1

Beschreibung

Der Buzzer ist derselbe wie bei den Modulen RP6-Control-M32 und RP6-CCPRO-M128. Er wird durch Pin 5 des IO_Mxxx-Wannensteckers gesteuert.

Spannungsteiler

Benötigte Teile

Beschreibung

An den Pins P_LDR können analoge Sensoren angeschlossen werden, welche einen Spannungsteiler benötigen. Dies könnten z.B. zwei lichtsensitive Widerstände (LDRs) sein. Dafür müssen für R41 und R42 sie nötigen Widerstände eingelötet werden. Diese liegen bei vielen LDRs z.B. bei 68kΩ. Die Sensoren können nur in Verbindung mit dem M256-Modul verwendet werden, da sie an PF0 und PF1 des ADC_M256-Wannensteckers angeschlossen sind.

EEPROM

Benötigte Teile

Artikel Name Anzahl
I2C-EEPROM, DIL8-Package IC5 1
IC-Sockel, DIL8-Package IC5 1
Kondensator SMD, 1206-Package, 100nF C43 1
1x3-Jumper, RM2,54 J_EEP_A0-2 3

Weitere Infos zu EEPROMS siehe RP6v2_I2C-Portexpander.

Beschreibung

In den IC-Sockel (IC5) können diverse I2C-EEPROMs gesteckt werden. Am Jumper J_EEP_A0-2 können die Adressbits A0, A1 und A2 gewählt werden.

Anschluß der anderen Boards

Taster-Board

Das Taster-Board kann an die linke Vorderseite des Multi-IO-Moduls aufgesteckt oder angelötet werden. Statt dieses Boards können auch andere Tastaturen mit ADC an die dreipolige Stiftleiste P_TAST-EXT angesteckt werden.

Bumper-Board

Das Bumper-Board kann an der 7-poligen Stiftleiste P_BUMP angesteckt werden. Die Bumper-Ausgänge gehen dabei auf Pin 4 (L) und Pin 8 (R) des IO_Mxxx-Wannensteckers. Dafür müssen noch die Jumper bei diesen Pins gesetzt werden.

Die analogen (Sharp-Sensoren) oder digitalen (I2C der SRF02) Sensorleitungen sind dieselben. Um das zu realisieren, müssen zwei Jumper gesetzt werden. Dies geschieht über JP2 und JP1. Hier kann man (siehe Platinenaufdruck) die Leitungen des Bumper-Boards wahlweise auf den I2C legen, oder auf PF3 und PF4 des ADC_M256-Wannensteckers.

SDA des I2C liegt dabei auf einer Leitung mit dem Signal des linken Sharp-Sensors, SCL auf dem des rechten.

Liniensucher-Board

Das Liniensucher-Board kann mit einem 8-poligen Flachbandkabel an das Multi-IO-Modul gesteckt werden. Jedoch ist die Pinreihe am Liniensucher-Board einreihig (1x8), auf dem Multi-IO-Modul zweireihig (2x4). Dabei bitte die Pinbelegung beachten!

Radio-Board

Das Radio-Board hat keinen speziellen Anschluss. Da das Board aber auf 3,3V läuft und via I2C gesteuert werden kann, kann es mit der Pinreihe P_RADIO an den 3,3V-I2C-Bus auf dem Multi-IO-Modul angesteckt werden.

Anschlussmöglichkeiten weiterer Sensoren

DCF77-Funkuhr

Diese kann an die Pinreihe P_DCF angesteckt werden. Zur Sicherheit wird ein Kondensator (100nF, SMD, 1206-Package, C35) empfohlen. Das Signal des DCF77 wird über Pin 1 des IO_Mxxx-Wannensteckers ausgelesen, wenn der Jumper bei Pin 1 geschlossen ist.

GPS-Modul

Artikel Name Anzahl
Kondensator SMD, 1206-Package, 100nF C22 1
Widerstand SMD, 1206-Package, 4,7kΩ R39 1
Widerstand SMD, 1206-Package, 10kΩ R40 1
1x5-Jumper, RM2,54 P_GPS 1
1x2-Jumper, RM2,54 J_GPS_5V 1
1x3-Jumper, RM2,54 P_GPS1, J_GPS_TX 2

Das GPS-Modul Navilock NL-552ETTL kann an P_GPS angeschlossen werden und wird via UART ausgelesen. Dafür müssen die Pegel für Rx des GPS-Moduls jedoch angepasst werden, da das GPS auf 3,3V-Pegel liegt. Ein 5V-Pegel könnte das GPS-Modul beschädigen. Die ausgehenden Daten (Tx) des GPS-Moduls müssen dagegen nicht unbedingt angepasst werden, da UART auch 3,3V-Pegel akzeptiert.

Der Jumper J_GPS_5V schaltet das GPS an.

Der Jumper J_GPS_TX wählt den Tx-Pin des Master-Moduls (RP6(v2) BASE, RP6-Control-M32, RP6-CCPRO-M128, M256-WiFi-Platine) aus: bei manchen ist dies der Pin 6 (Jumper muss links stecken), bei manchen der Pin 8 (Jumper muss rechts stecken).

An P_GPS1 kann ein weiterer Mikrocontroller über UART direkt an Rx (mit Pegelwandler) und Tx des GPS-Moduls angeschlossen werden.

2D-Kompass

Dieses Modul kommuniziert über I2C und kann daher auf allen 5V-, GND- und I2C-Pins des Multi-IO-Modul angesteckt werden.

9D-Kompass

Für den 9D-Kompass ist am unteren rechten Rand eine Pinreihe P_KOMPASS angebracht, an welcher das Kompassmodul direkt auf- oder angesteckt werden kann. Es wird ein Kondensator (SMD, 1206-Package, 100nF, C33) empfohlen.

Luftfeuchtigkeits-Temperatur-Sensor

Dieser Sensor misst die Luftfeuchtigkeit und die Temperatur. Er kann über I2C ausgelesen werden und an der Pinreihe P_FEUCHTE an- oder aufgesteckt werden.

Es wird ein Kondensator (SMD, 1206-Package, 100nF, C21) empfohlen.

Luftdrucksensor

Dieser Sensor kann an der Pinreihe P_LUFTDRUCK an- oder aufgesteckt werden. Da er 3,3V Versorgungsspannung und 3,3V-I2C benötigt, liegen diese hier an.

Es wird ein Kondensator (SMD, 1206-Package, 100nF, C34) empfohlen.

SRF02-Abstandssensoren

Bis zu vier SRF02 können an die Pinreihen P_SRF1 und P_SRF2 angeschlossen werden. Pinbelegung siehe Platinenaufdruck.

Es wird ein Kondensator (SMD, 1206-Package, 100nF, C5) empfohlen.

Snake-Vision-Modul

Artikel Name Anzahl
2x3-Jumper, RM2,54 P_SNAKE 1

Das Snake-Vision-Modul kann an die Pinreihe P_SNAKE angeschlossen werden (auf Pinbelegung achten). Die Sensoren (rechts, links) sowie Taster und GND sind einfach an P_SNAKE anzuschließen.

Für die Versorgungsspannung gibt es drei Möglichkeiten:

Überbrückung des Spannungsreglers und der Dioden des Snake-Vision-Moduls und Anschluss von VCC des Snake-Vision-Moduls an VCC des Multi-IO-Moduls. Der Umbau wird im RP6-Forum beschrieben, siehe Weblinks unten.

Die zweite Möglichkeit entspricht der Ersten, mit der Ausnahme, dass VCC des Snake-Vision-Moduls an IO des Multi-IO-Moduls angeschlossen wird. Dadurch kann das Snake-Vision-Modul über einen High-Side-Switch (Q2 und R16) an Pin 4 des IO_Mxxx-Wannensteckers an- und abgeschaltet werden.

Die dafür benötigten Teile sind:

Artikel Name Anzahl
Evtl. Transistor SMD, 1206-Package, BC807 Q2 1
Evtl. Widerstand SMD, 1206-Package, 1kΩ R16 1


Die letzte Möglichkeit benötigt keinen Umbau des Snake-Vision-Moduls, da an seinen Eingang OC2 eine Ladungspumpe angeschlossen wird. Schließe dafür VCC des Snake-Vision-Moduls an VCC des Multi-IO-Moduls und OC2 an IO. Des Weiteren wird ein Jumper J_OC2 benötigt, welcher den nur hier notwendigen Widerstand R33 als Pulldown hinzuschaltet. Der Jumper J_OC2 sollte also geschlossen sein.

Artikel Name Anzahl
Evtl. Widerstand SMD, 1206-Package, 2,2..4,7kΩ R33 1
Evtl. 1x2-Jumper, RM2,54 J_OC2 1

Weitere Pinreihen

  • Am vorderen linken Rand kann man bis zu 10 Pins anbringen. Belegung siehe Abb.

BILD!!!!!!!!!!!!!!!!!!!!

  • Hinter dem 78x5-5V-Regler (U1) kann man auf 3x6 Pins VCC (die linken sechs Pins), GND (die mittleren sechs Pins) und die Batteriespannung (die rechten sechs Pins) abgreifen.
  • Am Jumper P_5V-I2C kann man 5V, GND, Int1 (5V-Pegel) und die I2C-Leitungen (5V-Pegel) abgreifen.
  • Am Jumper P_3V3-I2C kann man 3,3V, GND, Int1 (3,3V-Pegel) und die I2C-Leitungen (3,3V-Pegel) abgreifen.
  • Vor dem 10-poligen Wannenstecker SV_IO_MXXX befindet sich eine zweireihige Stiftleiste JP_IO1,2. An JP_IO 1 liegen alle auf der Platine verwendeten Signale für den Wannenstecker SV_IO_MXXX an. An JP_IO2 sind die Pins des Wannensteckers SV_IO_MXXX direkt herausgeführt. Dadurch können diese Pins auch auf andere Weise verwendet werden.

Wünscht man eine Verwendung, wie in dieser Anleitung empfohlen, müssen nur alle 9 Jumper gesetzt werden. Da Pin 2 jedoch nur von der M32 angesprochen werden kann (auf anderen Modulen ist dieser Pin auf GND) und Pin 9 nur von M32 oder der M128, liegt an beiden der Transistor zum Schalten des Liniensucher-Boards. Damit kann dieses Board sowohl von der M32 (Pin 2 oder Pin 9) als auch von der M256 (Pin 9) aus geschaltet werden. Lediglich die M128 kann diesen Transistor nicht schalten.

Anmerkung: Natürlich steht es jedem frei, andere Pins des Wannensteckers mit der IO-Leitung des Liniensucher-Boards zu verschalten.

  • Ähnlich wie im gerade genannten Fall ist es auch beim 10-poligen Wannenstecker SV_ADC_MXXX. Jedoch sind hier manche Pins (1, 3, 5 und 6) direkt auf einen Wähl-Jumper JP1,2,4 gelegt, wo sie mit Jumpern weiter auf Signale gelegt werden können. Nur Pin 6 ist nicht weitergeführt und steht zur eigenen Verfügung, ist jedoch nur bei dem M128-Modul als ADC verwendbar, auf allen anderen Modulen liegt hier GND an.
  • Vor dem 14-poligen Wannenstecker SV_ADC_M256 liegt eine weitere solche doppreihige Stiftleiste: JP_ADIO. Dieser verbindet wieder durch setzen der Jumper die Signale der Platine mit den Pins des Wannensteckers.
  • Der Jumper J_WAHL, eine 2x6-Stiftleiste, kann dazu verwendet werden, einige Signale auf verschiedene Arten weiterzuleiten:
Eigehendes Signal 1. Möglichkeit 2. Möglichkeit
Sharp links bzw. I2C der SRF02 PF4 des ADC_M256 (für Sharp-Verwendung) SCL des I2C (für SRF02-Verwendung)
Sharp rechts bzw. I2C der SRF02 PF3 des ADC_M256 (für Sharp-Verwendung) SDA des I2C (für SRF02-Verwendung)
Messung der 3,3V-Spannung PF4 des ADC_M256 Pin 3 des ADC_Mxxx
NE555-Berührungssensor PF3 des ADC_M256 Pin 1 des ADC_Mxxx
CNY70-L (linker der drei Sensoren) Pin 1 des ADC_Mxxx -
CNY70-M (mittlerer der drei Sensoren) Pin 3 des ADC_Mxxx -

Teileliste

Nicht alle der in diesen Listen aufgeführten Teile werden für den Bau benötigt. Bitte dafür die Anleitung genau lesen. Man muss nicht die gesamte Platine aufbauen, man kann auch nur einen Teil der Schaltung realisieren. Für das Löten lese bitte eine Lötanleitung und übe das Löten vorher. Ansonsten können Teile durch den zu langen Kontakt mit dem Lötkolben überhitzen oder es kann zu Kurzschlüssen auf der Platine kommen. Die angegebenen Bestellnummern sind nur ein Vorschlag, wo die Teile gekauft werden.

Die Teileliste samt Bestellnummern der Shops und Preisen wird als MS Excel-Sheet veröffentlicht, Lieferanten findet man unter Bezugsquellen

Kondensatoren

Spulen

Widerstände

ICs

LEDs

Dioden

Pins, Jumper, Stiftleisten

Sonstiges

Siehe auch


Weblinks

Alle wichtigen Daten (Lötanleitung, Anleitung in .pdf-Form, Schaltpläne) findet ihr HIER

Servo-Lib für M32 von Dirk

Orientierungs-Mitmach-Projekt von Dirk

Mitmachprojekt Orientierung

Umbau des Snake Vision für RP6

EEPROM

Autoren

--fabqu 21:30, 17. Feb 2013 (CET)

--Dirk 08:48, 19. Feb 2013 (CET)


LiFePO4 Speicher Test