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

RP6 ArduIO V1.0

RP6 ArduIO Erweiterungsmodul

Die RP6-ArduIO Erweiterungsplatine (siehe auch das Vorgängerprojekt,die RP6-MultiIO-Erweiterungsplatine) im üblichen RP6-Layout ist als reine I2C-Erweiterung sowohl für den RP6, als auch für Arduino-Boards und –Shields gedacht. Entwickelt wurde sie zusammen mit einigen Mitgliedern des Roboternetzes von fabqu (Hardwarearbeiten) und Dirk (Softwarearbeiten).

Eine Kurzbeschreibung der RP6-ArduIO Erweiterungsplatine findet ihr HIER.

Umfangreiche Dokumentation, sämtliche Beispielprogramme und Bibliotheken, Daten, Teilelisten und eine Lötanleitung finden sich unten in den Weblinks.


Hardware

Der Hardware-Artikel befindet sich HIER.


Software

Hier geht es um die Software für das von fabqu designte ArduIO Board. Für dieses Board soll es eine gemeinsame Library für die drei wesentlichen Plattformen des RP6-Systems und eine Library für den Arduino UNO geben. Ob auch eine Library für die RP6 CCPRO M128 veröffentlicht wird, ist noch offen.

RP6 M256 WIFI, CONTROL M32, BASE

Für die RP6 M256 WiFi, RP6 CONTROL M32 und RP6(v2) Base gibt es hier eine gemeinsame ArduIO Library. Die nachfolgenden Demos zu den einzelnen RP6-Mikrocontroller-Systemen nutzen diese Library.

ArduIO Library

Hier findet ihr die neue AVR-GCC Library für das ArduIO Board. Sie ist ausgelegt für die RP6 M256 WiFi, die RP6 CONTROL M32 und die RP6(v2) Base. Für die RP6 CCPRO M128 wird es vielleicht eine eigene Library geben.

Die Library für das Ardu IO Projekt Board (= "ArduIO") geht von folgenden Voraussetzungen aus:

  • Der RP6(v2) Roboter (= "BASE"), die RP6 CONTROL M32 (= "M32") oder RP6v2 M256 WiFi Platine (= "M256") wird für die Ansteuerung der ArduIO benutzt.
  • Die BASE, M32 oder M256 ist der I2C-Bus Master.
  • Die I2C-Bus Geschwindigkeit beträgt 100 kHz.
  • Alle Hardware-Komponenten der ArduIO sind aufgebaut (1).
  • Alle Jumper auf der ArduIO sind in ihrer Standardstellung (2).
  • Die ArduIO ist mit dem XBUS der BASE, M32 oder M256 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 folgende Abbildung!

Standard-Jumperstellung

ArduIO Jumper Standardstellung Hinweis: Die Jumper sind orange eingezeichnet!

Die Jumper der Stromversorgung (S1, JP_5V, JP_UB, JP_LOAD) wurden nicht berücksichtigt!


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

  • Dem Configuration Header -> Hier stehen alle Definitionen und Festlegungen, die der grundlegenden Konfiguration der ArduIO dienen. Diese Datei kann auf die eigenen Hardware-Voraussetzungen angepaßt werden, ohne dass die eigentliche Library (Header und Source) verändert werden muss.
  • Dem Library Header -> Hier gibt es Definitionen, Variablen- und Funktionsdeklarationen für die Library.
  • Der Library Source -> Das ist die eigentliche Library.
Configuration Header

Diese Datei ist der "Configuration Header" der neuen ArduIO Library. Sie gehört in den Ordner /.../RP6Lib/RP6common/.

Datei RP6_ArduIO.h:

/* ****************************************************************************
 *                           _______________________
 *                           \| RP6  ROBOT SYSTEM |/
 *                            \_-_-_-_-_-_-_-_-_-_/                  >>> COMMON
 * ----------------------------------------------------------------------------
 * ----------------------------- [c]2014 - Dirk -------------------------------
 * ****************************************************************************
 * File: RP6_ArduIO.h
 * Version: 1.1
 * Target: RP6 Base & Processor Expansion - ATMEGA32 @8.00 or 16.00MHz
 *         & RP6 M256 WiFi                - ATMEGA2560 @16.00MHz
 * Author(s): Dirk
 * ****************************************************************************
 * Description:
 * Configuration header file for new ArduIO Board library.
 *
 * ****************************************************************************
 * THE CHANGELOG CAN BE FOUND AT THE END OF THIS FILE!
 * ****************************************************************************
 */

#ifndef RP6_ARDUIO_H
#define RP6_ARDUIO_H


/*****************************************************************************/
// ArduIO hardwired components:
// - I2C PWM Controller (IC3: PCA9685)
// - I2C I/O Expander 1 5V (IC8: PCA9535)
// - I2C I/O Expander 2 5V (IC13: PCA9535)
// - I2C I/O Expander 3 3V3 (IC12: PCA9535)
// - I2C A/D and D/A Converter 1 (IC11: PCF8591)
// - I2C A/D and D/A Converter 2 (IC10: PCF8591)
// - I2C A/D and D/A Converter 3 (IC9: PCF8591)
// - UB Voltage Sensor
// - LEDs
// - PWM Ports
// - Power PWM Ports & H-Bridges

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

#include "RP6_ArduIOConfig.h"		// Configure the target system

/*****************************************************************************/
// I2C PWM Controller (PCA9685):
// (A5, A4, A3 always 0, A1 always 1!)
#define I2C_ARDUIO_PWM_ADR				0x84	// A2/0 = 0/0
//#define I2C_ARDUIO_PWM_ADR			0x86	// A2/0 = 0/1
//#define I2C_ARDUIO_PWM_ADR			0x8c	// A2/0 = 1/0
//#define I2C_ARDUIO_PWM_ADR			0x8e	// A2/0 = 1/1
//#define I2C_ARDUIO_PWM_ADR			0xe0	// ALLCALLADR

// ---------------------------------------------------------------
#define PWM_FREQUENCY					1000	// 1kHz (default)
// ---------------------------------------------------------------

#define CHALL_LED						0		// All LEDs (channels)

/*****************************************************************************/
// I2C I/O Expander (PCA9535):
// (A1 always 1!)
#define I2C_ARDUIO_IO_1_ADR				0x44	// A2/0 = 0/0
//#define I2C_ARDUIO_IO_1_ADR			0x46	// A2/0 = 0/1
//#define I2C_ARDUIO_IO_1_ADR			0x4c	// A2/0 = 1/0
//#define I2C_ARDUIO_IO_1_ADR			0x4e	// A2/0 = 1/1

//#define I2C_ARDUIO_IO_2_ADR			0x44	// A2/0 = 0/0
#define I2C_ARDUIO_IO_2_ADR				0x46	// A2/0 = 0/1
//#define I2C_ARDUIO_IO_2_ADR			0x4c	// A2/0 = 1/0
//#define I2C_ARDUIO_IO_2_ADR			0x4e	// A2/0 = 1/1

//#define I2C_ARDUIO_IO_3_ADR			0x44	// A2/0 = 0/0
//#define I2C_ARDUIO_IO_3_ADR			0x46	// A2/0 = 0/1
#define I2C_ARDUIO_IO_3_ADR				0x4c	// A2/0 = 1/0
//#define I2C_ARDUIO_IO_3_ADR			0x4e	// A2/0 = 1/1

/*****************************************************************************/
// I2C A/D and D/A Converter (PCF8591):
// (A1 always 1!)
#define I2C_ARDUIO_AD_1_ADR				0x94	// A2/0 = 0/0
//#define I2C_ARDUIO_AD_1_ADR			0x96	// A2/0 = 0/1
//#define I2C_ARDUIO_AD_1_ADR			0x9c	// A2/0 = 1/0
//#define I2C_ARDUIO_AD_1_ADR			0x9e	// A2/0 = 1/1

//#define I2C_ARDUIO_AD_2_ADR			0x94	// A2/0 = 0/0
#define I2C_ARDUIO_AD_2_ADR				0x96	// A2/0 = 0/1
//#define I2C_ARDUIO_AD_2_ADR			0x9c	// A2/0 = 1/0
//#define I2C_ARDUIO_AD_2_ADR			0x9e	// A2/0 = 1/1

//#define I2C_ARDUIO_AD_3_ADR			0x94	// A2/0 = 0/0
//#define I2C_ARDUIO_AD_3_ADR			0x96	// A2/0 = 0/1
#define I2C_ARDUIO_AD_3_ADR				0x9c	// A2/0 = 1/0
//#define I2C_ARDUIO_AD_3_ADR			0x9e	// A2/0 = 1/1

/*****************************************************************************/
// UB Voltage Sensor:
// (Connected to A/D and D/A Converter 1 (ADDA_1: IC11), AIN3 (AD13),
//  if jumper JP_AD-UB on the ArduIO Board is CLOSED!)
#define ADCVAL_UB_LOW					175		// UB 6.9V

/*****************************************************************************/
// LEDs:
// (Status LED1..LED4 are connected to LED11..LED8 of the PCA9685!)
#define ARD_CHLED1						12
#define ARD_CHLED2						11
#define ARD_CHLED3						10
#define ARD_CHLED4						9

/*****************************************************************************/
// PWM Ports:
// (Ports PWM1..PWM4 are connected to LED15..LED12 of the PCA9685!)
#define CHPWM1							16
#define CHPWM2							15
#define CHPWM3							14
#define CHPWM4							13

/*****************************************************************************/
// Power PWM Ports & H-Bridges:
// (H-Bridges HB1/HB2 are connected to LED0..LED3/LED4..LED7 of the PCA9685!)
// Power PWM Ports:
#define CHPOWERPWM1_P					1
#define CHPOWERPWM2_N					2
#define CHPOWERPWM3_P					3
#define CHPOWERPWM4_N					4
#define CHPOWERPWM5_P					5
#define CHPOWERPWM6_N					6
#define CHPOWERPWM7_P					7
#define CHPOWERPWM8_N					8

// H-Bridges:
#define CHHB1_P1						1
#define CHHB1_N1						2
#define CHHB1_P2						3
#define CHHB1_N2						4
#define CHHB2_P1						5
#define CHHB2_N1						6
#define CHHB2_P2						7
#define CHHB2_N2						8

/*****************************************************************************/
// Interrupt portpin definitions:
// Select INTx portpin definitions depending on RP6_ArduIOConfig.h:
#ifdef ARDUIO_RP6BASE
// Interrupt I/O portpin definitions (RP6Base):
#define IO_ARDUIO_INT1_IN				E_INT1	// ADC4 PA4  XBUS Pin 8
#define IO_ARDUIO_INT1_DDR				DDRA
#define IO_ARDUIO_INT1_PIN				PINA
#define IO_ARDUIO_INT1_PORT				PORTA
#else
#ifdef ARDUIO_RP6CONTROL
// Interrupt I/O portpin definitions (RP6Control M32):
#define IO_ARDUIO_INT1_IN				EINT1	// INT0 PD2  XBUS Pin 8
#define IO_ARDUIO_INT1_DDR				DDRD
#define IO_ARDUIO_INT1_PIN				PIND
#define IO_ARDUIO_INT1_PORT				PORTD
#define IO_ARDUIO_INT2_IN				EINT2	// INT1 PD3  XBUS Pin 11
#define IO_ARDUIO_INT2_DDR				DDRD
#define IO_ARDUIO_INT2_PIN				PIND
#define IO_ARDUIO_INT2_PORT				PORTD
#define IO_ARDUIO_INT3_IN				EINT3	// AIN0/INT2 PB2  XBUS Pin 9
#define IO_ARDUIO_INT3_DDR				DDRB
#define IO_ARDUIO_INT3_PIN				PINB
#define IO_ARDUIO_INT3_PORT				PORTB
#else
#ifdef ARDUIO_RP6M256WIFI
// Interrupt I/O portpin definitions (RP6M256 WiFi):
#define IO_ARDUIO_INT1_IN				INT1_PI12 // PCINT12 PJ3  XBUS Pin 8
#define IO_ARDUIO_INT1_DDR				DDRJ
#define IO_ARDUIO_INT1_PIN				PINJ
#define IO_ARDUIO_INT1_PORT				PORTJ
#define IO_ARDUIO_INT2_IN				INT2_PI15 // PCINT15 PJ6  XBUS Pin 11
#define IO_ARDUIO_INT2_DDR				DDRJ
#define IO_ARDUIO_INT2_PIN				PINJ
#define IO_ARDUIO_INT2_PORT				PORTJ
#define IO_ARDUIO_INT3_IN				INT3_PI14 // PCINT14 PJ5  XBUS Pin 9
#define IO_ARDUIO_INT3_DDR				DDRJ
#define IO_ARDUIO_INT3_PIN				PINJ
#define IO_ARDUIO_INT3_PORT				PORTJ
#define IO_ARDUIO_INTU_IN				INTU_PI13 // PCINT13 PJ4  XBUS Pin 7
#define IO_ARDUIO_INTU_DDR				DDRJ
#define IO_ARDUIO_INTU_PIN				PINJ
#define IO_ARDUIO_INTU_PORT				PORTJ
#else
	#error DEFINE "ARDUIO_RP6BASE", "ARDUIO_RP6CONTROL" OR "ARDUIO_RP6M256WIFI"
	#error AS TARGET IN RP6_ArduIOConfig.h
#endif
#endif
#endif

/*****************************************************************************/
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*                     Arduino Uno Expander definitions                      */
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// ATTENTION: Using this library you MAY NOT connect an Arduino Uno Board to
//            the RP6 ArduIO Board using the Arduino Uno Expander pin headers
//            on the ArduIO Board, if the Arduino Uno Board is the I2C bus
//            master!!!!!!
//            BE VERY CAREFUL:
//            You may damage the Arduino Uno AND your RP6 ArduIO Board!
//
//            Of course you may connect Arduino ADDON boards (shields) to the
//            Arduino Uno Expander pin headers on the ArduIO Board.
//            BE VERY CAREFUL:
//            Not all Arduino shields will work on the RP6 ArduIO Board!  
//            You may damage the Arduino shield AND your RP6 ArduIO Board!
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Arduino Uno Expander <-> RP6_ArduIO Mapping Table:
//   Arduino Uno:  ATmega328:              RP6_ArduIO:
//   Pin Function  Pin  Functions          Pin   Name  IO ADDA
//  -----------------------------------------------------------
//    0  D0  RX    PD0  RXD_PCINT16        P00   GP200  2
//    1  D1  TX    PD1  TXD_PCINT17        P01   GP201  2
//    2  D2        PD2  INT0_PCINT18       P02   GP202  2
//    3  D3  PWM   PD3  INT1_OC2B_PCINT19  P03   GP203  2
//    4  D4        PD4  T0_XCK_PCINT20     P04   GP204  2
//    5  D5  PWM   PD5  T1_OC0B_PCINT21    P05   GP205  2
//    6  D6  PWM   PD6  AIN0_OC0A_PCINT22  P06   GP206  2
//    7  D7        PD7  AIN1_PCINT23       P07   GP207  2
//    8  D8        PB0  ICP1_CLKO_PCINT0   P15   GP215  2
//    9  D9  PWM   PB1  OC1A_PCINT1        P14   GP214  2
//   10  D10 PWM   PB2  SS_OC1B_PCINT2     P13   GP213  2
//   11  D11 PWM   PB3  MOSI_OC2A_PCINT13  P12   GP212  2
//   12  D12       PB4  MISO_PCINT4        P11   GP211  2
//   13  D13       PB5  SCK_PCINT5         P10   GP210  2
//
//    0  A0        PC0  ADC0_PCINT8        AIN0  AD30      3
//    1  A1        PC1  ADC1_PCINT9        AIN1  AD31      3
//    2  A2        PC2  ADC2_PCINT10       AIN2  AD32      3
//    3  A3        PC3  ADC3_PCINT11       AIN3  AD33      3
//    4  A4  SDA   PC4  ADC4_SDA_PCINT12         SDA
//    5  A5  SCL   PC5  ADC5_SCL_PCINT13         SCL

//   Special "PWM portpin" connections:
//   Arduino Uno:  ATmega328:              RP6_ArduIO:
//   Pin Function  Pin  Functions          Name  JP_   Pins (*)
//  ------------------------------------------------------------
//    3  D3  PWM   PD3  INT1_OC2B_PCINT19  PWM3  PWM3  2-3
//    5  D5  PWM   PD5  T1_OC0B_PCINT21    PWM1  PWM1  1-2
//    6  D6  PWM   PD6  AIN0_OC0A_PCINT22  PWM1  PWM1  2-3
//    9  D9  PWM   PB1  OC1A_PCINT1        PWM2  PWM2  1-2
//   10  D10 PWM   PB2  SS_OC1B_PCINT2     PWM2  PWM2  2-3
//   11  D11 PWM   PB3  MOSI_OC2A_PCINT13  PWM3  PWM3  1-2
//  (At (*): Pins of JP_PWMx to be closed!)

// Arduino Uno Expander ATmega 328 portpin names:
#define IO_ARD_D0_RXD_PCINT16			0
#define IO_ARD_D1_TXD_PCINT17			1
#define IO_ARD_D2_INT0_PCINT18			2
#define IO_ARD_D3_INT1_OC2B_PCINT19		3
#define IO_ARD_D4_T0_XCK_PCINT20		4
#define IO_ARD_D5_T1_OC0B_PCINT21		5
#define IO_ARD_D6_AIN0_OC0A_PCINT22		6
#define IO_ARD_D7_AIN1_PCINT23			7
#define IO_ARD_D8_ICP1_CLKO_PCINT0		8
#define IO_ARD_D9_OC1A_PCINT1			9
#define IO_ARD_D10_SS_OC1B_PCINT2		10
#define IO_ARD_D11_MOSI_OC2A_PCINT13	11
#define IO_ARD_D12_MISO_PCINT4			12
#define IO_ARD_D13_SCK_PCINT5			13

#define AD_ARD_A0_ADC0_PCINT8			0
#define AD_ARD_A1_ADC1_PCINT9			1
#define AD_ARD_A2_ADC2_PCINT10			2
#define AD_ARD_A3_ADC3_PCINT11			3
#define AD_ARD_A4_ADC4_SDA_PCINT12		4
#define AD_ARD_A5_ADC5_SCL_PCINT13		5

// Arduino Uno Expander portpin short definitions:
#define IO_ARD_D0_RX					0
#define IO_ARD_D1_TX					1
#define IO_ARD_D2						2
#define IO_ARD_D3_PWM					3
#define IO_ARD_D4						4
#define IO_ARD_D5_PWM					5
#define IO_ARD_D6_PWM					6
#define IO_ARD_D7						7
#define IO_ARD_D8						8
#define IO_ARD_D9_PWM					9
#define IO_ARD_D10_PWM					10
#define IO_ARD_D11_PWM					11
#define IO_ARD_D12						12
#define IO_ARD_D13						13

#define AD_ARD_A0						0
#define AD_ARD_A1						1
#define AD_ARD_A2						2
#define AD_ARD_A3						3
#define AD_ARD_A4_SDA					4
#define AD_ARD_A5_SCL					5

// Arduino Uno Expander PWM portpin definitions:
// (Use only ONE of the IO_ARD_PWMx definitions! Never two or three!)
#define IO_ARD_PWM1						0				// JP_PWM1 open
//#define IO_ARD_PWM1						IO_ARD_D5_PWM	// JP_PWM1 1-2 closed
//#define IO_ARD_PWM1						IO_ARD_D6_PWM	// JP_PWM1 2-3 closed
// IMPORTANT: If JP_PWM1 is CLOSED on any pins, the JP_ARD2 jumper of that
//            Arduino Uno Expander PWM portpin (D5 or D6) MUST BE OPEN!!!
#define IO_ARD_PWM2						0				// JP_PWM2 open
//#define IO_ARD_PWM2						IO_ARD_D9_PWM	// JP_PWM2 1-2 closed
//#define IO_ARD_PWM2						IO_ARD_D10_PWM	// JP_PWM2 2-3 closed
// IMPORTANT: If JP_PWM2 is CLOSED on any pins, the JP_ARD2 jumper of that
//            Arduino Uno Expander PWM portpin (D9 or D10) MUST BE OPEN!!!
#define IO_ARD_PWM3						0				// JP_PWM3 open
//#define IO_ARD_PWM3						IO_ARD_D11_PWM	// JP_PWM3 1-2 closed
//#define IO_ARD_PWM3						IO_ARD_D3_PWM	// JP_PWM3 2-3 closed
// IMPORTANT: If JP_PWM3 is CLOSED on any pins, the JP_ARD2 jumper of that
//            Arduino Uno Expander PWM portpin (D11 or D3) MUST BE OPEN!!!

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Arduino Uno Expander read/write software examples:
// 1. Writing to the digital portpins (D0..D13):
//    io2outs.ARD_D10 = true;
//    updateArduino_Uno_Exp_IO();				// Set D10
//    ==> Hint: If D10 is connected to PWM2, then D10 will be set by this
//              PWM port instead of IO_2: P13!!!
//    io2outs.ARD_D8 = false;
//    updateArduino_Uno_Exp_IO();				// Clear D8
//    setArduino_Uno_Exp_IO(0b0001000000000000);// Set D9 & clear all others
//    ==> Bit positions in the io2ins and io2outs word:
//                          0b0000000000000000
//                            |||    ||      |
//                   Arduino: ||D8   |D7     D0
//                            n.c.   D13 
// 2. Controlling the digital "PWM portpins" (D3, 5, 6, 9, 10, 11):
//    ==> If one of these pins is disconnected from the IO_2 portpins and
//        instead is connected to a PWM port (PWM1, 2, 3), this "PWM portpin"
//        can be controlled by the PWM function:
//    dimArduino_Uno_Exp_PWM(1,duty);			// Set the D5 OR D6 duty cycle
//    dimArduino_Uno_Exp_PWM1(duty);			// The same!
//    ==> Hint: Depending on JP_PWM1 the PWM can be found at D5 OR D6!!!
// 3. Reading the digital portpins (D0..D13):
//    configArduIO_IO2(0b1111111111111111);		// All portpins are INPUTs
//    ==> This function must be called only ONCE!
//    task_readArduino_Uno_Exp_IO();			// Read D0..D13
//    io_D0 = io2ins.ARD_D0;					// This is D0
//    io_D11 = io2ins.ARD_D11;					// This is D11
//    all_ios = io2ins.word & 0x3fff;			// All portpins in 1 word
// 4. Reading the analog portpins (A0..A3):
//    task_readArduino_Uno_Exp_AD();			// Read A0..A3
//    adc_A0 = ad3ins.ARD_A0;					// This is A0
//    adc_A3 = ad3ins.ARD_A3;					// This is A3
// 5. Reading all portpins and the interrupt signal:
//    task_Arduino_Uno_Exp();					// Read D0..D13, A0..A3 and
//                                              // PCA9535 (2) INT
//    int = interrupt_RP6ArduIOstatus.ioexp_2	// This is PCA9535 (2) INT
//    ==> Hint 1: This XBUS INT1 indicates a level change on D0..D13!!!
//    ==> Hint 2: If the variable interrupt_rp6arduiostatus_changed becomes
//                TRUE after execution of this task, INT1 has changed!!!
//    ==> Hint 3: Pins 1-2 of jumper JP_INT3V3 must be CLOSED!!!

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*                   Arduino Uno Expander definitions end                    */
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*****************************************************************************/

#endif

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

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

Diese Datei ist der "Header" der neuen ArduIO Library. Sie gehört in den Ordner /.../RP6Lib/RP6common/.

Datei RP6_ArduIOLib.h:

/* ****************************************************************************
 *                           _______________________
 *                           \| RP6  ROBOT SYSTEM |/
 *                            \_-_-_-_-_-_-_-_-_-_/                  >>> COMMON
 * ----------------------------------------------------------------------------
 * ----------------------------- [c]2014 - Dirk -------------------------------
 * ****************************************************************************
 * File: RP6_ArduIOLib.h
 * Version: 1.1
 * Target: RP6 Base & Processor Expansion - ATMEGA32 @8.00 or 16.00MHz
 *         & RP6 M256 WiFi                - ATMEGA2560 @16.00MHz
 * Author(s): Dirk
 * ****************************************************************************
 * Description:
 * This is the RP6_ArduIOLib header file.
 * You have to include this file, if you want to use the library
 * RP6_ArduIOLib.c in your own projects.
 *
 * ****************************************************************************
 * THE CHANGELOG CAN BE FOUND AT THE END OF THIS FILE!
 * ****************************************************************************
 */

#ifndef RP6_ARDUIOLIB_H
#define RP6_ARDUIOLIB_H


/*****************************************************************************/
// ArduIO hardwired components:
// - I2C PWM Controller (IC3: PCA9685)
// - I2C I/O Expander 1 5V (IC8: PCA9535)
// - I2C I/O Expander 2 5V (IC13: PCA9535)
// - I2C I/O Expander 3 3V3 (IC12: PCA9535)
// - I2C A/D and D/A Converter 1 (IC11: PCF8591)
// - I2C A/D and D/A Converter 2 (IC10: PCF8591)
// - I2C A/D and D/A Converter 3 (IC9: PCF8591)
// - UB Voltage Sensor
// - LEDs
// - PWM Ports
// - Power PWM Ports & H-Bridges

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

#include "RP6_ArduIO.h"				// Config. header for ArduIO Library

// Select includes depending on RP6_ArduIOConfig.h:
#ifdef ARDUIO_RP6BASE
	#include "RP6RobotBaseLib.h"	// The RP6 Robot Base Library.
#else
#ifdef ARDUIO_RP6CONTROL
	#include "RP6ControlLib.h"		// The RP6 Control M32 Library.
#else
#ifdef ARDUIO_RP6M256WIFI
	#include "RP6M256Lib.h" 		// The RP6 M256 Library.
#else
	#error DEFINE "ARDUIO_RP6BASE", "ARDUIO_RP6CONTROL" OR "ARDUIO_RP6M256WIFI"
	#error AS TARGET IN RP6_ArduIOConfig.h
#endif
#endif
#endif
#include "RP6I2CmasterTWI.h"		// Include the I2C-Bus Master Library

/*****************************************************************************/
// ArduIO Status:

#define DISABLE_ON_SHUTDOWN				// Disable access to PPWM, PWM, Out
										// & DAC ports in SHUTDOWN mode
										// (default)!

// The ArduIO status bits with access settings & UB voltage low flag:
typedef union {
 	uint8_t byte;
	struct {
		unsigned ubatLow       :1;		// UB voltage low
		unsigned hb1Enable     :1;		// H-Bridge 1 (HB1) enable
		unsigned hb2Enable     :1;		// H-Bridge 2 (HB2) enable
		unsigned ppwm_g1Enable :1;		// Power PWM group 1 (PPWM1..4) enable
		unsigned ppwm_g2Enable :1;		// Power PWM group 2 (PPWM5..8) enable
		unsigned pwmsEnable    :1;		// Free PWMs (PWM1..4) enable
		unsigned outsEnable    :1;		// IO_1..3 IOs enable as outputs
		unsigned dasEnable     :1;		// ADDA_1..3 DACs enable
	};
} RP6ArduIOstatus_t;

extern RP6ArduIOstatus_t RP6ArduIOstatus;	// ArduIO status bits (read only)

void enableHB(uint8_t);
#define enableHB1() {enableHB(1);}
#define enableHB2() {enableHB(2);}
#define isHB1Enable() (RP6ArduIOstatus_LIB.byte & 2)
#define isHB2Enable() (RP6ArduIOstatus_LIB.byte & 4)
void disableHB(uint8_t);
#define disableHB1() {disableHB(1);}
#define disableHB2() {disableHB(2);}
void enablePPWM_G(uint8_t);
#define enablePPWM_G1() {enablePPWM_G(1);}
#define enablePPWM_G2() {enablePPWM_G(2);}
#define isPPWM_G1Enable() (RP6ArduIOstatus_LIB.byte & 8)
#define isPPWM_G2Enable() (RP6ArduIOstatus_LIB.byte & 16)
void disablePPWM_G(uint8_t);
#define disablePPWM_G1() {disablePPWM_G(1);}
#define disablePPWM_G2() {disablePPWM_G(2);}
void enablePWMs(void);
#define isPWMsEnable() (RP6ArduIOstatus_LIB.byte & 32)
void disablePWMs(void);
void enableOuts(void);
#define isOutsEnable() (RP6ArduIOstatus_LIB.byte & 64)
void disableOuts(void);
void enableDAs(void);
#define isDAsEnable() (RP6ArduIOstatus_LIB.byte & 128)
void disableDAs(void);
#define setArduIODefaultStatus() {enablePPWM_G(1);enablePPWM_G(2); \
 enablePWMs();enableOuts();enableDAs();}
#define setArduIOShutdownStatus() {disableHB(1);disableHB(2); \
 disablePPWM_G(1);disablePPWM_G(2);disablePWMs();disableOuts();disableDAs();}

/*****************************************************************************/
// I2C PWM 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_DEFAULT			17
#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_DEFAULT			4		// Totem poles (default)
#define PCA9685_MODE2_ARDUIO			16		// Inverted open-drains
#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_ARD_init(uint16_t);
#define initPWM(__FREQ__) {PCA9685_ARD_init(__FREQ__);}
void PCA9685_ARD_set(uint8_t, uint16_t);
#define setPWM(__CHANNEL__,__DUTY__) {PCA9685_ARD_set(__CHANNEL__,__DUTY__);}

/*****************************************************************************/
// I2C I/O Expander (PCF9535):

// Registers:
#define PCA9535_INPUT_P0				0
#define PCA9535_INPUT_P1				1
#define PCA9535_OUTPUT_P0				2
#define PCA9535_OUTPUT_P1				3
#define PCA9535_POL_INV_P0				4
#define PCA9535_POL_INV_P1				5
#define PCA9535_CONFIG_P0				6
#define PCA9535_CONFIG_P1				7

// I2C I/O Expander 1 5V (IC8: PCA9535):
#define IO_1							1
typedef union {
	uint16_t word;
	struct {
		unsigned P00:1;					// P00
		unsigned P01:1;					// P01
		unsigned P02:1;					// P02
		unsigned P03:1;					// P03
		unsigned P04:1;					// P04
		unsigned P05:1;					// P05
		unsigned P06:1;					// P06
		unsigned P07:1;					// P07
		unsigned P10:1;					// P10
		unsigned P11:1;					// P11
		unsigned P12:1;					// P12
		unsigned P13:1;					// P13
		unsigned P14:1;					// P14
		unsigned P15:1;					// P15
		unsigned P16:1;					// P16
		unsigned P17:1;					// P17
	};
	struct {
		unsigned GP100:1;				// IO_1: P00
		unsigned GP101:1;				// IO_1: P01
		unsigned GP102:1;				// IO_1: P02
		unsigned GP103:1;				// IO_1: P03
		unsigned GP104:1;				// IO_1: P04
		unsigned GP105:1;				// IO_1: P05
		unsigned GP106:1;				// IO_1: P06
		unsigned GP107:1;				// IO_1: P07
		unsigned GP110:1;				// IO_1: P10
		unsigned GP111:1;				// IO_1: P11
		unsigned GP112:1;				// IO_1: P12
		unsigned GP113:1;				// IO_1: P13
		unsigned GP114:1;				// IO_1: P14
		unsigned GP115:1;				// IO_1: P15
		unsigned GP116:1;				// IO_1: P16
		unsigned GP117:1;				// IO_1: P17
	};
} ioexp_1_t;

extern ioexp_1_t io1config;
extern ioexp_1_t io1invrt;
extern ioexp_1_t io1ins;
extern ioexp_1_t io1outs;

// I2C I/O Expander 2 5V (IC13: PCA9535):
#define IO_2							2
typedef union {
	uint16_t word;
	struct {
		unsigned P00:1;					// P00
		unsigned P01:1;					// P01
		unsigned P02:1;					// P02
		unsigned P03:1;					// P03
		unsigned P04:1;					// P04
		unsigned P05:1;					// P05
		unsigned P06:1;					// P06
		unsigned P07:1;					// P07
		unsigned P10:1;					// P10
		unsigned P11:1;					// P11
		unsigned P12:1;					// P12
		unsigned P13:1;					// P13
		unsigned P14:1;					// P14
		unsigned P15:1;					// P15
		unsigned P16:1;					// P16
		unsigned P17:1;					// P17
	};
	struct {
		unsigned GP200:1;				// IO_2: P00
		unsigned GP201:1;				// IO_2: P01
		unsigned GP202:1;				// IO_2: P02
		unsigned GP203:1;				// IO_2: P03
		unsigned GP204:1;				// IO_2: P04
		unsigned GP205:1;				// IO_2: P05
		unsigned GP206:1;				// IO_2: P06
		unsigned GP207:1;				// IO_2: P07
		unsigned GP210:1;				// IO_2: P10
		unsigned GP211:1;				// IO_2: P11
		unsigned GP212:1;				// IO_2: P12
		unsigned GP213:1;				// IO_2: P13
		unsigned GP214:1;				// IO_2: P14
		unsigned GP215:1;				// IO_2: P15
		unsigned GP216:1;				// IO_2: P16
		unsigned GP217:1;				// IO_2: P17
	};
	struct {
		unsigned ARD_D0:1;				// ARD: D0
		unsigned ARD_D1:1;				// ARD: D1
		unsigned ARD_D2:1;				// ARD: D2
		unsigned ARD_D3:1;				// ARD: D3
		unsigned ARD_D4:1;				// ARD: D4
		unsigned ARD_D5:1;				// ARD: D5
		unsigned ARD_D6:1;				// ARD: D6
		unsigned ARD_D7:1;				// ARD: D7
		unsigned ARD_D13:1;				// ARD: D13
		unsigned ARD_D12:1;				// ARD: D12
		unsigned ARD_D11:1;				// ARD: D11
		unsigned ARD_D10:1;				// ARD: D10
		unsigned ARD_D9:1;				// ARD: D9
		unsigned ARD_D8:1;				// ARD: D8
		unsigned GP216:1;				// IO_2: P16
		unsigned GP217:1;				// IO_2: P17
	};
} ioexp_2_t;

extern ioexp_2_t io2config;
extern ioexp_2_t io2invrt;
extern ioexp_2_t io2ins;
extern ioexp_2_t io2outs;

// I2C I/O Expander 3 3V3 (IC12: PCA9535):
#define IO_3							3
typedef union {
	uint16_t word;
	struct {
		unsigned P00:1;					// P00
		unsigned P01:1;					// P01
		unsigned P02:1;					// P02
		unsigned P03:1;					// P03
		unsigned P04:1;					// P04
		unsigned P05:1;					// P05
		unsigned P06:1;					// P06
		unsigned P07:1;					// P07
		unsigned P10:1;					// P10
		unsigned P11:1;					// P11
		unsigned P12:1;					// P12
		unsigned P13:1;					// P13
		unsigned P14:1;					// P14
		unsigned P15:1;					// P15
		unsigned P16:1;					// P16
		unsigned P17:1;					// P17
	};
	struct {
		unsigned GP300:1;				// IO_3: P00
		unsigned GP301:1;				// IO_3: P01
		unsigned GP302:1;				// IO_3: P02
		unsigned GP303:1;				// IO_3: P03
		unsigned GP304:1;				// IO_3: P04
		unsigned GP305:1;				// IO_3: P05
		unsigned GP306:1;				// IO_3: P06
		unsigned GP307:1;				// IO_3: P07
		unsigned GP310:1;				// IO_3: P10
		unsigned GP311:1;				// IO_3: P11
		unsigned GP312:1;				// IO_3: P12
		unsigned GP313:1;				// IO_3: P13
		unsigned GP314:1;				// IO_3: P14
		unsigned GP315:1;				// IO_3: P15
		unsigned GP316:1;				// IO_3: P16
		unsigned GP317:1;				// IO_3: P17
	};
} ioexp_3_t;

extern ioexp_3_t io3config;
extern ioexp_3_t io3invrt;
extern ioexp_3_t io3ins;
extern ioexp_3_t io3outs;

// I2C I/O Expander (PCA9535) interrupt status bits:
typedef union {
 	uint8_t byte;
	struct {
		unsigned int1    :1;			// INT1  XBUS Pin 8
		unsigned int2    :1;			// INT2  XBUS Pin 11
		unsigned int3    :1;			// INT3  XBUS Pin 9
		unsigned intu    :1;			// INTU  XBUS Pin 7
		unsigned unused  :4;
	};
	struct {
		unsigned ioexp_2 :1;			// INT1: PCA9535 (2) INT
		unsigned ioexp_1 :1;			// INT2: PCA9535 (1) INT
		unsigned ioexp_3 :1;			// INT3: PCA9535 (3) INT
		unsigned noname  :5;
	};
} interrupt_RP6ArduIOstatus_t;

extern interrupt_RP6ArduIOstatus_t interrupt_RP6ArduIOstatus;
extern uint8_t interrupt_rp6arduiostatus_changed;

// I2C I/O Expander (PCA9535) general functions:
void configArduIO_IO(uint8_t, uint16_t);
#define configArduIO_IO1(__INOUT__) {configArduIO_IO(1,__INOUT__);}
#define configArduIO_IO2(__INOUT__) {configArduIO_IO(2,__INOUT__);}
#define configArduIO_IO3(__INOUT__) {configArduIO_IO(3,__INOUT__);}
void updateArduIO_IO(uint8_t);
#define updateArduIO_IO1() {updateArduIO_IO(1);}
#define updateArduIO_IO2() {updateArduIO_IO(2);}
#define updateArduIO_IO3() {updateArduIO_IO(3);}
void setArduIO_IO(uint8_t, uint16_t);
#define setArduIO_IO1(__OUT__) {setArduIO_IO(1,__OUT__);}
#define setArduIO_IO2(__OUT__) {setArduIO_IO(2,__OUT__);}
#define setArduIO_IO3(__OUT__) {setArduIO_IO(3,__OUT__);}
void invertArduIO_IO(uint8_t, uint16_t);
#define invertArduIO_IO1(__INVRT__) {invertArduIO_IO(1,__INVRT__);}
#define invertArduIO_IO2(__INVRT__) {invertArduIO_IO(2,__INVRT__);}
#define invertArduIO_IO3(__INVRT__) {invertArduIO_IO(3,__INVRT__);}
void task_readArduIO_IO(uint8_t);
#define task_readArduIO_IO1() {task_readArduIO_IO(1);}
#define task_readArduIO_IO2() {task_readArduIO_IO(2);}
#define task_readArduIO_IO3() {task_readArduIO_IO(3);}
#define task_readAllArduIO_IOs() {task_readArduIO_IO(1); \
 task_readArduIO_IO(2);task_readArduIO_IO(3);}
void task_checkArduIO_INTs(void);
#define int_status_changed() (interrupt_rp6arduiostatus_changed)

/*****************************************************************************/
// I2C A/D and D/A Converter (PCF8591):

#define READ_ADCUB	// If defined: Function task_readArduIO_AD(1) will also
					//  (default)  read the UB voltage ADC value (adcub) and
					//             will update the UB voltage low condition
					//             flag (RP6ArduIOstatus.ubatLow)!
					// If NOT defined: The UB voltage ADC value can be found
					//                 in the variable ad1ins.ArduIO_UB after
					//                 execution of task_readArduIO_AD(1)!
					// READ_ADCUB should NOT be defined, if jumper JP_AD-UB
					// on the ArduIO Board is OPEN!

// Control Byte bitmasks:
#define PCF8591_CONTROL_DEFAULT			0
#define PCF8591_CONTROL_ARDUIO			0b01000100	// Auto-increment & DAC

#define PCF8591_CONTROL_AUTO_INC		4			// Auto-increment
#define PCF8591_CONTROL_DAC_ENABLE		64			// DAC enable

// I2C A/D and D/A Converter 1 (IC11: PCF8591):
#define ADDA_1							1
typedef union {
	struct {
		uint8_t AIN0;					// AIN0
		uint8_t AIN1;					// AIN1
		uint8_t AIN2;					// AIN2
		uint8_t AIN3;					// AIN3
	};
	struct {
		uint8_t AD10;					// ADDA_1: AIN0
		uint8_t AD11;					// ADDA_1: AIN1
		uint8_t AD12;					// ADDA_1: AIN2
		uint8_t AD13;					// ADDA_1: AIN3
	};
	struct {
		uint8_t AD10;					// ADDA_1: AIN0
		uint8_t AD11;					// ADDA_1: AIN1
		uint8_t AD12;					// ADDA_1: AIN2
		uint8_t ArduIO_UB;				// ArduIO: UB
	};
} addaexp_1_t;

extern addaexp_1_t ad1ins;

// I2C A/D and D/A Converter 2 (IC10: PCF8591):
#define ADDA_2							2
typedef union {
	struct {
		uint8_t AIN0;					// AIN0
		uint8_t AIN1;					// AIN1
		uint8_t AIN2;					// AIN2
		uint8_t AIN3;					// AIN3
	};
	struct {
		uint8_t AD20;					// ADDA_2: AIN0
		uint8_t AD21;					// ADDA_2: AIN1
		uint8_t AD22;					// ADDA_2: AIN2
		uint8_t AD23;					// ADDA_2: AIN3
	};
} addaexp_2_t;

extern addaexp_2_t ad2ins;

// I2C A/D and D/A Converter 3 (IC9: PCF8591):
#define ADDA_3							3
typedef union {
	struct {
		uint8_t AIN0;					// AIN0
		uint8_t AIN1;					// AIN1
		uint8_t AIN2;					// AIN2
		uint8_t AIN3;					// AIN3
	};
	struct {
		uint8_t AD30;					// ADDA_3: AIN0
		uint8_t AD31;					// ADDA_3: AIN1
		uint8_t AD32;					// ADDA_3: AIN2
		uint8_t AD33;					// ADDA_3: AIN3
	};
	struct {
		uint8_t ARD_A0;					// ARD: A0
		uint8_t ARD_A1;					// ARD: A1
		uint8_t ARD_A2;					// ARD: A2
		uint8_t ARD_A3;					// ARD: A3
	};
} addaexp_3_t;

extern addaexp_3_t ad3ins;

// I2C A/D and D/A Converter (PCF8591) general functions:
#define UCV_AD(__AD__) (uint16_t)(__AD__*500.0f/255.0f)

void task_readArduIO_AD(uint8_t);
#define task_readArduIO_AD1() {task_readArduIO_AD(1);}
#define task_readArduIO_AD2() {task_readArduIO_AD(2);}
#define task_readArduIO_AD3() {task_readArduIO_AD(3);}
#define task_readAllArduIO_ADs() {task_readArduIO_AD(1); \
 task_readArduIO_AD(2);task_readArduIO_AD(3);}

#define AOUT_CV(__CV__) (uint8_t)(__CV__*0.51f)

extern uint8_t da1aout;
extern uint8_t da2aout;
extern uint8_t da3aout;

void writeArduIO_DA(uint8_t, uint8_t);
#define writeArduIO_DA1(__AOUT__) {writeArduIO_DA(1,__AOUT__);}
#define writeArduIO_DA2(__AOUT__) {writeArduIO_DA(2,__AOUT__);}
#define writeArduIO_DA3(__AOUT__) {writeArduIO_DA(3,__AOUT__);}
void disableArduIO_DA(uint8_t);
#define disableArduIO_DA1() {disableArduIO_DA(1);}
#define disableArduIO_DA2() {disableArduIO_DA(2);}
#define disableArduIO_DA3() {disableArduIO_DA(3);}
#define disableAllArduIO_DAs() {disableArduIO_DA(1); \
 disableArduIO_DA(2);disableArduIO_DA(3);}

/*****************************************************************************/
// UB Voltage Sensor:

extern uint8_t adcub;
extern double ubv;

uint8_t getUbSensor(void);
double calculateUb(void);
double measureUb(void);
#define isUbLow() (RP6ArduIOstatus_LIB.byte & 1)

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

// --------------------------------------------------------------
// Duty cycle constants:
#define DUTY_0							0		// 0%
#define DUTY_10							409		// 10%
#define DUTY_25							1023	// 25%
#define DUTY_50							2047	// 50%
#define DUTY_75							3071	// 75%
#define DUTY_90							3685	// 90%
#define DUTY_100						4095	// 100%
// Relative duty cycle [__PCT__ = 0..100%] macro:
#define DUTY_PCT(__PCT__) (uint16_t)((uint32_t)__PCT__*4095/100)
// --------------------------------------------------------------

void setArduIOLEDs(uint8_t);

void dimArduIOLED(uint8_t, uint16_t);
#define dimArduIOLED1(__DUTY__) {dimArduIOLED(1,__DUTY__);}
#define dimArduIOLED2(__DUTY__) {dimArduIOLED(2,__DUTY__);}
#define dimArduIOLED3(__DUTY__) {dimArduIOLED(3,__DUTY__);}
#define dimArduIOLED4(__DUTY__) {dimArduIOLED(4,__DUTY__);}
void setArduIOLED1(uint8_t);
void setArduIOLED2(uint8_t);
void setArduIOLED3(uint8_t);
void setArduIOLED4(uint8_t);

/*****************************************************************************/
// PWM Ports:

void setArduIOPWMs(uint8_t);

void dimArduIOPWM(uint8_t, uint16_t);
#define dimArduIOPWM1(__DUTY__) {dimArduIOPWM(1,__DUTY__);}
#define dimArduIOPWM2(__DUTY__) {dimArduIOPWM(2,__DUTY__);}
#define dimArduIOPWM3(__DUTY__) {dimArduIOPWM(3,__DUTY__);}
#define dimArduIOPWM4(__DUTY__) {dimArduIOPWM(4,__DUTY__);}
void setArduIOPWM1(uint8_t);
void setArduIOPWM2(uint8_t);
void setArduIOPWM3(uint8_t);
void setArduIOPWM4(uint8_t);

/*****************************************************************************/
// Power PWM Ports & H-Bridges:

// Power PWM Ports:
void setArduIOPowerPWMMode(void);
void setArduIOPowerPWMs(uint8_t);

void dimArduIOPowerPWM(uint8_t, uint16_t);
#define dimArduIOPowerPWM1(__DUTY__) {dimArduIOPowerPWM(1,__DUTY__);}
#define dimArduIOPowerPWM2(__DUTY__) {dimArduIOPowerPWM(2,__DUTY__);}
#define dimArduIOPowerPWM3(__DUTY__) {dimArduIOPowerPWM(3,__DUTY__);}
#define dimArduIOPowerPWM4(__DUTY__) {dimArduIOPowerPWM(4,__DUTY__);}
#define dimArduIOPowerPWM5(__DUTY__) {dimArduIOPowerPWM(5,__DUTY__);}
#define dimArduIOPowerPWM6(__DUTY__) {dimArduIOPowerPWM(6,__DUTY__);}
#define dimArduIOPowerPWM7(__DUTY__) {dimArduIOPowerPWM(7,__DUTY__);}
#define dimArduIOPowerPWM8(__DUTY__) {dimArduIOPowerPWM(8,__DUTY__);}
void setArduIOPowerPWM1(uint8_t);
void setArduIOPowerPWM2(uint8_t);
void setArduIOPowerPWM3(uint8_t);
void setArduIOPowerPWM4(uint8_t);
void setArduIOPowerPWM5(uint8_t);
void setArduIOPowerPWM6(uint8_t);
void setArduIOPowerPWM7(uint8_t);
void setArduIOPowerPWM8(uint8_t);

// H-Bridges:

// ------------------------------------------------------------
// Direction/command:
#ifndef FWD
#define FWD								0		// Forwards
#define BWD								1		// Backwards
#endif
#define BRK								4		// Speed break
#define OFF								5		// Power OFF
// ------------------------------------------------------------

void adjustArduIOPowerHB(uint8_t hb, uint8_t dir, uint16_t duty);
#define powerHB1(__DIR__,__DUTY__) {adjustArduIOPowerHB(1,__DIR__,__DUTY__);}
#define powerHB1STOP() {adjustArduIOPowerHB(1,FWD,DUTY_0);}
#define powerHB1FWD(__DUTY__) {adjustArduIOPowerHB(1,FWD,__DUTY__);}
#define powerHB1BWD(__DUTY__) {adjustArduIOPowerHB(1,BWD,__DUTY__);}
#define powerHB1BRK() {adjustArduIOPowerHB(1,BRK,0);}
#define powerHB1OFF() {adjustArduIOPowerHB(1,OFF,0);}
#define powerHB2(__DIR__,__DUTY__) {adjustArduIOPowerHB(2,__DIR__,__DUTY__);}
#define powerHB2STOP() {adjustArduIOPowerHB(2,FWD,DUTY_0);}
#define powerHB2FWD(__DUTY__) {adjustArduIOPowerHB(2,FWD,__DUTY__);}
#define powerHB2BWD(__DUTY__) {adjustArduIOPowerHB(2,BWD,__DUTY__);}
#define powerHB2BRK() {adjustArduIOPowerHB(2,BRK,0);}
#define powerHB2OFF() {adjustArduIOPowerHB(2,OFF,0);}

/*****************************************************************************/
// ArduIO Board system control routine:

void task_RP6_ArduIOSystem(void);

/*****************************************************************************/
// ArduIO Board initialisation and shutdown:

void arduio_init(void);
void arduio_shutdown(void);

/*****************************************************************************/
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*                      Arduino Uno Expander functions                       */
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
void updateArduino_Uno_Exp_IO(void);
void setArduino_Uno_Exp_IO(uint16_t);
#define task_readArduino_Uno_Exp_IO() {task_readArduIO_IO(2);}
#define task_readArduino_Uno_Exp_AD() {task_readArduIO_AD(3);}
#define dimArduino_Uno_Exp_PWM(__PWM__,__DUTY__) \
 {dimArduIOPWM(__PWM__,(4095-__DUTY__));}
#define dimArduino_Uno_Exp_PWM1(__DUTY__) \
 {dimArduIOPWM(1,(4095-__DUTY__));}
#define dimArduino_Uno_Exp_PWM2(__DUTY__) \
 {dimArduIOPWM(2,(4095-__DUTY__));}
#define dimArduino_Uno_Exp_PWM3(__DUTY__) \
 {dimArduIOPWM(3,(4095-__DUTY__));}
// ArduIO Board Arduino Uno Expander control routine:
void task_Arduino_Uno_Exp(void);

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*                    Arduino Uno Expander functions end                     */
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*****************************************************************************/

#endif

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

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

Diese Datei enthält den "Sourcecode" der neuen ArduIO Library. Sie gehört in den Ordner /.../RP6Lib/RP6common/.

Datei RP6_ArduIOLib.c:

/* ****************************************************************************
 *                           _______________________
 *                           \| RP6  ROBOT SYSTEM |/
 *                            \_-_-_-_-_-_-_-_-_-_/                  >>> COMMON
 * ----------------------------------------------------------------------------
 * ----------------------------- [c]2014 - Dirk -------------------------------
 * ****************************************************************************
 * File: RP6_ArduIOLib.c
 * Version: 1.1
 * Target: RP6 Base & Processor Expansion - ATMEGA32 @8.00 or 16.00MHz
 *         & RP6 M256 WiFi                - ATMEGA2560 @16.00MHz
 *         with the RP6_ArduIO Board.
 * Author(s): Dirk
 * ****************************************************************************
 * Description:
 * 
 * This is our new Library that contains basic routines and functions for
 * accessing the hardwired components of the ArduIO Board.
 *
 * ****************************************************************************
 * THE CHANGELOG CAN BE FOUND AT THE END OF THIS FILE!
 * ****************************************************************************
 */

/*****************************************************************************/
// ArduIO hardwired components:
// - I2C PWM Controller (IC3: PCA9685)
// - I2C I/O Expander 1 5V (IC8: PCA9535)
// - I2C I/O Expander 2 5V (IC13: PCA9535)
// - I2C I/O Expander 3 3V3 (IC12: PCA9535)
// - I2C A/D and D/A Converter 1 (IC11: PCF8591)
// - I2C A/D and D/A Converter 2 (IC10: PCF8591)
// - I2C A/D and D/A Converter 3 (IC9: PCF8591)
// - UB Voltage Sensor
// - LEDs
// - PWM Ports
// - Power PWM Ports & H-Bridges

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

#include "RP6_ArduIOLib.h" 		

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

uint8_t registerBuf[5]; 

/*****************************************************************************/
// ArduIO Status:

RP6ArduIOstatus_t RP6ArduIOstatus;		// ArduIO status bits (public)
RP6ArduIOstatus_t RP6ArduIOstatus_LIB;	// ArduIO status bits (lib internal)

/**
 * Enable access to a H-Bridge [1 or 2].
 *
 * HB1: Power PWM group 1 (power PWM numbers 1..4)
 * HB2: Power PWM group 2 (power PWM numbers 5..8)
 *
 * Input: hb -> H-Bridge (HB) number [1 or 2]
 *
 * There is also a macro enableHBx(),
 * which does exactly the same as this function,
 * where x = H-Bridge number = [1 or 2].
 * There is a macro isHBxEnable(), that may be
 * used to read the HBx access status.
 *
 * Hints: - If you ENABLE access to a H-Bridge,
 *          access to the corresponding power
 *          PWM group will be DISABLED!
 *        - In order to use H-Bridge 1, you have
 *          to connect pins 3-4 and 5-6 of the
 *          SV_H-BRIDGES plug on the ArduIO
 *          Board!
 *        - Motor 1 connection schematic:
 *           Pins      Motor 1      pins
 *           ---------------------------
 *            3-4  ->  +     -  <-  5-6
 *        - In order to use H-Bridge 2, you have
 *          to connect pins 7-8 and 9-10 of the
 *          SV_H-BRIDGES plug on the ArduIO
 *          Board!
 *        - Motor 2 connection schematic:
 *           Pins      Motor 2      pins
 *           ---------------------------
 *            7-8  ->  +     -  <-  9-10
 *
 * Example:
 *   enableHB1();   // Or enableHB(1);
 *   // this enables access to H-Bridge 1!
 *
 */
void enableHB(uint8_t hb)
{
	if (hb == 1) {
		RP6ArduIOstatus_LIB.ppwm_g1Enable = false;
		RP6ArduIOstatus_LIB.hb1Enable = true;
	}
	if (hb == 2) {
		RP6ArduIOstatus_LIB.ppwm_g2Enable = false;
		RP6ArduIOstatus_LIB.hb2Enable = true;
	}
	RP6ArduIOstatus.byte = RP6ArduIOstatus_LIB.byte;
}

/**
 * Disable access to a H-Bridge [1 or 2]
 * (default).
 *
 * Input: hb -> H-Bridge (HB) number [1 or 2]
 *
 * Example:
 *   disableHB2();   // Or disableHB(2);
 *   // this disables access to H-Bridge 2!
 *
 */
void disableHB(uint8_t hb)
{
	if (hb == 1) RP6ArduIOstatus_LIB.hb1Enable = false;
	if (hb == 2) RP6ArduIOstatus_LIB.hb2Enable = false;
	RP6ArduIOstatus.byte = RP6ArduIOstatus_LIB.byte;
}

/**
 * Enable access to a power PWM group [1 or 2]
 * (default).
 *
 * Power PWM group 1: HB1 (power PWM numbers 1..4)
 * Power PWM group 2: HB2 (power PWM numbers 5..8)
 *
 * Input: ppwm_g -> Power PWM group [1 or 2]
 *
 * There is also a macro enablePPWM_Gx(),
 * which does exactly the same as this function,
 * where x = Power PWM group = [1 or 2].
 * There is a macro isPPWM_GxEnable(), that may
 * be used to read the power PWM group x access
 * status.
 *
 * Hints: - If you ENABLE access to a power PWM
 *          group, access to the corresponding
 *          H-Bridge will be DISABLED!
 *        - ! IF  YOU  WANT  TO  USE  POWER  PWM !
 *          ! NUMBERS  1..4  (POWER PWM GROUP 1) !
 *          ! AS 4 SINGLE POWER PWM OUTPUTS, YOU !
 *          ! HAVE TO ENSURE,  THAT PINS 3-4 AND !
 *          ! 5-6  OF SV_H-BRIDGES PLUG ARE  NOT !
 *          ! CONNECTED!!!  YOU MAY  DAMAGE  THE !
 *          ! ARDUIO  BOARD,  IF THESE PINS  ARE !
 *          ! CONNECTED!!!                       !
 *        - ! IF  YOU  WANT  TO  USE  POWER  PWM !
 *          ! NUMBERS  5..8  (POWER PWM GROUP 2) !
 *          ! AS 4 SINGLE POWER PWM OUTPUTS, YOU !
 *          ! HAVE TO ENSURE,  THAT PINS 7-8 AND !
 *          ! 9-10 OF SV_H-BRIDGES PLUG ARE  NOT !
 *          ! CONNECTED!!!  YOU MAY  DAMAGE  THE !
 *          ! ARDUIO  BOARD,  IF THESE PINS  ARE !
 *          ! CONNECTED!!!                       !
 *
 * Example:
 *   enablePPWM_G1();   // Or enablePPWM_G(1);
 *   // this enables access to power PWM group 1
 *   // (power PWM numbers 1..4)!
 *
 */
void enablePPWM_G(uint8_t ppwm_g)
{
	if (ppwm_g == 1) {
		RP6ArduIOstatus_LIB.hb1Enable = false;
		RP6ArduIOstatus_LIB.ppwm_g1Enable = true;
	}
	if (ppwm_g == 2) {
		RP6ArduIOstatus_LIB.hb2Enable = false;
		RP6ArduIOstatus_LIB.ppwm_g2Enable = true;
	}
	RP6ArduIOstatus.byte = RP6ArduIOstatus_LIB.byte;
}

/**
 * Disable access to a power PWM group [1 or 2].
 *
 * Input: ppwm_g -> Power PWM group [1 or 2]
 *
 * Example:
 *   disablePPWM_G2();   // Or disablePPWM_G(2);
 *   // this disables access to power PWM group 2
 *   // (power PWM numbers 5..8)!
 *
 */
void disablePPWM_G(uint8_t ppwm_g)
{
	if (ppwm_g == 1) RP6ArduIOstatus_LIB.ppwm_g1Enable = false;
	if (ppwm_g == 2) RP6ArduIOstatus_LIB.ppwm_g2Enable = false;
	RP6ArduIOstatus.byte = RP6ArduIOstatus_LIB.byte;
}

/**
 * Enable access to the 4 free PWMs (default).
 * There is a macro isPWMsEnable(), that may be
 * used to read the PWMs access status.
 *
 */
void enablePWMs(void)
{
	RP6ArduIOstatus_LIB.pwmsEnable = true;
	RP6ArduIOstatus.byte = RP6ArduIOstatus_LIB.byte;
}

/**
 * Disable access to the 4 free PWMs.
 *
 */
void disablePWMs(void)
{
	RP6ArduIOstatus_LIB.pwmsEnable = false;
	RP6ArduIOstatus.byte = RP6ArduIOstatus_LIB.byte;
}

/**
 * Enable access to all IO_1..3 IO ports to be
 * used as outputs (Outs) (default).
 * There is a macro isOutsEnable(), that may be
 * used to read the Outs access status.
 *
 */
void enableOuts(void)
{
	RP6ArduIOstatus_LIB.outsEnable = true;
	RP6ArduIOstatus.byte = RP6ArduIOstatus_LIB.byte;
}

/**
 * Disable access to all IO_1..3 IO ports to be
 * used as outputs (Outs).
 *
 * Hint: The IO_1..3 IO ports can ALWAYS be used
 *       as inputs (Ins)!
 *
 */
void disableOuts(void)
{
	RP6ArduIOstatus_LIB.outsEnable = false;
	RP6ArduIOstatus.byte = RP6ArduIOstatus_LIB.byte;
}

/**
 * Enable access to all ADDA_1..3 DACs (default).
 * There is a macro isDAsEnable(), that may be
 * used to read the DACs access status.
 *
 */
void enableDAs(void)
{
	RP6ArduIOstatus_LIB.dasEnable = true;
	RP6ArduIOstatus.byte = RP6ArduIOstatus_LIB.byte;
}

/**
 * Disable access to all ADDA_1..3 DACs.
 *
 * Hint: The 3 DAC outputs (AOUT) are NOT
 *       disabled by this function! Pls. use
 *       function disableAllArduIO_DAs() for
 *       this!
 *
 */
void disableDAs(void)
{
	RP6ArduIOstatus_LIB.dasEnable = false;
	RP6ArduIOstatus.byte = RP6ArduIOstatus_LIB.byte;
}

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

/**
 * Call this once before using the PWM function.
 *
 * Input: PWM frequency [40..1000 Hz]
 *
 * There is also a macro initPWM(freq), which
 * does exactly the same as this function.
 *
 * Example:
 *   initPWM(1000);   // Or PCA9685_ARD_init(1000);
 *
 */
void PCA9685_ARD_init(uint16_t freq)
{
	if ((freq < 40) || (freq > 1000)) freq = 1000;
	I2CTWI_transmitByte(I2C_ARDUIO_PWM_ADR, PCA9685_MODE2);
	uint8_t last_mode = I2CTWI_readByte(I2C_ARDUIO_PWM_ADR);
	last_mode |= PCA9685_MODE2_INVRT;			// Set INVRT bit
	last_mode &= ~PCA9685_MODE2_OUTDRV;			// Clear OUTDRV bit
	I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_MODE2, last_mode);
	I2CTWI_transmitByte(I2C_ARDUIO_PWM_ADR, PCA9685_MODE1);
	last_mode = I2CTWI_readByte(I2C_ARDUIO_PWM_ADR);
	last_mode |= PCA9685_MODE1_AI;				// Set AI bit
	uint8_t mode1 = last_mode;
	mode1 |= PCA9685_MODE1_SLEEP;				// Set SLEEP bit
	I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_MODE1, mode1);
	uint8_t prescale = (uint8_t) (F_PCA9685 / 4096 / freq - 0.5);
	I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_PRE_SCALE, prescale);
	last_mode &= ~PCA9685_MODE1_SLEEP;			// Clear SLEEP bit
	I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_MODE1, last_mode);
	mSleep(1);
	last_mode |= PCA9685_MODE1_RESTART;			// Clear RESTART bit
	I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_MODE1, last_mode);
	return;
}

/**
 * This is the PWM duty set function.
 *
 * Input: channel -> Channel number [1..16]
 *                   0 = ALL 16 channels
 *        duty    -> Duty cycle [0..4095]
 *
 * There is also a macro setPWM(channel, duty),
 * which does exactly the same as this function.
 *
 * Example:
 *   setPWM(2,300);   // Or PCA9685_ARD_set(2,300);
 *   // this sets channel 2 with a duty cycle
 *   // value of 300 (about 7.33%).
 *
 */
void PCA9685_ARD_set(uint8_t channel, uint16_t duty)
{
	if (channel > 16) return;
	if (duty > 4095) duty = 4095;
	uint8_t reg = channel * 4 + 4;				// Register LEDx_OFF_L
	if (!channel) reg = PCA9685_ALL_LED_OFF_L;	// Register ALL_LED_OFF_L
	I2CTWI_transmit3Bytes(I2C_ARDUIO_PWM_ADR, reg, (duty & 0x00ff), (duty >> 8));
}

/*****************************************************************************/
// I2C I/O Expander (PCA9535):

ioexp_1_t io1config;
ioexp_2_t io2config;
ioexp_3_t io3config;

/**
 * Configurate the portpins of an IO_x port as
 * input or output. This port configuration is
 * stored in the global ioxconfig variable, where
 * x = IO-Expander number = [1..3].
 *
 * Input: io    -> IO-Expander number [1..3]
 *        inout -> Config value (16 bit):
 *                  Bit 0 = output
 *                  Bit 1 = input
 *
 * There is also a macro configArduIO_IOx(inout),
 * which does exactly the same as this function,
 * where x = IO-Expander number = [1..3].
 *
 * Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 *       ! THE ACCESS IS ENABLED (default): !
 *       !   ==> enableOuts(); <==          !
 *
 * Example:
 *   configArduIO_IO(IO_1,0b0000000000101001);
 *   // this configures the IO_1 portpins P00,
 *   // P03 and P05 as INPUTs and all other
 *   // portpins as OUTPUTs!
 *   configArduIO_IO1(0b0000000000101001);
 *   // does exactly the same!
 *
 */
void configArduIO_IO(uint8_t io, uint16_t inout)
{
	if (RP6ArduIOstatus_LIB.outsEnable || (inout == 0xffff)) {
		switch (io) {							// IO-Expander number:
			case IO_1 :							//  IO_1
				I2CTWI_transmit3Bytes(I2C_ARDUIO_IO_1_ADR, PCA9535_CONFIG_P0, (inout & 0x00ff), (inout >> 8));
				io1config.word = inout;
				break;
			case IO_2 :							//  IO_2
				I2CTWI_transmit3Bytes(I2C_ARDUIO_IO_2_ADR, PCA9535_CONFIG_P0, (inout & 0x00ff), (inout >> 8));
				io2config.word = inout;
				break;
			case IO_3 :							//  IO_3
				I2CTWI_transmit3Bytes(I2C_ARDUIO_IO_3_ADR, PCA9535_CONFIG_P0, (inout & 0x00ff), (inout >> 8));
				io3config.word = inout;
		}
	}
}

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

ioexp_1_t io1outs;
ioexp_2_t io2outs;
ioexp_3_t io3outs;

/**
 * Update an IO_x port with current value from
 * the global ioxouts variable, where x = IO-
 * Expander number = [1..3].
 * The 16 IO_x portpins will be SET (high, ON)
 * or CLEARED (low, OFF).
 *
 * Input: io  -> IO-Expander number [1..3]
 *
 * There is also a macro updateArduIO_IOx(),
 * which does exactly the same as this function,
 * where x = IO-Expander number = [1..3].
 *
 * Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 *       ! THE ACCESS IS ENABLED (default): !
 *       !   ==> enableOuts(); <==          !
 *
 * Examples:
 *   io1outs.word = 0b0000000000101001;
 *   updateArduIO_IO1();
 *   // this CLEARs the port and SETs the
 *   // IO_1 portpins P00, P03 and P05!
 *
 *   // Other possibility:
 *   io3outs.GP316 = true;   // Or io3outs.P16 = true;
 *   updateArduIO_IO(IO_3);
 *   // this SETs the IO_3 portpin P16 and
 *   // does not affect any other portpin!
 *
 */
void updateArduIO_IO(uint8_t io)
{
	if (RP6ArduIOstatus_LIB.outsEnable) {
		switch (io) {							// IO-Expander number:
			case IO_1 :							//  IO_1
				I2CTWI_transmit3Bytes(I2C_ARDUIO_IO_1_ADR, PCA9535_OUTPUT_P0, (io1outs.word & 0x00ff), (io1outs.word >> 8));
				break;
			case IO_2 :							//  IO_2
				I2CTWI_transmit3Bytes(I2C_ARDUIO_IO_2_ADR, PCA9535_OUTPUT_P0, (io2outs.word & 0x00ff), (io2outs.word >> 8));
				break;
			case IO_3 :							//  IO_3
				I2CTWI_transmit3Bytes(I2C_ARDUIO_IO_3_ADR, PCA9535_OUTPUT_P0, (io3outs.word & 0x00ff), (io3outs.word >> 8));
		}
	}
}

/**
 * This function SETs (high, ON) or CLEARs
 * (low, OFF) the 16 IO_x portpins, where
 * x = IO-Expander number = [1..3].
 *
 * Input: io  -> IO-Expander number [1..3]
 *        out -> Output value (16 bit)
 *
 * There is also a macro setArduIO_IOx(out),
 * which does exactly the same as this function,
 * where x = IO-Expander number = [1..3].
 *
 * Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 *       ! THE ACCESS IS ENABLED (default): !
 *       !   ==> enableOuts(); <==          !
 *
 * Example:
 *   setArduIO_IO(IO_1,0b0000000000101001);
 *   // this CLEARs the port and SETs the
 *   // IO_1 portpins P00, P03 and P05!
 *   setArduIO_IO1(0b0000000000101001);
 *   // does exactly the same!
 *
 */
void setArduIO_IO(uint8_t io, uint16_t out)
{
	if (RP6ArduIOstatus_LIB.outsEnable) {
		switch (io) {							// IO-Expander number:
			case IO_1 :							//  IO_1
				io1outs.word = out;
				updateArduIO_IO(IO_1);
				break;
			case IO_2 :							//  IO_2
				io2outs.word = out;
				updateArduIO_IO(IO_2);
				break;
			case IO_3 :							//  IO_3
				io3outs.word = out;
				updateArduIO_IO(IO_3);
		}
	}
}

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

ioexp_1_t io1invrt;
ioexp_2_t io2invrt;
ioexp_3_t io3invrt;

/**
 * Invert the input values of the portpins of an
 * IO_x port. This port setting is stored in the
 * global ioxinvrt variable, where x = IO-
 * Expander number = [1..3].
 *
 * Input: io    -> IO-Expander number [1..3]
 *        invrt -> Setting value (16 bit):
 *                  Bit 0 = retain
 *                  Bit 1 = invert
 *
 * There is also a macro invertArduIO_IOx(invrt),
 * which does exactly the same as this function,
 * where x = IO-Expander number = [1..3].
 *
 * Example:
 *   invertArduIO_IO(IO_1,0b0000000000101001);
 *   // this inverts the input values of the IO_1
 *   // portpins P00, P03 and P05 and retains the
 *   // input values of all other portpins!
 *   invertArduIO_IO1(0b0000000000101001);
 *   // does exactly the same!
 *
 */
void invertArduIO_IO(uint8_t io, uint16_t invrt)
{
	switch (io) {								// IO-Expander number:
		case IO_1 :								//  IO_1
			I2CTWI_transmit3Bytes(I2C_ARDUIO_IO_1_ADR, PCA9535_POL_INV_P0, (invrt & 0x00ff), (invrt >> 8));
			io1invrt.word = invrt;
			break;
		case IO_2 :								//  IO_2
			I2CTWI_transmit3Bytes(I2C_ARDUIO_IO_2_ADR, PCA9535_POL_INV_P0, (invrt & 0x00ff), (invrt >> 8));
			io2invrt.word = invrt;
			break;
		case IO_3 :								//  IO_3
			I2CTWI_transmit3Bytes(I2C_ARDUIO_IO_3_ADR, PCA9535_POL_INV_P0, (invrt & 0x00ff), (invrt >> 8));
			io3invrt.word = invrt;
	}
}

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

ioexp_1_t io1ins;
ioexp_2_t io2ins;
ioexp_3_t io3ins;

/**
 * This function checks an IO_x port with it's
 * 16 pins (P00..P17), where x = IO-Expander
 * number = [1..3]!
 * You may call this function (task) frequently
 * out of the main loop.
 * The input values (true/false, high/low) of the
 * portpins are read into the global ioxins
 * variable.
 *
 * Input: io  -> IO-Expander number [1..3]
 *
 * There is also a macro task_readArduIO_IOx(),
 * which does exactly the same as this function,
 * where x = IO-Expander number = [1..3].
 * The macro task_readAllArduIO_IOs() reads the
 * portpins (P00..P17) of ALL 3 IO-Expanders.
 *
 * Hint: The portpin input values can be
 *       inverted with the function
 *       invertArduIO_IO(io,invrt)!
 *
 * Examples:
 *   task_readArduIO_IO(IO_1);
 *   if (io1ins.GP101) writeString_P("IO_1:P01 = High");
 *   else writeString_P("IO_1:P01 = Low");
 *   task_readArduIO_IO2();
 *   if (!io2ins.GP214) writeString_P("IO_2:P14 = Low");
 *
 */
void task_readArduIO_IO(uint8_t io)
{
	switch (io) {								// IO-Expander number:
		case IO_1 :								//  IO_1
			I2CTWI_transmitByte(I2C_ARDUIO_IO_1_ADR, PCA9535_INPUT_P0);
			I2CTWI_readBytes(I2C_ARDUIO_IO_1_ADR, registerBuf, 2);
			io1ins.word = registerBuf[0];
			io1ins.word |= (registerBuf[1] << 8);
			break;
		case IO_2 :								//  IO_2
			I2CTWI_transmitByte(I2C_ARDUIO_IO_2_ADR, PCA9535_INPUT_P0);
			I2CTWI_readBytes(I2C_ARDUIO_IO_2_ADR, registerBuf, 2);
			io2ins.word = registerBuf[0];
			io2ins.word |= (registerBuf[1] << 8);
			break;
		case IO_3 :								//  IO_3
			I2CTWI_transmitByte(I2C_ARDUIO_IO_3_ADR, PCA9535_INPUT_P0);
			I2CTWI_readBytes(I2C_ARDUIO_IO_3_ADR, registerBuf, 2);
			io3ins.word = registerBuf[0];
			io3ins.word |= (registerBuf[1] << 8);
	}
}

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

interrupt_RP6ArduIOstatus_t interrupt_RP6ArduIOstatus, newstatus;
uint8_t interrupt_rp6arduiostatus_changed;

/** 
 * This function checks all interrupt pins on
 * the XBUS (INT1..3, INTU).
 * This function (task) must be called VERY
 * frequently out of the main loop.
 * Bigger delays result in slower reaction to
 * interrupt requests of the RP6 ArduIO Board.
 * Interrupt function table:
 *   Int. : Function        IRQ
 *   ---------------------------
 *   INT1 : PCA9535 (2) INT  L
 *   INT2 : PCA9535 (1) INT  L
 *   INT3 : PCA9535 (3) INT  L
 *   INTU : not used
 * You can see in the "IRQ" column, which level
 * (H/L) means an ACTIVE INTERRUPT signal.
 * The interrupt pin levels (H=true/L=false) are
 * read into the global interrupt_RP6ArduIOstatus
 * variable.
 * The variable interrupt_rp6arduiostatus_changed
 * will be TRUE, if the RP6ArduIO interrupt status
 * has changed since the last call of this task,
 * else it will be FALSE.
 * There is also a macro int_status_changed(),
 * that may be used instead of the variable
 * interrupt_rp6arduiostatus_changed.
 *
 * Hints: - This function checks the interrupt
 *          signals by polling. This is NOT the
 *          best way to to this job. You will
 *          have to write your own task, if you
 *          want to use the interrupt function of
 *          the ATmega32/2560 microcontroller.
 *        - Every interrupt signal of the ArduIO
 *          Board may be cut off from the XBUS
 *          by opening a jumper (JP_INT3V3):
 *          INT1 -> Pins 1-2 (PCA9535 (2) INT)
 *          INT2 -> Pins 5-6 (PCA9535 (1) INT)
 *          INT3 -> Pins 3-4 (PCA9535 (3) INT)
 *
 * Example:
 *   task_checkArduIO_INTs();
 *   if (interrupt_rp6arduiostatus_changed)
 *        writeString_P("RP6ArduIO INT state changed!!!\n");
 *   if (!interrupt_RP6ArduIOstatus.ioexp_1)
 *        writeString_P("==> PCA9535 (1) INT (XBUS INT2)!!!\n");
 *
 */
void task_checkArduIO_INTs(void)
{
	if(IO_ARDUIO_INT1_PIN & IO_ARDUIO_INT1_IN)	// XBUS INT1
		newstatus.int1 = true;
	else
		newstatus.int1 = false;
#ifdef IO_ARDUIO_INT2_IN
	if(IO_ARDUIO_INT2_PIN & IO_ARDUIO_INT2_IN)	// XBUS INT2
		newstatus.int2 = true;
	else
		newstatus.int2 = false;
#endif
#ifdef IO_ARDUIO_INT3_IN
	if(IO_ARDUIO_INT3_PIN & IO_ARDUIO_INT3_IN)	// XBUS INT3
		newstatus.int3 = true;
	else
		newstatus.int3 = false;
#endif
//#ifdef IO_ARDUIO_INTU_IN
//	if(IO_ARDUIO_INTU_PIN & IO_ARDUIO_INTU_IN)	// XBUS INTU
//		newstatus.intu = true;
//	else
//		newstatus.intu = false;
//#endif
	if (newstatus.byte != interrupt_RP6ArduIOstatus.byte) {
		interrupt_rp6arduiostatus_changed = true;
		interrupt_RP6ArduIOstatus.byte = newstatus.byte;
	}
	else interrupt_rp6arduiostatus_changed = false;
}

/*****************************************************************************/
// I2C A/D and D/A Converter (PCF8591):

addaexp_1_t ad1ins;
addaexp_2_t ad2ins;
addaexp_3_t ad3ins;

/**
 * This function reads the 3 ADDA_x ADC ports
 * (AIN0..AIN3), where x = AD/DA-Expander number
 * = [1..3]!
 * You may call this function (task) frequently
 * out of the main loop.
 * The AIN0..AIN3 ADC values [0..255] are read
 * into the global adxins struct:
 *   uint8_t adxins.ADxy, where y = ADC channel
 *   (AIN0..3) number of ADDA_x = [0..3]
 *
 * Input: ad  -> AD/DA-Expander number [1..3]
 *
 * There is also a macro task_readArduIO_ADx(),
 * which does exactly the same as this function,
 * where x = AD/DA-Expander number = [1..3].
 * The macro task_readAllArduIO_ADs() reads the
 * ADC ports (AIN0..AIN3) of ALL 3 AD/DA-
 * Expanders.
 *
 * Hint only for ad == 1 (ADDA_1):
 *       If READ_ADCUB is defined, the variable
 *       adcub is filled with the UB voltage ADC
 *       value. Depending on adcub the UB voltage
 *       low flag is SET/CLEARED in the ArduIO
 *       status byte (RP6ArduIOstatus.ubatLow)!
 *       There is also a macro isUbLow(), that
 *       may be used instead of
 *       RP6ArduIOstatus.ubatLow.
 *
 * Examples:
 *   task_readArduIO_AD(ADDA_1);
 *   writeString_P("\nADDA_1:AIN0 = ");
 *   writeInteger(ad1ins.AD10, DEC);
 *   writeString_P("\n");
 *
 *   task_readArduIO_AD2();
 *   writeString_P("\nADDA_2:AIN3 = ");
 *   writeInteger(ad2ins.AD23, DEC);
 *   writeString_P(" (U: ");
 *   writeInteger(UCV_AD(ad2ins.AD23), DEC);
 *   writeString_P("cV)\n"); // 100cV = 1V
 *
 */
void task_readArduIO_AD(uint8_t ad)
{
	switch (ad) {								// AD/DA-Expander number:
		case ADDA_1 :							//  ADDA_1
			I2CTWI_transmitByte(I2C_ARDUIO_AD_1_ADR, PCF8591_CONTROL_ARDUIO);
			I2CTWI_readBytes(I2C_ARDUIO_AD_1_ADR, registerBuf, 5);
			ad1ins.AD10 = registerBuf[1];
			ad1ins.AD11 = registerBuf[2];
			ad1ins.AD12 = registerBuf[3];
			ad1ins.AD13 = registerBuf[4];
#ifdef READ_ADCUB
			adcub = ad1ins.ArduIO_UB;			// = ad1ins.AD13
			// Test for UB voltage low condition:
			if (adcub < ADCVAL_UB_LOW) RP6ArduIOstatus_LIB.ubatLow = true;
			else RP6ArduIOstatus_LIB.ubatLow = false;
			RP6ArduIOstatus.byte = RP6ArduIOstatus_LIB.byte;
#endif
			break;
		case ADDA_2 :							//  ADDA_2
			I2CTWI_transmitByte(I2C_ARDUIO_AD_2_ADR, PCF8591_CONTROL_ARDUIO);
			I2CTWI_readBytes(I2C_ARDUIO_AD_2_ADR, registerBuf, 5);
			ad2ins.AD20 = registerBuf[1];
			ad2ins.AD21 = registerBuf[2];
			ad2ins.AD22 = registerBuf[3];
			ad2ins.AD23 = registerBuf[4];
			break;
		case ADDA_3 :							//  ADDA_3
			I2CTWI_transmitByte(I2C_ARDUIO_AD_3_ADR, PCF8591_CONTROL_ARDUIO);
			I2CTWI_readBytes(I2C_ARDUIO_AD_3_ADR, registerBuf, 5);
			ad3ins.AD30 = registerBuf[1];
			ad3ins.AD31 = registerBuf[2];
			ad3ins.AD32 = registerBuf[3];
			ad3ins.AD33 = registerBuf[4];
	}
}

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

uint8_t da1aout = 0;
uint8_t da2aout = 0;
uint8_t da3aout = 0;

/**
 * This function sends an 8 bit value (aout) to
 * one of the three DA converters on the ArduIO
 * Board. After this the analog voltage [0..5V]
 * can be measured at the DAC output pin (AOUT)
 * of the addressed AD/DA-Expander.
 * The value aout is also stored in daxaout.
 *
 * Input: da   -> AD/DA-Expander number [1..3]
 *        aout -> Output value (8 bit)
 *
 * There is also a macro writeArduIO_DAx(aout),
 * which does exactly the same as this function,
 * where x = AD/DA-Expander number = [1..3].
 *
 * Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 *       ! THE ACCESS IS ENABLED (default): !
 *       !   ==> enableDAs(); <==           !
 *
 * Example:
 *   writeArduIO_DA1(127);   // Or writeArduIO_DA(1,127);
 *   // this sends the value 127 to the DAC of
 *   // AD/DA-Expander 1. This DAC now generates
 *   // an output voltage (Vo) of 2.5V:
 *   //   Vo [V] = aout * 5 / 255
 *   // ... or 250cV (1cV = one-hundreth of 1V):
 *   //   Vo [cV] = aout * 500 / 255
 *   writeArduIO_DA1(AOUT_CV(250)); // 250cV = 2.5V
 *   // does exactly the same!
 *
 */
void writeArduIO_DA(uint8_t da, uint8_t aout)
{
	if (RP6ArduIOstatus_LIB.dasEnable) {
		switch (da) {							// AD/DA-Expander number:
			case ADDA_1 :						//  ADDA_1
				I2CTWI_transmit2Bytes(I2C_ARDUIO_AD_1_ADR, PCF8591_CONTROL_DAC_ENABLE, aout);
				da1aout = aout;
				break;
			case ADDA_2 :						//  ADDA_2
				I2CTWI_transmit2Bytes(I2C_ARDUIO_AD_2_ADR, PCF8591_CONTROL_DAC_ENABLE, aout);
				da2aout = aout;
				break;
			case ADDA_3 :						//  ADDA_3
				I2CTWI_transmit2Bytes(I2C_ARDUIO_AD_3_ADR, PCF8591_CONTROL_DAC_ENABLE, aout);
				da3aout = aout;
		}
	}
}

/**
 * This function disables the DAC output (AOUT)
 * of the addressed AD/DA-Expander (set PCF8591
 * default mode).
 *
 * Input: da  -> AD/DA-Expander number [1..3]
 *
 * There is also a macro disableArduIO_DAx(),
 * which does exactly the same as this function,
 * where x = AD/DA-Expander number = [1..3].
 * The macro disableAllArduIO_DAs() disables the
 * DAC outputs (AOUT) of ALL 3 AD/DA-Expanders.
 *
 * Hints: - The function task_readArduIO_AD(ad)
 *          ENABLES the DAC output (AOUT) of the
 *          addressed AD/DA-Expander!
 *        - Access to the 3 DACs is NOT disabled
 *          by this function! Pls. use function
 *          disableDAs() for this!
 *
 */
void disableArduIO_DA(uint8_t da)
{
	switch (da) {								// AD/DA-Expander number:
		case ADDA_1 :							//  ADDA_1
			I2CTWI_transmitByte(I2C_ARDUIO_AD_1_ADR, PCF8591_CONTROL_DEFAULT);
			break;
		case ADDA_2 :							//  ADDA_2
			I2CTWI_transmitByte(I2C_ARDUIO_AD_2_ADR, PCF8591_CONTROL_DEFAULT);
			break;
		case ADDA_3 :							//  ADDA_3
			I2CTWI_transmitByte(I2C_ARDUIO_AD_3_ADR, PCF8591_CONTROL_DEFAULT);
	}
}

/*****************************************************************************/
// UB Voltage Sensor:

uint8_t adcub;							// UB voltage sensor ADC value

/**
 * This function reads and returns the ADC value of
 * the UB voltage sensor. The value is also stored
 * in adcub. Depending on adcub the UB voltage low
 * flag is SET/CLEARED in the ArduIO status byte
 * (RP6ArduIOstatus.ubatLow)!
 * There is also a macro isUbLow(), that may be
 * used instead of RP6ArduIOstatus.ubatLow.
 *
 * Hint: Jumper JP_AD-UB must be closed in order to
 *       measure the UB voltage!
 *
 */
uint8_t getUbSensor(void)
{
	task_readArduIO_AD1();
	adcub = ad1ins.ArduIO_UB;					// ADDA_1:AIN3
	// Test for UB voltage low condition:
	if (adcub < ADCVAL_UB_LOW) RP6ArduIOstatus_LIB.ubatLow = true;
	else RP6ArduIOstatus_LIB.ubatLow = false;
	RP6ArduIOstatus.byte = RP6ArduIOstatus_LIB.byte;
	return adcub;
}

double ubv;								// UB voltage [V]

/**
 * Calculates and returns the UB voltage value
 * by using the data read from the UB voltage
 * sensor with the function getUbSensor().
 *
 * Hint: The calculation assumes a reference
 *       voltage of 5.0V and a voltage divider
 *       100k/100k at the sensor input!
 *
 */
double calculateUb(void)
{
	return (10.0f / 255.0f * adcub);
}

/**
 * Measures and returns the UB voltage value [V].
 * The ADC value of the UB voltage sensor is also
 * stored in adcub. Depending on adcub the UB
 * voltage low flag is SET/CLEARED in the ArduIO
 * status byte (RP6ArduIOstatus.ubatLow)!
 * There is also a macro isUbLow(), that may be
 * used instead of RP6ArduIOstatus.ubatLow.
 *
 * Hints: - Jumper JP_AD-UB must be closed in
 *          order to measure the UB voltage!
 *        - The calculation assumes a reference
 *          voltage of 5.0V and a voltage
 *          divider 100k/100k at the sensor
 *          input!
 *
 */
double measureUb(void)
{
	task_readArduIO_AD1();
	adcub = ad1ins.ArduIO_UB;					// ADDA_1:AIN3
	// Test for UB voltage low condition:
	if (adcub < ADCVAL_UB_LOW) RP6ArduIOstatus_LIB.ubatLow = true;
	else RP6ArduIOstatus_LIB.ubatLow = false;
	RP6ArduIOstatus.byte = RP6ArduIOstatus_LIB.byte;
	return (10.0f / 255.0f * adcub);
}

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

/** 
 * Set the 4 status LEDs of the ArduIO.
 *
 * Example:
 *          setArduIOLEDs(0b1010);
 *          // this CLEARs LEDs 1 and 3
 *          // and SETs LEDs 2 and 4!
 *
 */
void setArduIOLEDs(uint8_t leds)
{
	if (leds & 0b00000001) PCA9685_ARD_set(ARD_CHLED1, 4095);
	else PCA9685_ARD_set(ARD_CHLED1, 0);
	if (leds & 0b00000010) PCA9685_ARD_set(ARD_CHLED2, 4095);
	else PCA9685_ARD_set(ARD_CHLED2, 0);
	if (leds & 0b00000100) PCA9685_ARD_set(ARD_CHLED3, 4095);
	else PCA9685_ARD_set(ARD_CHLED3, 0);
	if (leds & 0b00001000) PCA9685_ARD_set(ARD_CHLED4, 4095);
	else PCA9685_ARD_set(ARD_CHLED4, 0);
}

/** 
 * Dim the 4 status LEDs of the ArduIO.
 *
 * Input: led  -> LED number [1..4]
 *        duty -> Duty cycle [0..4095] = [0..100%]
 *
 * There is also a macro dimArduIOLEDx(duty),
 * which does exactly the same as this function,
 * where x = LED number = [1..4].
 *
 * Example:
 *   dimArduIOLED2(DUTY_50);   // Or dimArduIOLED(2,2047);
 *   // this dims LED2 with a
 *   // duty cycle of 50%!
 *   dimArduIOLED2(DUTY_PCT(50));   // Or dimArduIOLED2(2047);
 *   // does exactly the same!
 *
 */
void dimArduIOLED(uint8_t led, uint16_t duty)
{
	if (led == 1) PCA9685_ARD_set(ARD_CHLED1, duty);
	if (led == 2) PCA9685_ARD_set(ARD_CHLED2, duty);
	if (led == 3) PCA9685_ARD_set(ARD_CHLED3, duty);
	if (led == 4) PCA9685_ARD_set(ARD_CHLED4, duty);
}

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

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

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

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

/*****************************************************************************/
// PWM Ports:

/** 
 * Set the 4 free PWM ports of the ArduIO to ON or
 * OFF (set the MAX/MIN [100%/0%] PWM duty cycle).
 *
 * Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 *       ! THE ACCESS IS ENABLED (default): !
 *       !   ==> enablePWMs(); <==          !
 *
 * Example:
 *          setArduIOPWMs(0b1010);
 *          // this CLEARs PWMs 1 and 3 [0%]
 *          // and SETs PWMs 2 and 4 [100%]!
 *
 */
void setArduIOPWMs(uint8_t pwms)
{
	if (RP6ArduIOstatus_LIB.pwmsEnable) {
		if (pwms & 0b00000001) PCA9685_ARD_set(CHPWM1, 4095);
		else PCA9685_ARD_set(CHPWM1, 0);
		if (pwms & 0b00000010) PCA9685_ARD_set(CHPWM2, 4095);
		else PCA9685_ARD_set(CHPWM2, 0);
		if (pwms & 0b00000100) PCA9685_ARD_set(CHPWM3, 4095);
		else PCA9685_ARD_set(CHPWM3, 0);
		if (pwms & 0b00001000) PCA9685_ARD_set(CHPWM4, 4095);
		else PCA9685_ARD_set(CHPWM4, 0);
	}
}

/** 
 * Dim the 4 free PWM ports of the ArduIO (set the
 * PWM duty cycle).
 *
 * Input: pwm  -> PWM number [1..4]
 *        duty -> Duty cycle [0..4095] = [0..100%]
 *
 * There is also a macro dimArduIOPWMx(duty),
 * which does exactly the same as this function,
 * where x = PWM number = [1..4].
 *
 * Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 *       ! THE ACCESS IS ENABLED (default): !
 *       !   ==> enablePWMs(); <==          !
 *
 * Example:
 *   dimArduIOPWM2(DUTY_50);   // Or dimArduIOPWM(2,2047);
 *   // this dims PWM2 with a
 *   // PWM duty cycle of 50%!
 *   dimArduIOPWM2(DUTY_PCT(50));   // Or dimArduIOPWM2(2047);
 *   // does exactly the same!
 *
 */
void dimArduIOPWM(uint8_t pwm, uint16_t duty)
{
	if (RP6ArduIOstatus_LIB.pwmsEnable) {
		if (pwm == 1) PCA9685_ARD_set(CHPWM1, duty);
		if (pwm == 2) PCA9685_ARD_set(CHPWM2, duty);
		if (pwm == 3) PCA9685_ARD_set(CHPWM3, duty);
		if (pwm == 4) PCA9685_ARD_set(CHPWM4, duty);
	}
}

/** 
 * Set ONLY PWM1, don't change anything for the other PWMs.
 *
 * Input: pwm -> 0 (false) = PWM off [0%]
 *               >0 (true) = PWM max. duty cycle [100%]
 *
 * Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 *       ! THE ACCESS IS ENABLED (default): !
 *       !   ==> enablePWMs(); <==          !
 *
 */
void setArduIOPWM1(uint8_t pwm)
{
	if (RP6ArduIOstatus_LIB.pwmsEnable) {
		if (pwm > 0) PCA9685_ARD_set(CHPWM1, 4095); 
		else PCA9685_ARD_set(CHPWM1, 0);
	}
}	

/** 
 * Set ONLY PWM2, don't change anything for the other PWMs.
 */
void setArduIOPWM2(uint8_t pwm)
{
	if (RP6ArduIOstatus_LIB.pwmsEnable) {
		if (pwm > 0) PCA9685_ARD_set(CHPWM2, 4095); 
		else PCA9685_ARD_set(CHPWM2, 0);
	}	
}	

/** 
 * Set ONLY PWM3, don't change anything for the other PWMs.
 */
void setArduIOPWM3(uint8_t pwm)
{
	if (RP6ArduIOstatus_LIB.pwmsEnable) {
		if (pwm > 0) PCA9685_ARD_set(CHPWM3, 4095); 
		else PCA9685_ARD_set(CHPWM3, 0);	
	}
}	

/** 
 * Set ONLY PWM4, don't change anything for the other PWMs.
 */
void setArduIOPWM4(uint8_t pwm)
{
	if (RP6ArduIOstatus_LIB.pwmsEnable) {
		if (pwm > 0) PCA9685_ARD_set(CHPWM4, 4095); 
		else PCA9685_ARD_set(CHPWM4, 0);	
	}
}

/*****************************************************************************/
// Power PWM Ports & H-Bridges:

// Power PWM Ports:
/** 
 * Set the 8 power PWM ports of the ArduIO to be
 * used as 8 SINGLE power PWM ports and switch
 * all 8 power PWM ports off (0% PWM duty cycle).
 *
 * Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 *       ! THE ACCESS IS ENABLED (default): !
 *       !   ==> enablePPWM_G(1); <==       !
 *       !   ==> enablePPWM_G(2); <==       !
 *
 */
void setArduIOPowerPWMMode(void)
{
	if (RP6ArduIOstatus_LIB.ppwm_g1Enable) {
		I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED0_ON_H, 0);
		PCA9685_ARD_set(CHPOWERPWM1_P, 0);
		I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED1_ON_H, 0);
		PCA9685_ARD_set(CHPOWERPWM2_N, 4095);
		I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED2_ON_H, 0);
		PCA9685_ARD_set(CHPOWERPWM3_P, 0);
		I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED3_ON_H, 0);
		PCA9685_ARD_set(CHPOWERPWM4_N, 4095);
	}
	if (RP6ArduIOstatus_LIB.ppwm_g2Enable) {
		I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED4_ON_H, 0);
		PCA9685_ARD_set(CHPOWERPWM5_P, 0);
		I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED5_ON_H, 0);
		PCA9685_ARD_set(CHPOWERPWM6_N, 4095);
		I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED6_ON_H, 0);
		PCA9685_ARD_set(CHPOWERPWM7_P, 0);
		I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED7_ON_H, 0);
		PCA9685_ARD_set(CHPOWERPWM8_N, 4095);
	}
}

/** 
 * Set the 8 power PWM ports of the ArduIO to ON or
 * OFF (set the MAX/MIN [100%/0%] PWM duty cycle).
 *
 * Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 *       ! THE ACCESS IS ENABLED (default): !
 *       !   ==> enablePPWM_G(1); <==       !
 *       !   ==> enablePPWM_G(2); <==       !
 *
 * Example:
 *          setArduIOPowerPWMs(0b00001010);
 *          // this CLEARs power PWMs 1, 3, 5..8 [0%]
 *          // and SETs power PWMs 2 and 4 [100%]!
 *
 */
void setArduIOPowerPWMs(uint8_t ppwms)
{
	if (RP6ArduIOstatus_LIB.ppwm_g1Enable) {
		if (ppwms & 0b00000001) PCA9685_ARD_set(CHPOWERPWM1_P, 4095);
		else PCA9685_ARD_set(CHPOWERPWM1_P, 0);
		if (ppwms & 0b00000010) PCA9685_ARD_set(CHPOWERPWM2_N, 0);
		else PCA9685_ARD_set(CHPOWERPWM2_N, 4095);
		if (ppwms & 0b00000100) PCA9685_ARD_set(CHPOWERPWM3_P, 4095);
		else PCA9685_ARD_set(CHPOWERPWM3_P, 0);
		if (ppwms & 0b00001000) PCA9685_ARD_set(CHPOWERPWM4_N, 0);
		else PCA9685_ARD_set(CHPOWERPWM4_N, 4095);
	}
	if (RP6ArduIOstatus_LIB.ppwm_g2Enable) {
		if (ppwms & 0b00010000) PCA9685_ARD_set(CHPOWERPWM5_P, 4095);
		else PCA9685_ARD_set(CHPOWERPWM5_P, 0);
		if (ppwms & 0b00100000) PCA9685_ARD_set(CHPOWERPWM6_N, 0);
		else PCA9685_ARD_set(CHPOWERPWM6_N, 4095);
		if (ppwms & 0b01000000) PCA9685_ARD_set(CHPOWERPWM7_P, 4095);
		else PCA9685_ARD_set(CHPOWERPWM7_P, 0);
		if (ppwms & 0b10000000) PCA9685_ARD_set(CHPOWERPWM8_N, 0);
		else PCA9685_ARD_set(CHPOWERPWM8_N, 4095);
	}
}

/** 
 * Dim the 8 power PWM ports of the ArduIO (set the
 * PWM duty cycle).
 *
 * Input: ppwm -> Power PWM number [1..8]
 *        duty -> Duty cycle [0..4095] = [0..100%]
 *
 * There is also a macro dimArduIOPowerPWMx(duty),
 * which does exactly the same as this function,
 * where x = Power PWM number = [1..8].
 *
 * Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 *       ! THE ACCESS IS ENABLED (default): !
 *       !   ==> enablePPWM_G(1); <==       !
 *       !   ==> enablePPWM_G(2); <==       !
 *
 * Example:
 *   dimArduIOPowerPWM2(DUTY_50);   // Or dimArduIOPowerPWM(2,2047);
 *   // this dims power PWM2 with a
 *   // duty cycle of 50%!
 *   dimArduIOPowerPWM2(DUTY_PCT(50));   // Or dimArduIOPowerPWM2(2047);
 *   // does exactly the same!
 *
 */
void dimArduIOPowerPWM(uint8_t ppwm, uint16_t duty)
{
	if (RP6ArduIOstatus_LIB.ppwm_g1Enable) {
		if (ppwm == 1) PCA9685_ARD_set(CHPOWERPWM1_P, duty);
		if (ppwm == 2) PCA9685_ARD_set(CHPOWERPWM2_N, (4095 - duty));
		if (ppwm == 3) PCA9685_ARD_set(CHPOWERPWM3_P, duty);
		if (ppwm == 4) PCA9685_ARD_set(CHPOWERPWM4_N, (4095 - duty));
	}
	if (RP6ArduIOstatus_LIB.ppwm_g2Enable) {
		if (ppwm == 5) PCA9685_ARD_set(CHPOWERPWM5_P, duty);
		if (ppwm == 6) PCA9685_ARD_set(CHPOWERPWM6_N, (4095 - duty));
		if (ppwm == 7) PCA9685_ARD_set(CHPOWERPWM7_P, duty);
		if (ppwm == 8) PCA9685_ARD_set(CHPOWERPWM8_N, (4095 - duty));
	}
}

/** 
 * Set ONLY power PWM1, don't change anything for
 * the other power PWMs.
 *
 * Input: ppwm -> 0 (false) = Power PWM off [0%]
 *                >0 (true) = Power PWM max. duty cycle [100%]
 *
 * Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 *       ! THE ACCESS IS ENABLED (default): !
 *       !   ==> enablePPWM_G(1); <==       !
 *
 */
void setArduIOPowerPWM1(uint8_t ppwm)
{
	if (RP6ArduIOstatus_LIB.ppwm_g1Enable) {
		if (ppwm > 0) PCA9685_ARD_set(CHPOWERPWM1_P, 4095); 
		else PCA9685_ARD_set(CHPOWERPWM1_P, 0);
	}
}	

/** 
 * Set ONLY power PWM2, don't change anything for
 * the other power PWMs.
 */
void setArduIOPowerPWM2(uint8_t ppwm)
{
	if (RP6ArduIOstatus_LIB.ppwm_g1Enable) {
		if (ppwm > 0) PCA9685_ARD_set(CHPOWERPWM2_N, 0); 
		else PCA9685_ARD_set(CHPOWERPWM2_N, 4095);
	}
}	

/** 
 * Set ONLY power PWM3, don't change anything for
 * the other power PWMs.
 */
void setArduIOPowerPWM3(uint8_t ppwm)
{
	if (RP6ArduIOstatus_LIB.ppwm_g1Enable) {
		if (ppwm > 0) PCA9685_ARD_set(CHPOWERPWM3_P, 4095); 
		else PCA9685_ARD_set(CHPOWERPWM3_P, 0);
	}
}	

/** 
 * Set ONLY power PWM4, don't change anything for
 * the other power PWMs.
 */
void setArduIOPowerPWM4(uint8_t ppwm)
{
	if (RP6ArduIOstatus_LIB.ppwm_g1Enable) {
		if (ppwm > 0) PCA9685_ARD_set(CHPOWERPWM4_N, 0); 
		else PCA9685_ARD_set(CHPOWERPWM4_N, 4095);
	}
}

/** 
 * Set ONLY power PWM5, don't change anything for
 * the other power PWMs.
 *
 * Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 *       ! THE ACCESS IS ENABLED (default): !
 *       !   ==> enablePPWM_G(2); <==       !
 *
 */
void setArduIOPowerPWM5(uint8_t ppwm)
{
	if (RP6ArduIOstatus_LIB.ppwm_g2Enable) {
		if (ppwm > 0) PCA9685_ARD_set(CHPOWERPWM5_P, 4095); 
		else PCA9685_ARD_set(CHPOWERPWM5_P, 0);
	}
}	

/** 
 * Set ONLY power PWM6, don't change anything for
 * the other power PWMs.
 */
void setArduIOPowerPWM6(uint8_t ppwm)
{
	if (RP6ArduIOstatus_LIB.ppwm_g2Enable) {
		if (ppwm > 0) PCA9685_ARD_set(CHPOWERPWM6_N, 0); 
		else PCA9685_ARD_set(CHPOWERPWM6_N, 4095);
	}
}	

/** 
 * Set ONLY power PWM7, don't change anything for
 * the other power PWMs.
 */
void setArduIOPowerPWM7(uint8_t ppwm)
{
	if (RP6ArduIOstatus_LIB.ppwm_g2Enable) {
		if (ppwm > 0) PCA9685_ARD_set(CHPOWERPWM7_P, 4095); 
		else PCA9685_ARD_set(CHPOWERPWM7_P, 0);
	}
}	

/** 
 * Set ONLY power PWM8, don't change anything for
 * the other power PWMs.
 */
void setArduIOPowerPWM8(uint8_t ppwm)
{
	if (RP6ArduIOstatus_LIB.ppwm_g2Enable) {
		if (ppwm > 0) PCA9685_ARD_set(CHPOWERPWM8_N, 0); 
		else PCA9685_ARD_set(CHPOWERPWM8_N, 4095);
	}
}

// H-Bridges:

uint8_t last_hb, last_dir;

/** 
 * Adjust all functions of the two H-Bridges.
 *
 * Input: hb   -> H-Bridge (HB) number [1 or 2]
 *        dir  -> Direction [0, 1, 4, 5]
 *        duty -> Duty cycle [0..4095] = [0..100%]
 * 
 * There are also 6 macros for each HB:
 *   powerHBx(dir,duty);
 *   powerHBxSTOP();
 *   powerHBxFWD(duty);
 *   powerHBxBWD(duty);
 *   powerHBxBRK();
 *   powerHBxOFF();
 * which do exactly the same as this function,
 * where x = H-Bridge number = [1 or 2].
 *
 * Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 *       ! THE ACCESS IS ENABLED:           !
 *       !   ==> enableHB(1); <==           !
 *       !   ==> enableHB(2); <==           !
 *
 * Examples:
 *   powerHB1(BWD,DUTY_50);   // Or adjustArduIOPowerHB(1,1,2047);
 *   // this moves a motor at HB1 backward with
 *   // a duty cycle of 50%!
 *   powerHB1BWD(DUTY_PCT(50));
 *   // does exactly the same!
 *
 *   powerHB2STOP();   // Or powerHB2(FWD,DUTY_0);
 *   // this stops a motor at HB2 (duty cycle: 0%)
 *   // and sets direction FWD!
 *   // If you don't want direction FWD to be set,
 *   // you have to use: powerHB2(BWD,DUTY_0)!
 *
 *   powerHB1BRK();
 *   // this stops a motor at HB1 faster than the
 *   // function powerHB1STOP() by shorting it!
 *
 *   powerHB2OFF();
 *   // this stops a motor at HB2 by cutting off
 *   // all four HB2 motor driver MOSFets!
 *
 */
void adjustArduIOPowerHB(uint8_t hb, uint8_t dir, uint16_t duty)
{
	uint8_t newcall = 1;
	if ((RP6ArduIOstatus_LIB.hb1Enable) || (RP6ArduIOstatus_LIB.hb2Enable)) {
		if ((hb == last_hb) && (dir == last_dir))
			newcall = 0;
		else {
			newcall = 1;
			last_hb = hb;						// Store last H-Bridge number
			last_dir = dir;						// Store last direction
		}
	}
												// H-Bridge 1
	if ((hb == 1) && (RP6ArduIOstatus_LIB.hb1Enable)) {
		switch (dir) {							//  Direction:
			case FWD :							//   Forwards
				if (newcall) {
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED1_OFF_H, 0);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED1_ON_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED2_OFF_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED0_OFF_H, 0);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED0_ON_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED3_ON_H, 0);
				}
				PCA9685_ARD_set(CHHB1_N2, (4095 - duty));
				break;
			case BWD :							//   Backwards
				if (newcall) {
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED0_OFF_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED3_OFF_H, 0);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED3_ON_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED2_OFF_H, 0);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED2_ON_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED1_ON_H, 0);
				}
				PCA9685_ARD_set(CHHB1_N1, (4095 - duty));
				break;
			case BRK :							//   Speed break
				if (newcall) {
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED0_OFF_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED2_OFF_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED1_OFF_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED3_OFF_H, 0x10);
				}
				break;
			case OFF :							//   Power OFF
				if (newcall) {
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED0_OFF_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED2_OFF_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED1_OFF_H, 0);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED1_ON_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED3_OFF_H, 0);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED3_ON_H, 0x10);
				}
		}
	}
												// H-Bridge 2
	else if ((hb == 2) && (RP6ArduIOstatus_LIB.hb2Enable)) {
		switch (dir) {							//  Direction:
			case FWD :							//   Forwards
				if (newcall) {
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED5_OFF_H, 0);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED5_ON_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED6_OFF_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED4_OFF_H, 0);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED4_ON_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED7_ON_H, 0);
				}
				PCA9685_ARD_set(CHHB2_N2, (4095 - duty));
				break;
			case BWD :							//   Backwards
				if (newcall) {
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED4_OFF_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED7_OFF_H, 0);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED7_ON_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED6_OFF_H, 0);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED6_ON_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED5_ON_H, 0);
				}
				PCA9685_ARD_set(CHHB2_N1, (4095 - duty));
				break;
			case BRK :							//   Speed break
				if (newcall) {
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED4_OFF_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED6_OFF_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED5_OFF_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED7_OFF_H, 0x10);
				}
				break;
			case OFF :							//   Power OFF
				if (newcall) {
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED4_OFF_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED6_OFF_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED5_OFF_H, 0);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED5_ON_H, 0x10);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED7_OFF_H, 0);
					I2CTWI_transmit2Bytes(I2C_ARDUIO_PWM_ADR, PCA9685_LED7_ON_H, 0x10);
				}
		}
	}
}

/*****************************************************************************/
/*****************************************************************************/
/*****************************************************************************/
// ArduIO Board system control routine:

/**
 * Call all important ArduIO Board system tasks.
 * This task will read:
 *  - All ArduIO Board digital portpins
 *    Result: io1ins.GP100..io1ins.GP117
 *            io2ins.GP200..io2ins.GP217
 *            io3ins.GP300..io3ins.GP317
 *  - All PCA9535 (1..3) INTs (XBUS INT2, 1, 3)
 *    Result: interrupt_RP6ArduIOstatus.ioexp_1
 *            interrupt_RP6ArduIOstatus.ioexp_2
 *            interrupt_RP6ArduIOstatus.ioexp_3
 *  - All ArduIO Board analog portpins
 *    Result: ad1ins.AD10..ad1ins.AD13
 *            ad2ins.AD20..ad2ins.AD23
 *            ad3ins.AD30..ad3ins.AD33
 * The variable interrupt_rp6arduiostatus_changed
 * will be TRUE, if the RP6ArduIO interrupt status
 * has changed since the last call of this task
 * (or task_checkArduIO_INTs), else it will be
 * FALSE.
 * There is also a macro int_status_changed(),
 * that may be used instead of the variable
 * interrupt_rp6arduiostatus_changed.
 *
 * Hints: - Do NOT use task_Arduino_Uno_Exp()
 *          together with THIS task!
 *        - You should only use this task, if you
 *          have to read ALL ArduIO Board input
 *          portpins!
 *        - Digital portpins can be read, if they
 *          were configured as INPUTs before:
 *          configArduIO_IO1(0b1111111111111111);
 *          configArduIO_IO2(0b1111111111111111);
 *          configArduIO_IO3(0b1111111111111111);
 *        - Digital portpin input values can be
 *          inverted with the function
 *          invertArduIO_IO(io,invrt)!
 *        - PCA9535 INTs can only be read, if the
 *          corresponding jumper (JP_INT3V3) is
 *          CLOSED:
 *          INT1 -> Pins 1-2 (PCA9535 (2) INT)
 *          INT2 -> Pins 5-6 (PCA9535 (1) INT)
 *          INT3 -> Pins 3-4 (PCA9535 (3) INT)
 *        - XBUS INT2 and INT3 are NOT available
 *          with RP6v2 Base!!!
 *
 */
void task_RP6_ArduIOSystem(void)
{
	task_readAllArduIO_IOs();
	task_checkArduIO_INTs();
	task_readAllArduIO_ADs();
}

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


/*****************************************************************************/
/*****************************************************************************/
// ArduIO Board initialisation and shutdown:

/**
 * You MUST call this function ONCE at the
 * beginning of a main program, that uses the
 * ArduIO Board.
 * DEFAULT initialisation settings are:
 * - Default access to ArduIO functions enable
 * - Default PWM frequency
 * - Power PWM mode enable
 * - H-Bridge mode disable
 * - All 8 power PWMs off
 * - All 4 free PWMs off
 * - All 4 LEDs off
 *
 * Hints: - After power on the 48 ArduIO IOs are
 *          configured as INPUTs (PCA9535
 *          default!). This function does NOT
 *          configurate the IOs!
 *        - After power on the 3 ArduIO DACs are
 *          disabled (PCF8591 default!). This
 *          function does NOT affect the state or
 *          the output voltage of the DACs!
 *
 */
void arduio_init(void)
{
	// ArduIO Status (DEFAULT):
	setArduIODefaultStatus();					// ArduIO access default status
	// PWM Controller:
	PCA9685_ARD_init(PWM_FREQUENCY);			// Init PWM default frequency
	// Power PWM Ports & H-Bridges:
	setArduIOPowerPWMMode();					// ArduIO 8 power PWMs off
	// PWMs:
	setArduIOPWMs(0b0000);						// ArduIO 4 free PWMs off
	// LEDs:
	setArduIOLEDs(0b0000);						// ArduIO 4 LEDs off
	// I/O Expanders:
	io1config.word = 0xffff;
	io2config.word = 0xffff;
	io3config.word = 0xffff;					// ArduIO 48 IOs INPUTs
	io1invrt.word = 0;
	io2invrt.word = 0;
	io3invrt.word = 0;							// ArduIO 48 IOs NOT inverted
}

/**
 * If you don't use any function of the ArduIO
 * Board, you can put the ArduIO Board into
 * "SHUTDOWN MODE". In this mode the electric
 * power consumption is very low to save energy.
 * If DISABLE_ON_SHUTDOWN is defined (default),
 * access to ArduIO functions is disabled in
 * SHUTDOWN mode.
 * SHUTDOWN settings are:
 * - Power PWM mode enable
 * - H-Bridge mode disable
 * - All 8 power PWMs off
 * - All 4 free PWMs off
 * - All 4 LEDs off
 * - All 48 IOs INPUTs
 * - All 3 DACs disable
 * - Access to ArduIO functions disable
 *   (if DISABLE_ON_SHUTDOWN is defined!)
 *
 */
void arduio_shutdown(void)
{
	// ArduIO Status (DEFAULT):
	setArduIODefaultStatus();					// ArduIO access default status
	// Power PWM Ports & H-Bridges:
	setArduIOPowerPWMMode();					// ArduIO 8 power PWMs off
	// PWMs:
	setArduIOPWMs(0b0000);						// ArduIO 4 free PWMs off
	// LEDs:
	setArduIOLEDs(0b0000);						// ArduIO 4 LEDs off
	// I/O Expanders:
	configArduIO_IO1(0b1111111111111111);
	configArduIO_IO2(0b1111111111111111);
	configArduIO_IO3(0b1111111111111111);		// ArduIO 48 IOs INPUTs
	// A/D and D/A Converters:
	disableAllArduIO_DAs();						// ArduIO 3 DACs disable
#ifdef DISABLE_ON_SHUTDOWN
	// ArduIO Status (SHUTDOWN):
	setArduIOShutdownStatus();					// ArduIO access shutdown status
#endif
}

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


/*****************************************************************************/
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*                       Arduino Uno Expander functions                      */
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/

/*~
 ~ Update the IO_2 port with current value from
 ~ the global io2outs variable.
 ~ The 16 IO_2 portpins will be SET (high, ON)
 ~ or CLEARED (low, OFF). 14 of these IO_2
 ~ portpins are connected with the digital 
 ~ Arduino Uno Expander portpins D0..D13.
 ~
 ~ There is a special option for the Arduino Uno
 ~ Expander "PWM portpins" D3, D5, D6, D9, D10
 ~ and D11:
 ~ If you set a jumper on JP_PWMx (x = PWM
 ~ number), the corresponding PWMx is connected
 ~ with one of these "PWM portpins":
 ~   PWM1 -> P5  (JP_PWM1 pins 1-2 closed)
 ~        or P6  (JP_PWM1 pins 2-3 closed)
 ~   PWM2 -> P9  (JP_PWM2 pins 1-2 closed)
 ~        or P10 (JP_PWM2 pins 2-3 closed)
 ~   PWM3 -> P11 (JP_PWM3 pins 1-2 closed)
 ~        or P3  (JP_PWM3 pins 2-3 closed)
 ~ If all JP_PWMx pins are open, PWMx is NOT
 ~ connected to the Arduino Uno Expander!!!
 ~ If JP_PWMx pins are closed, the JP_ARD2 jumper
 ~ of that "PWM portpin" (D3, D5, D6, D9, D10
 ~ and/or D11) on the ArduIO Board MUST BE OPEN
 ~ (IO_2 portpin(s) disconnected)!!!
 ~
 ~ Bit positions of the Arduino Uno Expander
 ~ portpins in the io2outs word:
 ~          0b0000000000000000
 ~            |||    ||      |
 ~   Arduino: ||D8   |D7     D0
 ~            n.c.   D13 
 ~
 ~ Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 ~       ! THE ACCESS IS ENABLED (default): !
 ~       !   ==> enableOuts(); <==          !
 ~       !   ==> enablePWMs(); <==          !
 ~
 ~ Examples:
 ~   io2outs.word = 0b0000000100101001;
 ~   updateArduino_Uno_Exp_IO();
 ~   // this CLEARs the port and SETs the
 ~   // Arduino Uno Expander portpins D0, D3,
 ~   // D5 and D13!
 ~
 ~   // Other possibility:
 ~   io2outs.ARD_D8 = true;   // Or io2outs.P15 = true;
 ~   updateArduino_Uno_Exp_IO();
 ~   // this SETs the Arduino Uno Expander
 ~   // portpin D8 and does not affect any
 ~   // other portpin!
 ~
 */
void updateArduino_Uno_Exp_IO(void)
{
	if (RP6ArduIOstatus_LIB.outsEnable) {
		I2CTWI_transmit3Bytes(I2C_ARDUIO_IO_2_ADR, PCA9535_OUTPUT_P0, (io2outs.word & 0x00ff), (io2outs.word >> 8));
	}
	// Set the Arduino Uno Expander PWM portpins (see RP6_ArduIO.h!):
	if (IO_ARD_PWM1) {							// PWM1 -> D5 or D6
		if (IO_ARD_PWM1 == IO_ARD_D5_PWM) {		// D5
			setArduIOPWM1(!io2outs.ARD_D5);		// IO:low = PWM:ON!!!
		}
		if (IO_ARD_PWM1 == IO_ARD_D6_PWM) {		// D6
			setArduIOPWM1(!io2outs.ARD_D6);
		}
	}
	if (IO_ARD_PWM2) {							// PWM2 -> D9 or D10
		if (IO_ARD_PWM2 == IO_ARD_D9_PWM) {		// D9
			setArduIOPWM2(!io2outs.ARD_D9);
		}
		if (IO_ARD_PWM2 == IO_ARD_D10_PWM) {	// D10
			setArduIOPWM2(!io2outs.ARD_D10);
		}
	}
	if (IO_ARD_PWM3) {							// PWM3 -> D11 or D3
		if (IO_ARD_PWM3 == IO_ARD_D11_PWM) {	// D11
			setArduIOPWM3(!io2outs.ARD_D11);
		}
		if (IO_ARD_PWM3 == IO_ARD_D3_PWM) {		// D3
			setArduIOPWM3(!io2outs.ARD_D3);
		}
	}
}

/*~
 ~ This function SETs (high, ON) or CLEARs
 ~ (low, OFF) the 16 IO_2 portpins. 14 of these
 ~ IO_2 portpins are connected with the digital 
 ~ Arduino Uno Expander portpins D0..D13.
 ~
 ~ There is a special option for the Arduino Uno
 ~ Expander "PWM portpins" D3, D5, D6, D9, D10
 ~ and D11:
 ~ If you set a jumper on JP_PWMx (x = PWM
 ~ number), the corresponding PWMx is connected
 ~ with one of these "PWM portpins":
 ~   PWM1 -> P5  (JP_PWM1 pins 1-2 closed)
 ~        or P6  (JP_PWM1 pins 2-3 closed)
 ~   PWM2 -> P9  (JP_PWM2 pins 1-2 closed)
 ~        or P10 (JP_PWM2 pins 2-3 closed)
 ~   PWM3 -> P11 (JP_PWM3 pins 1-2 closed)
 ~        or P3  (JP_PWM3 pins 2-3 closed)
 ~ If all JP_PWMx pins are open, PWMx is NOT
 ~ connected to the Arduino Uno Expander!!!
 ~ If JP_PWMx pins are closed, the JP_ARD2 jumper
 ~ of that "PWM portpin" (D3, D5, D6, D9, D10
 ~ and/or D11) on the ArduIO Board MUST BE OPEN
 ~ (IO_2 portpin(s) disconnected)!!!
 ~
 ~ Input: out -> Output value (16 bit)
 ~
 ~ Bit positions of the Arduino Uno Expander
 ~ portpins in the output value (out):
 ~          0b0000000000000000
 ~            |||    ||      |
 ~   Arduino: ||D8   |D7     D0
 ~            n.c.   D13 
 ~
 ~ Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 ~       ! THE ACCESS IS ENABLED (default): !
 ~       !   ==> enableOuts(); <==          !
 ~       !   ==> enablePWMs(); <==          !
 ~
 ~ Example:
 ~   setArduino_Uno_Exp_IO(0b0010000000101001);
 ~   // this CLEARs the port and SETs the
 ~   // Arduino Uno Expander portpins D0, D3,
 ~   // D5 and D8!
 ~
 */
void setArduino_Uno_Exp_IO(uint16_t out)
{
	if (RP6ArduIOstatus_LIB.outsEnable) {
		io2outs.word = out;
		updateArduino_Uno_Exp_IO();
	}
}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// ArduIO Board Arduino Uno Expander control routine:

/*~
 ~ Call all important Arduino Uno Expander tasks.
 ~ This task will read:
 ~  - All Arduino digital portpins D0..D13
 ~    Result: io2ins.ARD_D0..io2ins.ARD_D13
 ~  - The PCA9535 (2) INT (XBUS INT1)
 ~    Result: interrupt_RP6ArduIOstatus.ioexp_2
 ~  - The Arduino analog portpins A0..A3
 ~    Result: ad3ins.ARD_A0..ad3ins.ARD_A3
 ~ The variable interrupt_rp6arduiostatus_changed
 ~ will be TRUE, if the RP6ArduIO interrupt status
 ~ has changed since the last call of this task
 ~ (or task_checkArduIO_INTs), else it will be
 ~ FALSE.
 ~ There is also a macro int_status_changed(),
 ~ that may be used instead of the variable
 ~ interrupt_rp6arduiostatus_changed.
 ~
 ~ Hints: - You can use task_RP6_ArduIOSystem()
 ~          instead of THIS task! Do NOT use both
 ~          tasks together!
 ~        - You should only use this task, if you
 ~          have to read ALL digital and analog
 ~          Arduino Uno Expander input portpins!
 ~        - Digital portpins can be read, if they
 ~          were configured as INPUTs before:
 ~          configArduIO_IO2(0b1111111111111111);
 ~        - Digital portpin input values can be
 ~          inverted with the function
 ~          invertArduIO_IO(2,invrt)!
 ~        - PCA9535 (2) INT can only be read, if
 ~          the corresponding jumper (JP_INT3V3)
 ~          is CLOSED:
 ~          INT1 -> Pins 1-2 (PCA9535 (2) INT)
 ~
 */
void task_Arduino_Uno_Exp(void)
{
	task_readArduino_Uno_Exp_IO();				// Or task_readArduIO_IO(2);
	if(IO_ARDUIO_INT1_PIN & IO_ARDUIO_INT1_IN)	// XBUS INT1
		newstatus.int1 = true;
	else
		newstatus.int1 = false;
	if (newstatus.int1 != interrupt_RP6ArduIOstatus.int1) {
		interrupt_rp6arduiostatus_changed = true;
		interrupt_RP6ArduIOstatus.int1 = newstatus.int1;
	}
	else interrupt_rp6arduiostatus_changed = false;
	task_readArduino_Uno_Exp_AD();				// Or task_readArduIO_AD(3);
}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*                    Arduino Uno Expander functions end                     */
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*****************************************************************************/

/******************************************************************************
 * Additional info
 * ****************************************************************************
 * Changelog:
 * - v. 1.1 (adapted for use with MultiIOLib) 28.11.2014 by Dirk
 * - v. 1.0 (initial release) 22.10.2014 by Dirk
 *
 * ****************************************************************************
 */

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


RP6 M256 WIFI

Die Demos für die RP6 M256 WiFi (und -wenn ihr wollt- auch eure eigenen Programme) nutzen die ArduIO Library, s.o.!

Config

Diese Datei enthält nur die Information, welches RP6-Mikrocontroller-System (RP6 Base, RP6 CONTROL M32, RP6 M256 WiFi) das ArduIO Board ansteuert. Sie gehört in den Projektordner.

Datei RP6_ArduIOConfig.h:

/**
 * Settings for the RP6_ArduIO Library
 */ 

#ifndef RP6_ARDUIOCONFIG_H
#define RP6_ARDUIOCONFIG_H


/**
 * Define the target here: 
 * (Use only ONE of them! Never two or three!) 
 */ 
//#define ARDUIO_RP6BASE 
//#define ARDUIO_RP6CONTROL
#define ARDUIO_RP6M256WIFI


#endif

makefile (z.B. für Demo 1):

...
TARGET = RP6M256_ArduIO_01
...
SRC += $(RP6_LIB_PATH)/RP6common/RP6_ArduIOLib.c
...
Demos der M32 anpassen

Es ist einfach, die M32 Demos an die M256 anzupassen. Die ArduIO Library braucht nicht verändert zu werden.

Folgende Anpassungen müssen gemacht werden:

- #include "RP6ControlLib.h" ==> #include "RP6M256Lib.h"
- initRP6Control();          ==> initRP6M256();
- getPressedKeyNumber()      ==> Tastenabfrage komplett entfernen!

Zusätzlich können bei der M256 alle UART-Ausgaben auf WiFi umgeleitet werden. Dazu muß an die UART-Ausgabebefehle "_WIFI" angehängt werden.

Beispiel:

- writeString_P("Text");     ==> writeString_P_WIFI("Text");

Die Funktion writeDouble() der M32 Demos kann für die WiFi-Ausgabe ersetzt werden durch:

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]);
}


RP6 CONTROL M32

Diese Demos für die RP6 CONTROL M32 (und -wenn ihr wollt- auch eure eigenen Programme) nutzen die ArduIO Library, s.o.!

Config

Diese Datei enthält nur die Information, welches RP6-Mikrocontroller-System (RP6 Base, RP6 CONTROL M32, RP6 M256 WiFi) das ArduIO Board ansteuert. Sie gehört in den Projektordner.

Datei RP6_ArduIOConfig.h:

/**
 * Settings for the RP6_ArduIO Library
 */ 

#ifndef RP6_ARDUIOCONFIG_H
#define RP6_ARDUIOCONFIG_H


/**
 * Define the target here: 
 * (Use only ONE of them! Never two or three!) 
 */ 
//#define ARDUIO_RP6BASE 
#define ARDUIO_RP6CONTROL
//#define ARDUIO_RP6M256WIFI


#endif

makefile (z.B. für Demo 1):

...
TARGET = RP6Control_ArduIO_01
...
SRC += $(RP6_LIB_PATH)/RP6common/RP6_ArduIOLib.c
...
Demo 1

Die Demo 1 besteht eigentlich aus ZWEI Testprogrammen. Wird sie so kompiliert, wie sie hier steht, erfolgt ein SCHREIB-Test (Output) auf allen Funktionen der ArduIO. Wird die Definition "WRITE_TEST" auskommentiert, erfolgt ein LESE-Test (Input).

Datei RP6Control_ArduIO_01.c:

/* 
 * ****************************************************************************
 * RP6 ROBOT SYSTEM - RP6 CONTROL M32 Examples
 * ****************************************************************************
 * Example: RP6Control ArduIO
 * Author(s): Dirk
 * ****************************************************************************
 * Description:
 * In this example we show a first test for the ArduIO 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 "RP6_ArduIO library":
// (This is the library for accessing the ArduIO Board!)

#include "RP6_ArduIOLib.h"

/*****************************************************************************/
// Define the kind of demo:
// (If you don't define WRITE_TEST the READ TEST will be performed!)
#define WRITE_TEST

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

/**
 * 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 ArduIO Test 1!\n");
#ifdef WRITE_TEST
	writeString_P("\nPLEASE ENSURE THAT NO PINS OF PLUG SV_H-BRIDGES ARE CONNECTED!!!\n");
#endif
	writeString_P("\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 Ardu IO",  "   Selftest 1");
	mSleep(2500);
	clearLCD();

	setLEDs(0b0000);

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

	uint8_t onoff = 0;

	startStopwatch1();

	// IMPORTANT:
	arduio_init();								// ArduIO init!!!
#ifdef WRITE_TEST
	writeString_P("Test -> LED1\n");
	setArduIOLED1(1);
	mSleep(500);
	setArduIOLED1(0);
	mSleep(500);
	setArduIOLED1(1);
	mSleep(1000);
	writeString_P("Test -> LED2\n");
	setArduIOLED2(1);
	mSleep(500);
	setArduIOLED2(0);
	mSleep(500);
	setArduIOLED2(1);
	mSleep(1000);
	writeString_P("Test -> LED3\n");
	setArduIOLED3(1);
	mSleep(500);
	setArduIOLED3(0);
	mSleep(500);
	setArduIOLED3(1);
	mSleep(1000);
	writeString_P("Test -> LED4\n");
	setArduIOLED4(1);
	mSleep(500);
	setArduIOLED4(0);
	mSleep(500);
	setArduIOLED4(1);
	mSleep(500);

	setArduIOLEDs(0b0000);

	configArduIO_IO1(0);
	configArduIO_IO2(0);
	configArduIO_IO3(0);						// All IOs OUTPUTs
	mSleep(100);
#else
	configArduIO_IO1(0b1111111111111111);
	configArduIO_IO2(0b1111111111111111);
	configArduIO_IO3(0b1111111111111111);		// All IOs INPUTs
	mSleep(100);
#endif
	writeString_P("\n===> PRESS BUTTON 5 TO STOP THE DEMO!!! <===\n\n");

	while(true) 
	{
		if(getStopwatch1() > 1000) // 1s
		{
			if (onoff) onoff = 0;
			else onoff = 1;
#ifndef WRITE_TEST
			// UB voltage sensor ADC test:
			ubv = measureUb();
			writeString("\nUB Voltage: ");
			writeDouble(ubv, 4, 1);
			writeString("V\nADC UB: ");
			writeInteger(adcub, DEC);
			writeString("\n");
#else
			// PWM controller test:
			//   LEDs & IOs & free PWMs & power PWMs ON/OFF:
			if (onoff) {
				setArduIO_IO1(0xffff);
				setArduIO_IO2(0xffff);
				setArduIO_IO3(0xffff);			// All IOs high
				setArduIOLED1(1);
				setArduIOLED2(0);
				setArduIOLED3(0);
				setArduIOLED4(1);
				setArduIOPWM1(1);
				setArduIOPWM2(0);
				setArduIOPWM3(0);
				setArduIOPWM4(1);
				setArduIOPowerPWMs(0b10101010);
			}
			else {
				setArduIO_IO1(0);
				setArduIO_IO2(0);
				setArduIO_IO3(0);				// All IOs low
				setArduIOLEDs(0b0110);
				setArduIOPWMs(0b0110);
				setArduIOPowerPWMs(0b01010101);
			}
#endif
#ifndef WRITE_TEST
			// I/O Expander 1 read test:
			task_readArduIO_IO1();				// Read GP100..GP117
			writeString("\nIO_1: ");
			writeIntegerLength(io1ins.word, BIN, 16);
			writeString("\n");
			// I/O Expander 2 read test:
			task_readArduIO_IO2();				// Read GP200..GP217
			writeString("\nIO_2: ");
			writeIntegerLength(io2ins.word, BIN, 16);
			writeString("\n ARD:     1111");
			writeString("\n        89012376543210\n");
			// I/O Expander 3 read test:
			task_readArduIO_IO3();				// Read GP300..GP317
			writeString("\nIO_3: ");
			writeIntegerLength(io3ins.word, BIN, 16);
			writeString("\n");

			// AD/DA Converter 1 ADC test:
			task_readArduIO_AD1();				// Read AD10..AD13
			writeString("ADDA_1: ");
			writeIntegerLength(ad1ins.AD10, DEC, 3);
			writeString(" | ");
			writeIntegerLength(ad1ins.AD11, DEC, 3);
			writeString(" | ");
			writeIntegerLength(ad1ins.AD12, DEC, 3);
			writeString(" | ");
			writeIntegerLength(ad1ins.AD13, DEC, 3);
			writeString("\n U[cV]: ");
			writeIntegerLength(UCV_AD(ad1ins.AD10), DEC, 3);
			writeString(" | ");
			writeIntegerLength(UCV_AD(ad1ins.AD11), DEC, 3);
			writeString(" | ");
			writeIntegerLength(UCV_AD(ad1ins.AD12), DEC, 3);
			writeString(" | ");
			writeIntegerLength(UCV_AD(ad1ins.AD13), DEC, 3);
			writeString("\n        A0  | A1  | A2  | A3\n");
			// AD/DA Converter 2 ADC test:
			task_readArduIO_AD2();				// Read AD20..AD23
			writeString("ADDA_2: ");
			writeIntegerLength(ad2ins.AD20, DEC, 3);
			writeString(" | ");
			writeIntegerLength(ad2ins.AD21, DEC, 3);
			writeString(" | ");
			writeIntegerLength(ad2ins.AD22, DEC, 3);
			writeString(" | ");
			writeIntegerLength(ad2ins.AD23, DEC, 3);
			writeString("\n U[cV]: ");
			writeIntegerLength(UCV_AD(ad2ins.AD20), DEC, 3);
			writeString(" | ");
			writeIntegerLength(UCV_AD(ad2ins.AD21), DEC, 3);
			writeString(" | ");
			writeIntegerLength(UCV_AD(ad2ins.AD22), DEC, 3);
			writeString(" | ");
			writeIntegerLength(UCV_AD(ad2ins.AD23), DEC, 3);
			writeString("\n        A0  | A1  | A2  | A3\n");
			// AD/DA Converter 3 ADC test:
			task_readArduIO_AD3();				// Read AD30..AD33
			writeString("ADDA_3: ");
			writeIntegerLength(ad3ins.ARD_A0, DEC, 3);
			writeString(" | ");
			writeIntegerLength(ad3ins.ARD_A1, DEC, 3);
			writeString(" | ");
			writeIntegerLength(ad3ins.ARD_A2, DEC, 3);
			writeString(" | ");
			writeIntegerLength(ad3ins.ARD_A3, DEC, 3);
			writeString("\n U[cV]: ");
			writeIntegerLength(UCV_AD(ad3ins.ARD_A0), DEC, 3);
			writeString(" | ");
			writeIntegerLength(UCV_AD(ad3ins.ARD_A1), DEC, 3);
			writeString(" | ");
			writeIntegerLength(UCV_AD(ad3ins.ARD_A2), DEC, 3);
			writeString(" | ");
			writeIntegerLength(UCV_AD(ad3ins.ARD_A3), DEC, 3);
			writeString("\n   ARD: A0  | A1  | A2  | A3\n");
#else
			// AD/DA Converter 1..3 DAC test:
			if (onoff) {
				writeString("==> DA1..3: 1.50V\n");
				writeArduIO_DA1(AOUT_CV(150));	// DA1: 1.5V
				writeArduIO_DA2(AOUT_CV(150));	// DA2: 1.5V
				writeArduIO_DA3(AOUT_CV(150));	// DA3: 1.5V
			}
			else {
				writeString("==> DA1..3: 3.50V\n");
				writeArduIO_DA1(AOUT_CV(350));	// DA1: 3.5V
				writeArduIO_DA2(AOUT_CV(350));	// DA2: 3.5V
				writeArduIO_DA3(AOUT_CV(350));	// DA3: 3.5V
			}
#endif
			// ArduIO shutdown:
			uint8_t key = getPressedKeyNumber(); 
			if (key == 5) {
				writeString("\nPress button 1 for ArduIO SHUTDOWN");
				writeString("\nor button 2, 3 or 4 to continue!!!\n");
				do {
					mSleep(10);
					key = getPressedKeyNumber();
				} while ((!key) || (key == 5));
				if (key == 1)  {
					writeString("\nPlease wait for ArduIO SHUTDOWN...\n");
					arduio_shutdown();
					mSleep(3000);
					writeString("\nThe ArduIO now is in SHUTDOWN MODE!!!\n");
					mSleep(1000);
					writeString("\nRESET the microcontroller now...\n\n");
					while(true) {};
				}
			}

			setStopwatch1(0);
		}

		task_I2CTWI();
	}

	return 0;
}
Erklärung
Demo 2

Die Demo 2 zeigt, wie die LEDs, freien PWMs und Power PWMs gedimmt werden können.

Datei RP6Control_ArduIO_02.c:

/* 
 * ****************************************************************************
 * RP6 ROBOT SYSTEM - RP6 CONTROL M32 Examples
 * ****************************************************************************
 * Example: RP6Control ArduIO
 * Author(s): Dirk
 * ****************************************************************************
 * Description:
 * In this example we show a second test for the ArduIO 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 "RP6_ArduIO library":
// (This is the library for accessing the ArduIO Board!)

#include "RP6_ArduIOLib.h"

/*****************************************************************************/
// 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 ArduIO Test 2!\n"); 
	writeString_P("\nPLEASE ENSURE THAT NO PINS OF PLUG SV_H-BRIDGES ARE CONNECTED!!!\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 Ardu IO",  "   Selftest 2");
	mSleep(2500);
	clearLCD();

	setLEDs(0b0000);

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

	uint8_t duty_pct = 0;

	startStopwatch1();

	// IMPORTANT:
	arduio_init();								// ArduIO init!!!

	writeString_P("\n===> PRESS BUTTON 5 TO STOP THE DEMO!!! <===\n\n");

	while(true) 
	{
		if(getStopwatch1() > 1000) // 1s
		{
			// PWM controller test:
			//   LEDs & free PWMs & power PWMs dim UP:
			writeString("==> DIM Tests: ");
			writeInteger(duty_pct, DEC);
			writeString(" % Duty Cycle\n");
			dimArduIOLED(1, DUTY_PCT(duty_pct));
			dimArduIOLED(2, DUTY_PCT(duty_pct));
			dimArduIOLED3(DUTY_PCT(duty_pct));
			dimArduIOLED4(DUTY_PCT(duty_pct));
			dimArduIOPWM(1, DUTY_PCT(duty_pct));
			dimArduIOPWM(2, DUTY_PCT(duty_pct));
			dimArduIOPWM3(DUTY_PCT(duty_pct));
			dimArduIOPWM4(DUTY_PCT(duty_pct));
			dimArduIOPowerPWM(1, DUTY_PCT(duty_pct));
			dimArduIOPowerPWM(2, DUTY_PCT(duty_pct));
			dimArduIOPowerPWM3(DUTY_PCT(duty_pct));
			dimArduIOPowerPWM4(DUTY_PCT(duty_pct));
			dimArduIOPowerPWM(5, DUTY_PCT(duty_pct));
			dimArduIOPowerPWM(6, DUTY_PCT(duty_pct));
			dimArduIOPowerPWM7(DUTY_PCT(duty_pct));
			dimArduIOPowerPWM8(DUTY_PCT(duty_pct));
			duty_pct += 10;
			if (duty_pct > 100) {
				duty_pct = 0;
				writeString("\n");
			}

			// ArduIO shutdown:
			uint8_t key = getPressedKeyNumber(); 
			if (key == 5) {
				writeString("\nPress button 1 for ArduIO SHUTDOWN");
				writeString("\nor button 2, 3 or 4 to continue!!!\n");
				do {
					mSleep(10);
					key = getPressedKeyNumber();
				} while ((!key) || (key == 5));
				if (key == 1)  {
					writeString("\nPlease wait for ArduIO SHUTDOWN...\n");
					arduio_shutdown();
					mSleep(3000);
					writeString("\nThe ArduIO now is in SHUTDOWN MODE!!!\n");
					mSleep(1000);
					writeString("\nRESET the microcontroller now...\n\n");
					while(true) {};
				}
			}

			setStopwatch1(0);
		}

		task_I2CTWI();
	}

	return 0;
}
Erklärung
Demo 3

Die Demo 3 demonstriert die Ansteuerung der H-Brücken.

Datei RP6Control_ArduIO_03.c:

/* 
 * ****************************************************************************
 * RP6 ROBOT SYSTEM - RP6 CONTROL M32 Examples
 * ****************************************************************************
 * Example: RP6Control ArduIO
 * Author(s): Dirk
 * ****************************************************************************
 * Description:
 * In this example we show a third test for the ArduIO 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 "RP6_ArduIO library":
// (This is the library for accessing the ArduIO Board!)

#include "RP6_ArduIOLib.h"

/*****************************************************************************/
// 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 ArduIO Test 3!\n");
	writeString_P("\nYOU MAY WATCH THE RED & GREEN MOSFET-LEDS AND/OR");
	writeString_P("\nCONNECT  A DC-MOTOR TO THE PLUG  SV_H-BRIDGES!!!\n\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 Ardu IO",  "   Selftest 3");
	mSleep(2500);
	clearLCD();

	setLEDs(0b0000);

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

	uint8_t duty_pct = 0;
	uint8_t cnt_sec = 0;

	startStopwatch1();

	// IMPORTANT:
	arduio_init();								// ArduIO init!!!
	enableHB1();								// Enable HB1!!!
	enableHB2();								// Enable HB2!!!

	writeString("Test -> HB1 OFF\n");
	powerHB1OFF();
	mSleep(5000);
	writeString("Test -> HB1 FWD 10%\n");
	powerHB1FWD(DUTY_PCT(10));
	mSleep(5000);
	writeString("Test -> HB1 STOP\n");
	powerHB1STOP();
	mSleep(5000);
	writeString("Test -> HB1 BWD 10%\n");
	powerHB1BWD(DUTY_PCT(10));
	mSleep(5000);
	writeString("Test -> HB1 BRK\n");
	powerHB1BRK();
	mSleep(5000);
	writeString("Test -> HB1 OFF\n");
	powerHB1OFF();
	mSleep(5000);

	writeString("Test -> HB2 OFF\n");
	powerHB2OFF();
	mSleep(5000);
	writeString("Test -> HB2 FWD 10%\n");
	powerHB2FWD(DUTY_PCT(10));
	mSleep(5000);
	writeString("Test -> HB2 STOP\n");
	powerHB2STOP();
	mSleep(5000);
	writeString("Test -> HB2 BWD 10%\n");
	powerHB2BWD(DUTY_PCT(10));
	mSleep(5000);
	writeString("Test -> HB2 BRK\n");
	powerHB2BRK();
	mSleep(5000);
	writeString("Test -> HB2 OFF\n");
	powerHB2OFF();
	mSleep(5000);

	writeString_P("\n===> PRESS BUTTON 5 TO STOP THE DEMO!!! <===\n\n");

	while(true) 
	{
		if(getStopwatch1() > 1000) // 1s
		{
			// PWM controller test:
			//   H-Bridges:
			writeString("==> HB1/2 DIM Tests: ");
			writeInteger(duty_pct, DEC);
			writeString(" % Duty Cycle");
			if (cnt_sec < 22) {					// 2 cycles FWD
				writeString(" Dir: FWD\n");
				powerHB1FWD(DUTY_PCT(duty_pct));
				powerHB2FWD(DUTY_PCT(duty_pct));
			}
			else {								// 2 cycles BWD
				writeString(" Dir: BWD\n");
				powerHB1BWD(DUTY_PCT(duty_pct));
				powerHB2BWD(DUTY_PCT(duty_pct));
			}
			cnt_sec++;
			if (cnt_sec > 43) cnt_sec = 0;
			duty_pct += 10;
			if (duty_pct > 100) {
				duty_pct = 0;
				writeString("\n");
			}

			// ArduIO shutdown:
			uint8_t key = getPressedKeyNumber(); 
			if (key == 5) {
				writeString("\nPress button 1 for ArduIO SHUTDOWN");
				writeString("\nor button 2, 3 or 4 to continue!!!\n");
				do {
					mSleep(10);
					key = getPressedKeyNumber();
				} while ((!key) || (key == 5));
				if (key == 1)  {
					writeString("\nPlease wait for ArduIO SHUTDOWN...\n");
					arduio_shutdown();
					mSleep(3000);
					writeString("\nThe ArduIO now is in SHUTDOWN MODE!!!\n");
					mSleep(1000);
					writeString("\nRESET the microcontroller now...\n\n");
					while(true) {};
				}
			}

			setStopwatch1(0);
		}

		task_I2CTWI();
	}

	return 0;
}
Erklärung
Demo 4
ArduIO RP6-Beleuchtung

Die "Demo 4" ist eigentlich kein fertiges Programm, sondern eine Aufgabe für euch. Es soll dabei um die RP6-Beleuchtung ("Scheinwerfer") gehen, die als "Überraschung" zum ArduIO Board gehört. Wenn man die 5 kleinen Platinen so anschließt, wie im Bild rechts eingezeichnet, dann steuert der I/O Expander 1 mit seinem zweiten Port (GP110..GP117) die Scheinwerfer an.

Was ist jetzt die Aufgabe?

==> Schreibe die Demo "RP6Control_09_Move" so um, dass die jeweilige Bewegung
    des RP6 mit der passenden Fahrzeug-Beleuchtung erfolgt. Im Ergebnis soll
    der RP6 sich genau so bewegen, wie in der Original-Demo.
==> Bei Links-Rotation soll der linke Blinker, bei Rechts-Rotation der rechte
    Blinker blinken. Bei Vorwärts-Fahrt soll das Fernlicht leuchten, während
    der Rotation das Abblend-/Standlicht.
==> Am Ende der while(true) Schleife (nach der Rechts-Rotation) soll der RP6
    anhalten, und es soll für 15 Sekunden nur das blaue Blinklicht an sein,
    bevor der Bewegungsablauf am Anfang der while(true) Schleife neu startet.

Das ist zu schaffen, oder?

Zur Ansteuerung der Scheinwerfer gibt es hier eine "Task", die ihr verwenden könnt:

/*****************************************************************************/
// Car lights:
#define BLINKER_PERIOD			667		// 1.5Hz
#define BLINKER_ON_TIME			367		// 55%
#define BLUELIGHT_PERIOD		1000	// 1.0Hz (2 altern. LEDs: 2.0Hz!)
#define BLUELIGHT_ON_TIME		500		// 50%
#define BLUELIGHT_FLASH					// Flash light (else: rotating light)
#define BLUELIGHT_FLASH_TIME	60		// 6%

typedef union {
 	uint8_t byte;
	struct {
		unsigned dimmed        :1;		// Dimmed head- & backlights (GP110)
		unsigned highbeam      :1;		// High beam headlights      (GP111)
		unsigned blinker_left  :1;		// Left blinker              (GP112)
		unsigned blinker_right :1;		// Right blinker             (GP113)
		unsigned stop          :1;		// Stop (brake) light        (GP114)
		unsigned blue          :1;		// Blue light                (GP115)
		unsigned reversing     :1;		// Reversing light           (GP116)
		unsigned fog           :1;		// Fog light                 (GP117)
	};
} carlight_status_t;

carlight_status_t RP6carlight_status;
carlight_status_t lights_on_status;
carlight_status_t lights_on_laststatus;

/**
 * RP6 vehicle illumination task.
 * You have to call this task frequently out of the main program loop.
 * The task uses the Stopwatches 6, 7 & 8!
 *
 * Example:
 *   ...
 *   arduio_init();                   // ArduIO init!!!
 *   configArduIO_IO1(0b0000000011111111);
 *   #ifdef BLUELIGHT_FLASH
 *     startStopwatch6();
 *   #endif
 *   startStopwatch7();               // For task_RP6carlights()
 *   startStopwatch8();
 *   ...
 *   RP6carlight_status.blue = 1;     // Blue light ON
 *   RP6carlight_status.highbeam = 0; // High beam headlights OFF
 *   ...
 *   while(true) // Main program loop
 *   {
 *     ...
 *     task_RP6carlights();
 *   }
 *
 */
void task_RP6carlights(void)
{
	uint8_t blinker_on = 0, blue_on = 0;
#ifdef BLUELIGHT_FLASH
	uint8_t blue_flash_on = 0;
	if (getStopwatch6() > BLUELIGHT_FLASH_TIME) {
		blue_flash_on = 1;
		if (getStopwatch6() > (BLUELIGHT_FLASH_TIME * 2)) {
			blue_flash_on = 0;
			setStopwatch6(0);
		}
	}
#endif
	if (getStopwatch7() > BLINKER_PERIOD) {
		blinker_on = 1;
		if (getStopwatch7() > (BLINKER_PERIOD + BLINKER_ON_TIME)) {
			blinker_on = 0;
			setStopwatch7(0);
		}
	}
	if (getStopwatch8() > BLUELIGHT_PERIOD) {
		blue_on = 1;
		if (getStopwatch8() > (BLUELIGHT_PERIOD + BLUELIGHT_ON_TIME)) {
			blue_on = 0;
			setStopwatch8(0);
		}
	}
	lights_on_status.byte = RP6carlight_status.byte;
	if (RP6carlight_status.blinker_left) {
		if (blinker_on) lights_on_status.blinker_left = 1;
		else lights_on_status.blinker_left = 0;	
	}
	if (RP6carlight_status.blinker_right) {
		if (blinker_on) lights_on_status.blinker_right = 1;
		else lights_on_status.blinker_right = 0;
	}
	if (RP6carlight_status.blue) {
		if (blue_on) {
			if (io1config.P15) configArduIO_IO1(0b0000000011111111);
#ifdef BLUELIGHT_FLASH
			if (blue_flash_on) lights_on_status.blue = 1;
			else lights_on_status.blue = 0;
#else
			lights_on_status.blue = 1;
#endif
		}
		else {
#ifdef BLUELIGHT_FLASH
			if (!io1config.P15) configArduIO_IO1(0b0010000011111111);
#else
			lights_on_status.blue = 0;
#endif
		}
	}
	else {
		if (!io1config.P15) configArduIO_IO1(0b0010000011111111);
	}
	if (lights_on_status.byte != lights_on_laststatus.byte) {
		io1outs.word &= 0b0000000011111111;
		io1outs.word |= (lights_on_status.byte << 8);
		updateArduIO_IO1();
		lights_on_laststatus.byte = lights_on_status.byte;
	}
}

/*****************************************************************************/
ArduIO RP6-Frontlichter und MultiIO Linienfolger Board
ArduIO RP6-Hecklichter und MultiIO Bumper Board

Viel Erfolg!


Tipps:

  • Die Carlights Task funktioniert nur in einer schnellen Schleife!
  • Damit scheidet die Lösung mit den Bewegungsbefehlen (move, rotate) im Modus "BLOCKING" aus, und man muss sie in nicht blockierende Bewegungsbefehle (4. Parameter "NON_BLOCKING") umändern.
  • Seht euch auch folgende nützlichen Befehle/Funktionen an:
    • isMovementComplete()
    • task_checkINT0()
    • task_I2CTWI()


Erklärung


RP6 BASE

Die Demos für die RP6(v2) Base (und -wenn ihr wollt- auch eure eigenen Programme) nutzen die ArduIO Library, s.o.!

Config

Diese Datei enthält nur die Information, welches RP6-Mikrocontroller-System (RP6 Base, RP6 CONTROL M32, RP6 M256 WiFi) das ArduIO Board ansteuert. Sie gehört in den Projektordner.

Datei RP6_ArduIOConfig.h:

/**
 * Settings for the RP6_ArduIO Library
 */ 

#ifndef RP6_ARDUIOCONFIG_H
#define RP6_ARDUIOCONFIG_H


/**
 * Define the target here: 
 * (Use only ONE of them! Never two or three!) 
 */ 
#define ARDUIO_RP6BASE 
//#define ARDUIO_RP6CONTROL
//#define ARDUIO_RP6M256WIFI


#endif

makefile (z.B. für Demo 1):

...
TARGET = RP6Base_ArduIO_01
...
SRC += $(RP6_LIB_PATH)/RP6common/RP6_ArduIOLib.c
...
Demos der M32 anpassen

Es ist einfach, die M32 Demos an die RP6 Base anzupassen. Die ArduIO Library braucht nicht verändert zu werden.

Folgende Anpassungen müssen gemacht werden:

- #include "RP6ControlLib.h" ==> #include "RP6RobotBaseLib.h"
- initRP6Control();          ==> initRobotBase();
- initLCD();                 ==> LCD-Ausgaben komplett entfernen!
-                            ==> powerON();
- setLEDs(0b1111);           ==> setLEDs(0b111111);
- getPressedKeyNumber()      ==> Tastenabfrage komplett entfernen!


RP6 CCPRO M128

Für die CCPRO M128 soll es hier evtl. eine eigene ArduIO Library geben. Die nachfolgenden Demos nutzen diese Library.

ArduIO Library

Schauen wir mal, ob es hier eine ArduIO Library für die CCPRO M128 geben wird. Das hängt sicher auch davon ab, ob einer der Nutzer das ArduIO Board mit der M128 betreiben will.

Erklärung

Demo 1

Erklärung

Demo 2

Erklärung

Demo 3

Erklärung


Arduino UNO

Das Ardu IO Projekt Board (= "ArduIO") ist nicht nur eine RP6 Erweiterungsplatine, sondern auch ein Arduino Shield. Damit stellt die ArduIO eine Verbindung zwischen dem RP6-System und der "Arduino-Welt" dar. Als Arduino Shield kann die ArduIO auf eine Arduino UNO Platine gesteckt werden, die dann alle Funktionen der ArduIO steuern kann. Weitere Arduino Shields können wiederum auf die ArduIO gesteckt werden. Die Verbindung zum RP6-System kann dann über die XBUS- und USRBUS-Stecker der ArduIO erfolgen.

HINWEIS: Wenn hier vom Arduino UNO die Rede ist, dann sind zur Ansteuerung
des RP6 ArduIO Boards natürlich auch alle weiteren Arduino BOARDS nutzbar,
die selbst einen Sockel für Arduino Shields haben. Die ArduIO kann also z.B.
auch auf dem neuen Arduino TRE (ARM Cortex A8!) oder dem pcDuino3 (ARM
Cortex A7!) genutzt werden.
Auch durch ARM Cortex M0..M4 Boards (z.B. M4: Nucleo STM32F401RE oder M3:
LPCXpresso Board) kann das RP6 ArduIO Board (und damit auch der RP6(v2)!)
angesteuert werden.
Die Adapterplatine Raspberry Pi to Arduino shields connection bridge oder
der ELV Raspberry Adapter für Arduino Shields RPi-AA1 ermöglichen, das RP6
ArduIO Board auf dem Raspberry Pi einzusetzen.
Mit Hilfe einer Adapterplatine (Allnet 113079 Breakoutplatine 2in1 für
Banana Pi + Arduino I/O) ist auch der Übergang zum Banana Pi möglich.

Die folgende ArduIO Library kann natürlich nur auf Plattformen eingesetzt
werden, die Software-kompatibel zum Arduino UNO sind!

ArduIO Library

Hier findet ihr die neue Arduino Library für das ArduIO Board.

Die Library für das Ardu IO Projekt Board (= "ArduIO") geht von folgenden Voraussetzungen aus:

  • Ein Arduino UNO Board wird für die Ansteuerung der ArduIO benutzt.
  • Der Arduino UNO ist der I2C-Bus Master.
  • Die I2C-Bus Geschwindigkeit beträgt 100 kHz.
  • Alle Hardware-Komponenten der ArduIO sind aufgebaut (1).
  • Alle Jumper auf der ArduIO sind in ihrer Standardstellung (2).
  • Die ArduIO ist auf das Arduino UNO Board aufgesteckt.
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 folgende Abbildung!

Standard-Jumperstellung

ArduIO Jumper Standardstellung Hinweis: Die Jumper sind orange eingezeichnet!

Die Jumper der Stromversorgung (S1, JP_5V, JP_UB, JP_LOAD, JP_5V_ARD, JP_3V3_ARD, JP_UBAT_ARD) wurden nicht berücksichtigt!


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

  • Dem Library Header -> Hier gibt es Definitionen, Variablen- und Funktionsdeklarationen für die Library.
  • Der Library Source -> Das ist die eigentliche Library.
  • Der Datei keywords.txt -> Hier stehen alle Bezeichnungen, die im Editor der Arduino IDE markiert (farblich hervorgehoben) werden.
  • Dem optional einzubindenden Definitionen Header -> Hier befinden sich ergänzende Definitionen, deren Benutzung nicht erforderlich ist, aber evtl. das eigene Programm besser lesbar macht.

Die Dateien dieser Arduino Library gehören ins Verzeichnis /.../libraries/RP6_ArduIO/.

Library Header

Datei RP6_ArduIO.h:

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*                                               ___   ___                   */
/*                 _______________________      /   \ /   \                  */
/*                 \| RP6  ROBOT SYSTEM |/     (  -  X  +  )                 */
/*                  \_-_-_-_-_-_-_-_-_-_/       \___/ \___/                  */
/*                                                ARDUINO                    */
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*------------------------------ [c]2014 - Dirk -----------------------------*/
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*~
 ~ Target:    Arduino UNO with RP6 ArduIO Board (Shield)
 ~ Library:   RP6_ArduIO Header
 ~ Version:   1.0
 ~ Author(s): Dirk
 ~
 ~ Description:
 ~ This is the RP6_ArduIO Library header file.
 ~ You have to include this file, if you want to use the library
 ~ RP6_ArduIO.cpp in your own projects.
 */
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/

#ifndef __RP6_ARDUIO_H__
#define __RP6_ARDUIO_H__


/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// ArduIO hardwired components:
// - I2C PWM Controller (IC3: PCA9685)
// - I2C I/O Expander 1 5V (IC8: PCA9535)
// - I2C I/O Expander 2 5V (IC13: PCA9535)
// - I2C I/O Expander 3 3V3 (IC12: PCA9535)
// - I2C A/D and D/A Converter 1 (IC11: PCF8591)
// - I2C A/D and D/A Converter 2 (IC10: PCF8591)
// - I2C A/D and D/A Converter 3 (IC9: PCF8591)
// - UB Voltage Sensor
// - LEDs
// - PWM Ports
// - Power PWM Ports & H-Bridges

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Includes:
#include <Arduino.h>

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Define the RP6_ArduIO class and public section:
class RP6_ArduIO {

public:

RP6_ArduIO();

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// I2C PWM Controller (PCA9685):
// (A5, A4, A3 always 0, A1 always 1!)
#define I2C_ARDUIO_PWM_ADR		0x42	// A2/0 = 0/0
//#define I2C_ARDUIO_PWM_ADR		0x43	// A2/0 = 0/1
//#define I2C_ARDUIO_PWM_ADR		0x46	// A2/0 = 1/0
//#define I2C_ARDUIO_PWM_ADR		0x47	// A2/0 = 1/1
//#define I2C_ARDUIO_PWM_ADR		0x70	// ALLCALLADR

// -------------------------------------------------------
#define PWM_FREQUENCY			1000	// 1kHz (default)
// -------------------------------------------------------

#define CHALL_LED			0	// All LEDs (channels)

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// I2C I/O Expander (PCA9535):
// (A1 always 1!)
#define I2C_ARDUIO_IO_1_ADR		0x22	// A2/0 = 0/0
//#define I2C_ARDUIO_IO_1_ADR		0x23	// A2/0 = 0/1
//#define I2C_ARDUIO_IO_1_ADR		0x26	// A2/0 = 1/0
//#define I2C_ARDUIO_IO_1_ADR		0x27	// A2/0 = 1/1

//#define I2C_ARDUIO_IO_2_ADR		0x22	// A2/0 = 0/0
#define I2C_ARDUIO_IO_2_ADR		0x23	// A2/0 = 0/1
//#define I2C_ARDUIO_IO_2_ADR		0x26	// A2/0 = 1/0
//#define I2C_ARDUIO_IO_2_ADR		0x27	// A2/0 = 1/1

//#define I2C_ARDUIO_IO_3_ADR		0x22	// A2/0 = 0/0
//#define I2C_ARDUIO_IO_3_ADR		0x23	// A2/0 = 0/1
#define I2C_ARDUIO_IO_3_ADR		0x26	// A2/0 = 1/0
//#define I2C_ARDUIO_IO_3_ADR		0x27	// A2/0 = 1/1

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// I2C A/D and D/A Converter (PCF8591):
// (A1 always 1!)
#define I2C_ARDUIO_AD_1_ADR		0x4a	// A2/0 = 0/0
//#define I2C_ARDUIO_AD_1_ADR		0x4b	// A2/0 = 0/1
//#define I2C_ARDUIO_AD_1_ADR		0x4e	// A2/0 = 1/0
//#define I2C_ARDUIO_AD_1_ADR		0x4f	// A2/0 = 1/1

//#define I2C_ARDUIO_AD_2_ADR		0x4a	// A2/0 = 0/0
#define I2C_ARDUIO_AD_2_ADR		0x4b	// A2/0 = 0/1
//#define I2C_ARDUIO_AD_2_ADR		0x4e	// A2/0 = 1/0
//#define I2C_ARDUIO_AD_2_ADR		0x4f	// A2/0 = 1/1

//#define I2C_ARDUIO_AD_3_ADR		0x4a	// A2/0 = 0/0
//#define I2C_ARDUIO_AD_3_ADR		0x4b	// A2/0 = 0/1
#define I2C_ARDUIO_AD_3_ADR		0x4e	// A2/0 = 1/0
//#define I2C_ARDUIO_AD_3_ADR		0x4f	// A2/0 = 1/1

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// UB Voltage Sensor:
// (Connected to A/D and D/A Converter 1 (ADDA_1: IC11), AIN3 (AD13),
//  if jumper JP_AD-UB on the ArduIO Board is CLOSED!)
#define ADCVAL_UB_LOW			175	// UB 6.9V

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// LEDs:
// (Status LED1..LED4 are connected to LED11..LED8 of the PCA9685!)
#define CHLED1				12
#define CHLED2				11
#define CHLED3				10
#define CHLED4				9

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// PWM Ports:
// (Ports PWM1..PWM4 are connected to LED15..LED12 of the PCA9685!)
#define CHPWM1				16
#define CHPWM2				15
#define CHPWM3				14
#define CHPWM4				13

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Power PWM Ports & H-Bridges:
// (H-Bridges HB1/HB2 are connected to LED0..LED3/LED4..LED7 of the PCA9685!)
// Power PWM Ports:
#define CHPOWERPWM1_P			1
#define CHPOWERPWM2_N			2
#define CHPOWERPWM3_P			3
#define CHPOWERPWM4_N			4
#define CHPOWERPWM5_P			5
#define CHPOWERPWM6_N			6
#define CHPOWERPWM7_P			7
#define CHPOWERPWM8_N			8

// H-Bridges:
#define CHHB1_P1			1
#define CHHB1_N1			2
#define CHHB1_P2			3
#define CHHB1_N2			4
#define CHHB2_P1			5
#define CHHB2_N1			6
#define CHHB2_P2			7
#define CHHB2_N2			8

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Arduino Uno Expander definitions:
// ATTENTION: Using this library you MAY NOT connect a RP6 System Board (RP6
//            Base, CONTROL M32, M256 WiFi) to the RP6 ArduIO Board using the
//            RP6 XBUS plug on the ArduIO Board, if the RP6 System Board is
//            the I2C bus master!!!
//            BE VERY CAREFUL:
//            You may damage the Arduino Uno AND your RP6 ArduIO Board!
//
//            Of course you may connect Arduino ADDON boards (shields) to the
//            Arduino Uno Expander pin headers on the ArduIO Board.
//            BE VERY CAREFUL:
//            Not all Arduino shields will work on the RP6 ArduIO Board!  
//            You may damage the Arduino shield AND your RP6 ArduIO Board!
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Arduino Uno Expander <-> RP6_ArduIO Mapping Table:
//   Arduino Uno:  ATmega328:              RP6_ArduIO:
//   Pin Function  Pin  Functions          Pin   Name  IO ADDA
//  -----------------------------------------------------------
//    0  D0  RX    PD0  RXD_PCINT16        P00   GP200  2
//    1  D1  TX    PD1  TXD_PCINT17        P01   GP201  2
//    2  D2        PD2  INT0_PCINT18       P02   GP202  2
//    3  D3  PWM   PD3  INT1_OC2B_PCINT19  P03   GP203  2
//    4  D4        PD4  T0_XCK_PCINT20     P04   GP204  2
//    5  D5  PWM   PD5  T1_OC0B_PCINT21    P05   GP205  2
//    6  D6  PWM   PD6  AIN0_OC0A_PCINT22  P06   GP206  2
//    7  D7        PD7  AIN1_PCINT23       P07   GP207  2
//    8  D8        PB0  ICP1_CLKO_PCINT0   P15   GP215  2
//    9  D9  PWM   PB1  OC1A_PCINT1        P14   GP214  2
//   10  D10 PWM   PB2  SS_OC1B_PCINT2     P13   GP213  2
//   11  D11 PWM   PB3  MOSI_OC2A_PCINT13  P12   GP212  2
//   12  D12       PB4  MISO_PCINT4        P11   GP211  2
//   13  D13       PB5  SCK_PCINT5         P10   GP210  2
//
//    0  A0        PC0  ADC0_PCINT8        AIN0  AD30      3
//    1  A1        PC1  ADC1_PCINT9        AIN1  AD31      3
//    2  A2        PC2  ADC2_PCINT10       AIN2  AD32      3
//    3  A3        PC3  ADC3_PCINT11       AIN3  AD33      3
//    4  A4  SDA   PC4  ADC4_SDA_PCINT12         SDA
//    5  A5  SCL   PC5  ADC5_SCL_PCINT13         SCL

// Arduino Uno Expander ATmega 328 portpin names:
#define IO_ARD_D0_RXD_PCINT16		0
#define IO_ARD_D1_TXD_PCINT17		1
#define IO_ARD_D2_INT0_PCINT18		2
#define IO_ARD_D3_INT1_OC2B_PCINT19	3
#define IO_ARD_D4_T0_XCK_PCINT20	4
#define IO_ARD_D5_T1_OC0B_PCINT21	5
#define IO_ARD_D6_AIN0_OC0A_PCINT22	6
#define IO_ARD_D7_AIN1_PCINT23		7
#define IO_ARD_D8_ICP1_CLKO_PCINT0	8
#define IO_ARD_D9_OC1A_PCINT1		9
#define IO_ARD_D10_SS_OC1B_PCINT2	10
#define IO_ARD_D11_MOSI_OC2A_PCINT13	11
#define IO_ARD_D12_MISO_PCINT4		12
#define IO_ARD_D13_SCK_PCINT5		13

#define AD_ARD_A0_ADC0_PCINT8		0
#define AD_ARD_A1_ADC1_PCINT9		1
#define AD_ARD_A2_ADC2_PCINT10		2
#define AD_ARD_A3_ADC3_PCINT11		3
#define AD_ARD_A4_ADC4_SDA_PCINT12	4
#define AD_ARD_A5_ADC5_SCL_PCINT13	5

// Arduino Uno Expander portpin short definitions:
#define IO_ARD_D0_RX			0
#define IO_ARD_D1_TX			1
#define IO_ARD_D2			2
#define IO_ARD_D3_PWM			3
#define IO_ARD_D4			4
#define IO_ARD_D5_PWM			5
#define IO_ARD_D6_PWM			6
#define IO_ARD_D7			7
#define IO_ARD_D8			8
#define IO_ARD_D9_PWM			9
#define IO_ARD_D10_PWM			10
#define IO_ARD_D11_PWM			11
#define IO_ARD_D12			12
#define IO_ARD_D13			13

#define AD_ARD_A0			0
#define AD_ARD_A1			1
#define AD_ARD_A2			2
#define AD_ARD_A3			3
#define AD_ARD_A4_SDA			4
#define AD_ARD_A5_SCL			5

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// ArduIO Status:

#define DISABLE_ON_SHUTDOWN		// Disable access to PPWM, PWM, Out
					// & DAC ports in SHUTDOWN mode
					// (default)!

// The ArduIO status bits with access settings & UB voltage low flag:
typedef union status_t {
  byte bits;
    struct {
      unsigned ubatLow       :1;	// UB voltage low
      unsigned hb1Enable     :1;	// H-Bridge 1 (HB1) enable
      unsigned hb2Enable     :1;	// H-Bridge 2 (HB2) enable
      unsigned ppwm_g1Enable :1;	// Power PWM group 1 (PPWM1..4) enable
      unsigned ppwm_g2Enable :1;	// Power PWM group 2 (PPWM5..8) enable
      unsigned pwmsEnable    :1;	// Free PWMs (PWM1..4) enable
      unsigned outsEnable    :1;	// IO_1..3 IOs enable as outputs
      unsigned dasEnable     :1;	// ADDA_1..3 DACs enable
    };
};

status_t status;  // ArduIO status bits (read only)

// Functions:
void enableHB(byte);
void disableHB(byte);
void enablePPWM_G(byte);
void disablePPWM_G(byte);
void enablePWMs(void);
void disablePWMs(void);
void enableOuts(void);
void disableOuts(void);
void enableDAs(void);
void disableDAs(void);
#define setArduIODefaultStatus() {enablePPWM_G(1);enablePPWM_G(2); \
 enablePWMs();enableOuts();enableDAs();}
#define setArduIOShutdownStatus() {disableHB(1);disableHB(2); \
 disablePPWM_G(1);disablePPWM_G(2);disablePWMs();disableOuts();disableDAs();}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// I2C PWM 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_DEFAULT		17
#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_DEFAULT		4		// Totem poles (default)
#define PCA9685_MODE2_ARDUIO		16		// Inverted open-drains
#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(unsigned int);
void PCA9685_set(byte, unsigned int);

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// I2C I/O Expander (PCA9535):

// Registers:
#define PCA9535_INPUT_P0		0
#define PCA9535_INPUT_P1		1
#define PCA9535_OUTPUT_P0		2
#define PCA9535_OUTPUT_P1		3
#define PCA9535_POL_INV_P0		4
#define PCA9535_POL_INV_P1		5
#define PCA9535_CONFIG_P0		6
#define PCA9535_CONFIG_P1		7

// I2C I/O Expander 1 5V (IC8: PCA9535):
#define IO_1				1
typedef union {
  unsigned int port;
    struct {
      unsigned P00:1;				// P00
      unsigned P01:1;				// P01
      unsigned P02:1;				// P02
      unsigned P03:1;				// P03
      unsigned P04:1;				// P04
      unsigned P05:1;				// P05
      unsigned P06:1;				// P06
      unsigned P07:1;				// P07
      unsigned P10:1;				// P10
      unsigned P11:1;				// P11
      unsigned P12:1;				// P12
      unsigned P13:1;				// P13
      unsigned P14:1;				// P14
      unsigned P15:1;				// P15
      unsigned P16:1;				// P16
      unsigned P17:1;				// P17
    };
    struct {
      unsigned GP100:1;				// IO_1: P00
      unsigned GP101:1;				// IO_1: P01
      unsigned GP102:1;				// IO_1: P02
      unsigned GP103:1;				// IO_1: P03
      unsigned GP104:1;				// IO_1: P04
      unsigned GP105:1;				// IO_1: P05
      unsigned GP106:1;				// IO_1: P06
      unsigned GP107:1;				// IO_1: P07
      unsigned GP110:1;				// IO_1: P10
      unsigned GP111:1;				// IO_1: P11
      unsigned GP112:1;				// IO_1: P12
      unsigned GP113:1;				// IO_1: P13
      unsigned GP114:1;				// IO_1: P14
      unsigned GP115:1;				// IO_1: P15
      unsigned GP116:1;				// IO_1: P16
      unsigned GP117:1;				// IO_1: P17
    };
} ioexp_1_t;

ioexp_1_t io1config;
ioexp_1_t io1invrt;
ioexp_1_t io1ins;
ioexp_1_t io1outs;

// I2C I/O Expander 2 5V (IC13: PCA9535):
#define IO_2				2
typedef union {
  unsigned int port;
    struct {
      unsigned P00:1;				// P00
      unsigned P01:1;				// P01
      unsigned P02:1;				// P02
      unsigned P03:1;				// P03
      unsigned P04:1;				// P04
      unsigned P05:1;				// P05
      unsigned P06:1;				// P06
      unsigned P07:1;				// P07
      unsigned P10:1;				// P10
      unsigned P11:1;				// P11
      unsigned P12:1;				// P12
      unsigned P13:1;				// P13
      unsigned P14:1;				// P14
      unsigned P15:1;				// P15
      unsigned P16:1;				// P16
      unsigned P17:1;				// P17
    };
    struct {
      unsigned GP200:1;				// IO_2: P00
      unsigned GP201:1;				// IO_2: P01
      unsigned GP202:1;				// IO_2: P02
      unsigned GP203:1;				// IO_2: P03
      unsigned GP204:1;				// IO_2: P04
      unsigned GP205:1;				// IO_2: P05
      unsigned GP206:1;				// IO_2: P06
      unsigned GP207:1;				// IO_2: P07
      unsigned GP210:1;				// IO_2: P10
      unsigned GP211:1;				// IO_2: P11
      unsigned GP212:1;				// IO_2: P12
      unsigned GP213:1;				// IO_2: P13
      unsigned GP214:1;				// IO_2: P14
      unsigned GP215:1;				// IO_2: P15
      unsigned GP216:1;				// IO_2: P16
      unsigned GP217:1;				// IO_2: P17
    };
    struct {
      unsigned ARD_D0:1;			// ARD: D0
      unsigned ARD_D1:1;			// ARD: D1
      unsigned ARD_D2:1;			// ARD: D2
      unsigned ARD_D3:1;			// ARD: D3
      unsigned ARD_D4:1;			// ARD: D4
      unsigned ARD_D5:1;			// ARD: D5
      unsigned ARD_D6:1;			// ARD: D6
      unsigned ARD_D7:1;			// ARD: D7
      unsigned ARD_D13:1;			// ARD: D13
      unsigned ARD_D12:1;			// ARD: D12
      unsigned ARD_D11:1;			// ARD: D11
      unsigned ARD_D10:1;			// ARD: D10
      unsigned ARD_D9:1;			// ARD: D9
      unsigned ARD_D8:1;			// ARD: D8
      unsigned unusedGP216:1;			// unused
      unsigned unusedGP217:1;			// unused
   };
} ioexp_2_t;

ioexp_2_t io2config;
ioexp_2_t io2invrt;
ioexp_2_t io2ins;
ioexp_2_t io2outs;

// I2C I/O Expander 3 3V3 (IC12: PCA9535):
#define IO_3				3
typedef union {
  unsigned int port;
    struct {
      unsigned P00:1;				// P00
      unsigned P01:1;				// P01
      unsigned P02:1;				// P02
      unsigned P03:1;				// P03
      unsigned P04:1;				// P04
      unsigned P05:1;				// P05
      unsigned P06:1;				// P06
      unsigned P07:1;				// P07
      unsigned P10:1;				// P10
      unsigned P11:1;				// P11
      unsigned P12:1;				// P12
      unsigned P13:1;				// P13
      unsigned P14:1;				// P14
      unsigned P15:1;				// P15
      unsigned P16:1;				// P16
      unsigned P17:1;				// P17
    };
    struct {
      unsigned GP300:1;				// IO_3: P00
      unsigned GP301:1;				// IO_3: P01
      unsigned GP302:1;				// IO_3: P02
      unsigned GP303:1;				// IO_3: P03
      unsigned GP304:1;				// IO_3: P04
      unsigned GP305:1;				// IO_3: P05
      unsigned GP306:1;				// IO_3: P06
      unsigned GP307:1;				// IO_3: P07
      unsigned GP310:1;				// IO_3: P10
      unsigned GP311:1;				// IO_3: P11
      unsigned GP312:1;				// IO_3: P12
      unsigned GP313:1;				// IO_3: P13
      unsigned GP314:1;				// IO_3: P14
      unsigned GP315:1;				// IO_3: P15
      unsigned GP316:1;				// IO_3: P16
      unsigned GP317:1;				// IO_3: P17
    };
} ioexp_3_t;

ioexp_3_t io3config;
ioexp_3_t io3invrt;
ioexp_3_t io3ins;
ioexp_3_t io3outs;

// I2C I/O Expander (PCA9535) general functions:
void config_IO(byte, unsigned int);
void update_IO(byte);
void set_IO(byte, unsigned int);
void invert_IO(byte, unsigned int);
void read_IO(byte);
#define readAllArduIO_IOs() {read_IO(1);read_IO(2);read_IO(3);}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// I2C A/D and D/A Converter (PCF8591):

#define READ_ADCUB	// If defined: Function read_AD(1) will also
			//  (default)  read the UB voltage ADC value (adcub) and
			//             will update the UB voltage low condition
			//             flag (status.ubatLow)!
			// If NOT defined: The UB voltage ADC value can be found
			//                 in the variable ad1ins.ArduIO_UB after
			//                 execution of read_AD(1)!
			// READ_ADCUB should NOT be defined, if jumper JP_AD-UB
			// on the ArduIO Board is OPEN!

// Control Byte bitmasks:
#define PCF8591_CONTROL_DEFAULT		0
#define PCF8591_CONTROL_ARDUIO		0b01000100	// Auto-increment & DAC

#define PCF8591_CONTROL_AUTO_INC	4		// Auto-increment
#define PCF8591_CONTROL_DAC_ENABLE	64		// DAC enable

// I2C A/D and D/A Converter 1 (IC11: PCF8591):
#define ADDA_1				1
typedef union {
  struct {
    byte AIN0;					// AIN0
    byte AIN1;					// AIN1
    byte AIN2;					// AIN2
    byte AIN3;					// AIN3
  };
  struct {
    byte AD10;					// ADDA_1: AIN0
    byte AD11;					// ADDA_1: AIN1
    byte AD12;					// ADDA_1: AIN2
    byte AD13;					// ADDA_1: AIN3
  };
  struct {
    byte unusedAD10;				// unused
    byte unusedAD11;				// unused
    byte unusedAD12;				// unused
    byte ArduIO_UB;				// ArduIO: UB
  };
} addaexp_1_t;

addaexp_1_t ad1ins;

// I2C A/D and D/A Converter 2 (IC10: PCF8591):
#define ADDA_2				2
typedef union {
  struct {
    byte AIN0;					// AIN0
    byte AIN1;					// AIN1
    byte AIN2;					// AIN2
    byte AIN3;					// AIN3
  };
  struct {
    byte AD20;					// ADDA_2: AIN0
    byte AD21;					// ADDA_2: AIN1
    byte AD22;					// ADDA_2: AIN2
    byte AD23;					// ADDA_2: AIN3
  };
} addaexp_2_t;

addaexp_2_t ad2ins;

// I2C A/D and D/A Converter 3 (IC9: PCF8591):
#define ADDA_3				3
typedef union {
  struct {
    byte AIN0;					// AIN0
    byte AIN1;					// AIN1
    byte AIN2;					// AIN2
    byte AIN3;					// AIN3
  };
  struct {
    byte AD30;					// ADDA_3: AIN0
    byte AD31;					// ADDA_3: AIN1
    byte AD32;					// ADDA_3: AIN2
    byte AD33;					// ADDA_3: AIN3
  };
  struct {
    byte ARD_A0;				// ARD: A0
    byte ARD_A1;				// ARD: A1
    byte ARD_A2;				// ARD: A2
    byte ARD_A3;				// ARD: A3
  };
} addaexp_3_t;

addaexp_3_t ad3ins;

// I2C A/D and D/A Converter (PCF8591) general functions:
#define UCV_AD(__AD__) (unsigned int)(__AD__*500.0f/255.0f)

void read_AD(byte);
#define readAllArduIO_ADs() {read_AD(1);read_AD(2);read_AD(3);}

#define AOUT_CV(__CV__) (byte)(__CV__*0.51f)

byte da1aout;
byte da2aout;
byte da3aout;

void write_DA(byte, byte);
void disable_DA(byte);
#define disableAllArduIO_DAs() {disable_DA(1);disable_DA(2);disable_DA(3);}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// UB Voltage Sensor:

byte adcub;
double ubv;

byte getUbSensor(void);
double calculateUb(void);
double measureUb(void);

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

// ------------------------------------------------------------------
// Duty cycle constants:
#define DUTY_0				0	// 0%
#define DUTY_10				409	// 10%
#define DUTY_25				1023	// 25%
#define DUTY_50				2047	// 50%
#define DUTY_75				3071	// 75%
#define DUTY_90				3685	// 90%
#define DUTY_100			4095	// 100%
// Relative duty cycle [__PCT__ = 0..100%] macro:
#define DUTY_PCT(__PCT__) (unsigned int)((unsigned long)__PCT__*4095/100)
// ------------------------------------------------------------------

void setLEDs(byte);

void dimLED(byte, unsigned int);
void setLED1(byte);
void setLED2(byte);
void setLED3(byte);
void setLED4(byte);

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// PWM Ports:

void setPWMs(byte);

void dimPWM(byte, unsigned int);
void setPWM1(byte);
void setPWM2(byte);
void setPWM3(byte);
void setPWM4(byte);

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Power PWM Ports & H-Bridges:

// Power PWM Ports:
void setPowerPWMMode(void);
void setPowerPWMs(byte);

void dimPowerPWM(byte, unsigned int);
void setPowerPWM1(byte);
void setPowerPWM2(byte);
void setPowerPWM3(byte);
void setPowerPWM4(byte);
void setPowerPWM5(byte);
void setPowerPWM6(byte);
void setPowerPWM7(byte);
void setPowerPWM8(byte);

// H-Bridges:

// ------------------------------------------------------------
// Direction/command:
#define FWD			0		// Forwards
#define BWD			1		// Backwards
#define BRK			4		// Speed break
#define OFF			5		// Power OFF
// ------------------------------------------------------------

void adjustPowerHB(byte hb, byte dir, unsigned int duty);

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// ArduIO Board system control routine:

void readSystem(void);

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// ArduIO Board initialisation and shutdown:

void init(void);
void shutdown(void);

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Arduino Uno Expander functions:

void updateArduino_Uno_Exp_IO(void);
void setArduino_Uno_Exp_IO(unsigned int);
// ArduIO Board Arduino Uno Expander control routine:
void readArduino_Uno_Exp(void);

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Class private section and end:

private:

status_t RP6ArduIOstatus;	// ArduIO status bits (lib internal)

};

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/

#endif

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
 ~ Additional info
 ~ ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
 ~ Changelog:
 ~
 ~  ---> changes are documented in the file "RP6_ArduIO.cpp"
 ~
 ~ ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
 */

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
Library Source

Datei RP6_ArduIO.cpp:

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*                                               ___   ___                   */
/*                 _______________________      /   \ /   \                  */
/*                 \| RP6  ROBOT SYSTEM |/     (  -  X  +  )                 */
/*                  \_-_-_-_-_-_-_-_-_-_/       \___/ \___/                  */
/*                                                ARDUINO                    */
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*------------------------------ [c]2014 - Dirk -----------------------------*/
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*~
 ~ Target:    Arduino UNO with RP6 ArduIO Board (Shield)
 ~ Library:   RP6_ArduIO Source
 ~ Version:   1.0
 ~ Author(s): Dirk
 ~
 ~ Description:
 ~ This is our new Library that contains basic routines and functions for
 ~ accessing the hardwired components of the RP6 ArduIO Board.
 ~ If you want to use the mentioned MACROS in your program, you have to
 ~ include the RP6_ArduIO Defines Header (RP6_ArduIO_Defines.h)!
 */
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// ArduIO hardwired components:
// - I2C PWM Controller (IC3: PCA9685)
// - I2C I/O Expander 1 5V (IC8: PCA9535)
// - I2C I/O Expander 2 5V (IC13: PCA9535)
// - I2C I/O Expander 3 3V3 (IC12: PCA9535)
// - I2C A/D and D/A Converter 1 (IC11: PCF8591)
// - I2C A/D and D/A Converter 2 (IC10: PCF8591)
// - I2C A/D and D/A Converter 3 (IC9: PCF8591)
// - UB Voltage Sensor
// - LEDs
// - PWM Ports
// - Power PWM Ports & H-Bridges

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Includes:
#include "RP6_ArduIO.h"
#include <Wire.h>

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Variables:
byte registerBuf; 

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Constructor:
RP6_ArduIO::RP6_ArduIO()
{}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// ArduIO Status:

/*~
 ~ Enable access to a H-Bridge [1 or 2].
 ~
 ~ HB1: Power PWM group 1 (power PWM numbers 1..4)
 ~ HB2: Power PWM group 2 (power PWM numbers 5..8)
 ~
 ~ Input: hb -> H-Bridge (HB) number [1 or 2]
 ~
 ~ There is also a macro enableHBx(),
 ~ which does exactly the same as this function,
 ~ where x = H-Bridge number = [1 or 2].
 ~ There is a macro isHBxEnable(), that may be
 ~ used to read the HBx access status.
 ~
 ~ Hints: - If you ENABLE access to a H-Bridge,
 ~          access to the corresponding power
 ~          PWM group will be DISABLED!
 ~        - In order to use H-Bridge 1, you have
 ~          to connect pins 3-4 and 5-6 of the
 ~          SV_H-BRIDGES plug on the ArduIO
 ~          Board!
 ~        - Motor 1 connection schematic:
 ~           Pins      Motor 1      pins
 ~           ---------------------------
 ~            3-4  ->  +     -  <-  5-6
 ~        - In order to use H-Bridge 2, you have
 ~          to connect pins 7-8 and 9-10 of the
 ~          SV_H-BRIDGES plug on the ArduIO
 ~          Board!
 ~        - Motor 2 connection schematic:
 ~           Pins      Motor 2      pins
 ~           ---------------------------
 ~            7-8  ->  +     -  <-  9-10
 ~
 ~ Example:
 ~   enableHB1();   // Or enableHB(1);
 ~   // this enables access to H-Bridge 1!
 ~
 */
void RP6_ArduIO::enableHB(byte hb)
{
  if (hb == 1) {
    RP6ArduIOstatus.ppwm_g1Enable = false;
    RP6ArduIOstatus.hb1Enable = true;
  }
  if (hb == 2) {
    RP6ArduIOstatus.ppwm_g2Enable = false;
    RP6ArduIOstatus.hb2Enable = true;
  }
  status.bits = RP6ArduIOstatus.bits;
}

/*~
 ~ Disable access to a H-Bridge [1 or 2]
 ~ (default).
 ~
 ~ Input: hb -> H-Bridge (HB) number [1 or 2]
 ~
 ~ Example:
 ~   disableHB2();   // Or disableHB(2);
 ~   // this disables access to H-Bridge 2!
 ~
 */
void RP6_ArduIO::disableHB(byte hb)
{
  if (hb == 1) RP6ArduIOstatus.hb1Enable = false;
  if (hb == 2) RP6ArduIOstatus.hb2Enable = false;
  status.bits = RP6ArduIOstatus.bits;
}

/*~
 ~ Enable access to a power PWM group [1 or 2]
 ~ (default).
 ~
 ~ Power PWM group 1: HB1 (power PWM numbers 1..4)
 ~ Power PWM group 2: HB2 (power PWM numbers 5..8)
 ~
 ~ Input: ppwm_g -> Power PWM group [1 or 2]
 ~
 ~ There is also a macro enablePPWM_Gx(),
 ~ which does exactly the same as this function,
 ~ where x = Power PWM group = [1 or 2].
 ~ There is a macro isPPWM_GxEnable(), that may
 ~ be used to read the power PWM group x access
 ~ status.
 ~
 ~ Hints: - If you ENABLE access to a power PWM
 ~          group, access to the corresponding
 ~          H-Bridge will be DISABLED!
 ~        - ! IF  YOU  WANT  TO  USE  POWER  PWM !
 ~          ! NUMBERS  1..4  (POWER PWM GROUP 1) !
 ~          ! AS 4 SINGLE POWER PWM OUTPUTS, YOU !
 ~          ! HAVE TO ENSURE,  THAT PINS 3-4 AND !
 ~          ! 5-6  OF SV_H-BRIDGES PLUG ARE  NOT !
 ~          ! CONNECTED!!!  YOU MAY  DAMAGE  THE !
 ~          ! ARDUIO  BOARD,  IF THESE PINS  ARE !
 ~          ! CONNECTED!!!                       !
 ~        - ! IF  YOU  WANT  TO  USE  POWER  PWM !
 ~          ! NUMBERS  5..8  (POWER PWM GROUP 2) !
 ~          ! AS 4 SINGLE POWER PWM OUTPUTS, YOU !
 ~          ! HAVE TO ENSURE,  THAT PINS 7-8 AND !
 ~          ! 9-10 OF SV_H-BRIDGES PLUG ARE  NOT !
 ~          ! CONNECTED!!!  YOU MAY  DAMAGE  THE !
 ~          ! ARDUIO  BOARD,  IF THESE PINS  ARE !
 ~          ! CONNECTED!!!                       !
 ~
 ~ Example:
 ~   enablePPWM_G1();   // Or enablePPWM_G(1);
 ~   // this enables access to power PWM group 1
 ~   // (power PWM numbers 1..4)!
 ~
 */
void RP6_ArduIO::enablePPWM_G(byte ppwm_g)
{
  if (ppwm_g == 1) {
    RP6ArduIOstatus.hb1Enable = false;
    RP6ArduIOstatus.ppwm_g1Enable = true;
  }
  if (ppwm_g == 2) {
    RP6ArduIOstatus.hb2Enable = false;
    RP6ArduIOstatus.ppwm_g2Enable = true;
  }
  status.bits = RP6ArduIOstatus.bits;
}

/*~
 ~ Disable access to a power PWM group [1 or 2].
 ~
 ~ Input: ppwm_g -> Power PWM group [1 or 2]
 ~
 ~ Example:
 ~   disablePPWM_G2();   // Or disablePPWM_G(2);
 ~   // this disables access to power PWM group 2
 ~   // (power PWM numbers 5..8)!
 ~
 */
void RP6_ArduIO::disablePPWM_G(byte ppwm_g)
{
  if (ppwm_g == 1) RP6ArduIOstatus.ppwm_g1Enable = false;
  if (ppwm_g == 2) RP6ArduIOstatus.ppwm_g2Enable = false;
  status.bits = RP6ArduIOstatus.bits;
}

/*~
 ~ Enable access to the 4 free PWMs (default).
 ~ There is a macro isPWMsEnable(), that may be
 ~ used to read the PWMs access status.
 ~
 */
void RP6_ArduIO::enablePWMs(void)
{
  RP6ArduIOstatus.pwmsEnable = true;
  status.bits = RP6ArduIOstatus.bits;
}

/*~
 ~ Disable access to the 4 free PWMs.
 ~
 */
void RP6_ArduIO::disablePWMs(void)
{
  RP6ArduIOstatus.pwmsEnable = false;
  status.bits = RP6ArduIOstatus.bits;
}

/*~
 ~ Enable access to all IO_1..3 IO ports to be
 ~ used as outputs (Outs) (default).
 ~ There is a macro isOutsEnable(), that may be
 ~ used to read the Outs access status.
 ~
 */
void RP6_ArduIO::enableOuts(void)
{
  RP6ArduIOstatus.outsEnable = true;
  status.bits = RP6ArduIOstatus.bits;
}

/*~
 ~ Disable access to all IO_1..3 IO ports to be
 ~ used as outputs (Outs).
 ~
 ~ Hint: The IO_1..3 IO ports can ALWAYS be used
 ~       as inputs (Ins)!
 ~
 */
void RP6_ArduIO::disableOuts(void)
{
  RP6ArduIOstatus.outsEnable = false;
  status.bits = RP6ArduIOstatus.bits;
}

/*~
 ~ Enable access to all ADDA_1..3 DACs (default).
 ~ There is a macro isDAsEnable(), that may be
 ~ used to read the DACs access status.
 ~
 */
void RP6_ArduIO::enableDAs(void)
{
  RP6ArduIOstatus.dasEnable = true;
  status.bits = RP6ArduIOstatus.bits;
}

/*~
 ~ Disable access to all ADDA_1..3 DACs.
 ~
 ~ Hint: The 3 DAC outputs (AOUT) are NOT
 ~       disabled by this function! Pls. use
 ~       macro disableAllArduIO_DAs() for this!
 ~
 */
void RP6_ArduIO::disableDAs(void)
{
  RP6ArduIOstatus.dasEnable = false;
  status.bits = RP6ArduIOstatus.bits;
}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// I2C PWM Controller (PCA9685):

/*~
 ~ Call this once before using the PWM function.
 ~
 ~ Input: PWM frequency [40..1000 Hz]
 ~
 ~ There is also a macro initPWM(freq), which
 ~ does exactly the same as this function.
 ~
 ~ Example:
 ~   initPWM(1000);   // Or PCA9685_init(1000);
 ~
 */
void RP6_ArduIO::PCA9685_init(unsigned int freq)
{
  byte last_mode;
  if ((freq < 40) || (freq > 1000)) freq = 1000;
  Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
  Wire.write(PCA9685_MODE2);
  Wire.endTransmission();
  Wire.requestFrom(I2C_ARDUIO_PWM_ADR, 1);
  if (Wire.available()) last_mode = Wire.read();
  last_mode |= PCA9685_MODE2_INVRT;			// Set INVRT bit
  last_mode &= ~PCA9685_MODE2_OUTDRV;			// Clear OUTDRV bit
  Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
  Wire.write(PCA9685_MODE2);
  Wire.write(last_mode);
  Wire.endTransmission();
  Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
  Wire.write(PCA9685_MODE1);
  Wire.endTransmission();
  Wire.requestFrom(I2C_ARDUIO_PWM_ADR, 1);
  if (Wire.available()) last_mode = Wire.read();
  last_mode |= PCA9685_MODE1_AI;			// Set AI bit
  byte mode1 = last_mode;
  mode1 |= PCA9685_MODE1_SLEEP;				// Set SLEEP bit
  Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
  Wire.write(PCA9685_MODE1);
  Wire.write(mode1);
  Wire.endTransmission();
  byte prescale = (byte) (F_PCA9685 / 4096 / freq - 0.5);
  Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
  Wire.write(PCA9685_PRE_SCALE);
  Wire.write(prescale);
  Wire.endTransmission();
  last_mode &= ~PCA9685_MODE1_SLEEP;			// Clear SLEEP bit
  Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
  Wire.write(PCA9685_MODE1);
  Wire.write(last_mode);
  Wire.endTransmission();
  delay(1);
  last_mode |= PCA9685_MODE1_RESTART;			// Clear RESTART bit
  Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
  Wire.write(PCA9685_MODE1);
  Wire.write(last_mode);
  Wire.endTransmission();
}

/*~
 ~ This is the PWM duty set function.
 ~
 ~ Input: channel -> Channel number [1..16]
 ~                   0 = ALL 16 channels
 ~        duty    -> Duty cycle [0..4095]
 ~
 ~ There is also a macro setPWM(channel, duty),
 ~ which does exactly the same as this function.
 ~
 ~ Example:
 ~   setPWM(2,300);   // Or PCA9685_set(2,300);
 ~   // this sets channel 2 with a duty cycle
 ~   // value of 300 (about 7.33%).
 ~
 */
void RP6_ArduIO::PCA9685_set(byte channel, unsigned int duty)
{
  if (channel > 16) return;
  if (duty > 4095) duty = 4095;
  byte reg = channel * 4 + 4;      // Register LEDx_OFF_L
  if (!channel) reg = PCA9685_ALL_LED_OFF_L;      // Register ALL_LED_OFF_L
  Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
  Wire.write(reg);
  Wire.write(duty & 0x00ff);
  Wire.write(duty >> 8);
  Wire.endTransmission();
}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// I2C I/O Expander (PCA9535):

/*~
 ~ Configurate the portpins of an IO_x port as
 ~ input or output. This port configuration is
 ~ stored in the global ioxconfig variable, where
 ~ x = IO-Expander number = [1..3].
 ~
 ~ Input: io    -> IO-Expander number [1..3]
 ~        inout -> Config value (16 bit):
 ~                  Bit 0 = output
 ~                  Bit 1 = input
 ~
 ~ There is also a macro config_IOx(inout),
 ~ which does exactly the same as this function,
 ~ where x = IO-Expander number = [1..3].
 ~
 ~ Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 ~       ! THE ACCESS IS ENABLED (default): !
 ~       !   ==> enableOuts(); <==          !
 ~
 ~ Example:
 ~   config_IO(IO_1,0b0000000000101001);
 ~   // this configures the IO_1 portpins P00,
 ~   // P03 and P05 as INPUTs and all other
 ~   // portpins as OUTPUTs!
 ~   config_IO1(0b0000000000101001);
 ~   // does exactly the same!
 ~
 */
void RP6_ArduIO::config_IO(byte io, unsigned int inout)
{
  if (RP6ArduIOstatus.outsEnable || (inout == 0xffff)) {
    switch (io) {					// IO-Expander number:
      case IO_1 :					//  IO_1
        Wire.beginTransmission(I2C_ARDUIO_IO_1_ADR);
        Wire.write(PCA9535_CONFIG_P0);
        Wire.write(inout & 0x00ff);
        Wire.write(inout >> 8);
        Wire.endTransmission();
        io1config.port = inout;
        break;
      case IO_2 :					//  IO_2
        Wire.beginTransmission(I2C_ARDUIO_IO_2_ADR);
        Wire.write(PCA9535_CONFIG_P0);
        Wire.write(inout & 0x00ff);
        Wire.write(inout >> 8);
        Wire.endTransmission();
        io2config.port = inout;
        break;
      case IO_3 :					//  IO_3
        Wire.beginTransmission(I2C_ARDUIO_IO_3_ADR);
        Wire.write(PCA9535_CONFIG_P0);
        Wire.write(inout & 0x00ff);
        Wire.write(inout >> 8);
        Wire.endTransmission();
        io3config.port = inout;
    }
  }
}

/*~
 ~ Update an IO_x port with current value from
 ~ the global ioxouts variable, where x = IO-
 ~ Expander number = [1..3].
 ~ The 16 IO_x portpins will be SET (high, ON)
 ~ or CLEARED (low, OFF).
 ~
 ~ Input: io  -> IO-Expander number [1..3]
 ~
 ~ There is also a macro update_IOx(),
 ~ which does exactly the same as this function,
 ~ where x = IO-Expander number = [1..3].
 ~
 ~ Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 ~       ! THE ACCESS IS ENABLED (default): !
 ~       !   ==> enableOuts(); <==          !
 ~
 ~ Examples:
 ~   io1outs.port = 0b0000000000101001;
 ~   update_IO1();
 ~   // this CLEARs the port and SETs the
 ~   // IO_1 portpins P00, P03 and P05!
 ~
 ~   // Other possibility:
 ~   io3outs.GP316 = true;   // Or io3outs.P16 = true;
 ~   update_IO(IO_3);
 ~   // this SETs the IO_3 portpin P16 and
 ~   // does not affect any other portpin!
 ~
 */
void RP6_ArduIO::update_IO(byte io)
{
  if (RP6ArduIOstatus.outsEnable) {
    switch (io) {					// IO-Expander number:
      case IO_1 :					//  IO_1
        Wire.beginTransmission(I2C_ARDUIO_IO_1_ADR);
        Wire.write(PCA9535_OUTPUT_P0);
        Wire.write(io1outs.port & 0x00ff);
        Wire.write(io1outs.port >> 8);
        Wire.endTransmission();
        break;
      case IO_2 :					//  IO_2
        Wire.beginTransmission(I2C_ARDUIO_IO_2_ADR);
        Wire.write(PCA9535_OUTPUT_P0);
        Wire.write(io2outs.port & 0x00ff);
        Wire.write(io2outs.port >> 8);
        Wire.endTransmission();
        break;
      case IO_3 :					//  IO_3
        Wire.beginTransmission(I2C_ARDUIO_IO_3_ADR);
        Wire.write(PCA9535_OUTPUT_P0);
        Wire.write(io3outs.port & 0x00ff);
        Wire.write(io3outs.port >> 8);
        Wire.endTransmission();
    }
  }
}

/*~
 ~ This function SETs (high, ON) or CLEARs
 ~ (low, OFF) the 16 IO_x portpins, where
 ~ x = IO-Expander number = [1..3].
 ~
 ~ Input: io  -> IO-Expander number [1..3]
 ~        out -> Output value (16 bit)
 ~
 ~ There is also a macro set_IOx(out),
 ~ which does exactly the same as this function,
 ~ where x = IO-Expander number = [1..3].
 ~
 ~ Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 ~       ! THE ACCESS IS ENABLED (default): !
 ~       !   ==> enableOuts(); <==          !
 ~
 ~ Example:
 ~   set_IO(IO_1,0b0000000000101001);
 ~   // this CLEARs the port and SETs the
 ~   // IO_1 portpins P00, P03 and P05!
 ~   set_IO1(0b0000000000101001);
 ~   // does exactly the same!
 ~
 */
void RP6_ArduIO::set_IO(byte io, unsigned int out)
{
  if (RP6ArduIOstatus.outsEnable) {
    switch (io) {					// IO-Expander number:
      case IO_1 :					//  IO_1
        io1outs.port = out;
        update_IO(IO_1);
        break;
      case IO_2 :					//  IO_2
        io2outs.port = out;
        update_IO(IO_2);
        break;
      case IO_3 :					//  IO_3
        io3outs.port = out;
        update_IO(IO_3);
    }
  }
}

/*~
 ~ Invert the input values of the portpins of an
 ~ IO_x port. This port setting is stored in the
 ~ global ioxinvrt variable, where x = IO-
 ~ Expander number = [1..3].
 ~
 ~ Input: io    -> IO-Expander number [1..3]
 ~        invrt -> Setting value (16 bit):
 ~                  Bit 0 = retain
 ~                  Bit 1 = invert
 ~
 ~ There is also a macro invert_IOx(invrt),
 ~ which does exactly the same as this function,
 ~ where x = IO-Expander number = [1..3].
 ~
 ~ Example:
 ~   invert_IO(IO_1,0b0000000000101001);
 ~   // this inverts the input values of the IO_1
 ~   // portpins P00, P03 and P05 and retains the
 ~   // input values of all other portpins!
 ~   invert_IO1(0b0000000000101001);
 ~   // does exactly the same!
 ~
 */
void RP6_ArduIO::invert_IO(byte io, unsigned int invrt)
{
  switch (io) {						// IO-Expander number:
    case IO_1 :						//  IO_1
      Wire.beginTransmission(I2C_ARDUIO_IO_1_ADR);
      Wire.write(PCA9535_POL_INV_P0);
      Wire.write(invrt & 0x00ff);
      Wire.write(invrt >> 8);
      Wire.endTransmission();
      io1invrt.port = invrt;
      break;
    case IO_2 :						//  IO_2
      Wire.beginTransmission(I2C_ARDUIO_IO_2_ADR);
      Wire.write(PCA9535_POL_INV_P0);
      Wire.write(invrt & 0x00ff);
      Wire.write(invrt >> 8);
      Wire.endTransmission();
      io2invrt.port = invrt;
      break;
    case IO_3 :						//  IO_3
      Wire.beginTransmission(I2C_ARDUIO_IO_3_ADR);
      Wire.write(PCA9535_POL_INV_P0);
      Wire.write(invrt & 0x00ff);
      Wire.write(invrt >> 8);
      Wire.endTransmission();
      io3invrt.port = invrt;
  }
}

/*~
 ~ This function checks an IO_x port with it's
 ~ 16 pins (P00..P17), where x = IO-Expander
 ~ number = [1..3]!
 ~ You may call this function frequently
 ~ out of the main loop.
 ~ The input values (true/false, high/low) of the
 ~ portpins are read into the global ioxins
 ~ variable.
 ~
 ~ Input: io  -> IO-Expander number [1..3]
 ~
 ~ There is also a macro read_IOx(),
 ~ which does exactly the same as this function,
 ~ where x = IO-Expander number = [1..3].
 ~ The macro readAll_IOs() reads the
 ~ portpins (P00..P17) of ALL 3 IO-Expanders.
 ~
 ~ Hint: The portpin input values can be
 ~       inverted with the function
 ~       invert_IO(io,invrt)!
 ~
 ~ Examples:
 ~   read_IO(IO_1);
 ~   if (io1ins.GP101) Serial.println("IO_1:P01 = High");
 ~   else Serial.println("IO_1:P01 = Low");
 ~   read_IO2();
 ~   if (!io2ins.GP214) Serial.println("IO_2:P14 = Low");
 ~
 */
void RP6_ArduIO::read_IO(byte io)
{
  switch (io) {						// IO-Expander number:
    case IO_1 :						//  IO_1
      Wire.beginTransmission(I2C_ARDUIO_IO_1_ADR);
      Wire.write(PCA9535_INPUT_P0);
      Wire.endTransmission();
      Wire.requestFrom(I2C_ARDUIO_IO_1_ADR, 2);      // request 2 bytes
      if (2 <= Wire.available()) {      // two bytes to be received
        registerBuf = Wire.read();      // receive low byte
        io1ins.port = registerBuf;
        registerBuf = Wire.read();      // receive high byte
        io1ins.port |= (registerBuf << 8);
      }
      break;
    case IO_2 :						//  IO_2
      Wire.beginTransmission(I2C_ARDUIO_IO_2_ADR);
      Wire.write(PCA9535_INPUT_P0);
      Wire.endTransmission();
      Wire.requestFrom(I2C_ARDUIO_IO_2_ADR, 2);
      if (2 <= Wire.available()) {
        registerBuf = Wire.read();
        io2ins.port = registerBuf;
        registerBuf = Wire.read();
        io2ins.port |= (registerBuf << 8);
      }
      break;
    case IO_3 :						//  IO_3
      Wire.beginTransmission(I2C_ARDUIO_IO_3_ADR);
      Wire.write(PCA9535_INPUT_P0);
      Wire.endTransmission();
      Wire.requestFrom(I2C_ARDUIO_IO_3_ADR, 2);
      if (2 <= Wire.available()) {
        registerBuf = Wire.read();
        io3ins.port = registerBuf;
        registerBuf = Wire.read();
        io3ins.port |= (registerBuf << 8);
      }
  }
}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// I2C A/D and D/A Converter (PCF8591):

/*~
 ~ This function reads the 3 ADDA_x ADC ports
 ~ (AIN0..AIN3), where x = AD/DA-Expander number
 ~ = [1..3]!
 ~ You may call this function frequently
 ~ out of the main loop.
 ~ The AIN0..AIN3 ADC values [0..255] are read
 ~ into the global adxins struct:
 ~   byte adxins.ADxy, where y = ADC channel
 ~   (AIN0..3) number of ADDA_x = [0..3]
 ~
 ~ Input: ad  -> AD/DA-Expander number [1..3]
 ~
 ~ There is also a macro read_ADx(),
 ~ which does exactly the same as this function,
 ~ where x = AD/DA-Expander number = [1..3].
 ~ The macro readAll_ADs() reads the
 ~ ADC ports (AIN0..AIN3) of ALL 3 AD/DA-
 ~ Expanders.
 ~
 ~ Hint only for ad == 1 (ADDA_1):
 ~       If READ_ADCUB is defined, the variable
 ~       adcub is filled with the UB voltage ADC
 ~       value. Depending on adcub the UB voltage
 ~       low flag is SET/CLEARED in the ArduIO
 ~       status byte (status.ubatLow)!
 ~       There is also a macro isUbLow(), that
 ~       may be used instead of
 ~       status.ubatLow.
 ~
 ~ Examples:
 ~   read_AD(ADDA_1);
 ~   Serial.print("ADDA_1:AIN0 = ");
 ~   Serial.print(ad1ins.AD10, DEC);
 ~   Serial.println("");
 ~
 ~   read_AD2();
 ~   Serial.print("ADDA_2:AIN3 = ");
 ~   Serial.print(ad2ins.AD23, DEC);
 ~   Serial.print(" (U: ");
 ~   Serial.print(UCV_AD(ad2ins.AD23), DEC);
 ~   Serial.println("cV)"); // 100cV = 1V
 ~
 */
void RP6_ArduIO::read_AD(byte ad)
{
  switch (ad) {						// AD/DA-Expander number:
    case ADDA_1 :					//  ADDA_1
      Wire.beginTransmission(I2C_ARDUIO_AD_1_ADR);
      Wire.write(PCF8591_CONTROL_ARDUIO);
      Wire.endTransmission();
      Wire.requestFrom(I2C_ARDUIO_AD_1_ADR, 5);
      if (Wire.available()) Wire.read();
      if (4 <= Wire.available()) {
        ad1ins.AD10 = Wire.read();
        ad1ins.AD11 = Wire.read();
        ad1ins.AD12 = Wire.read();
        ad1ins.AD13 = Wire.read();
      }
#ifdef READ_ADCUB
      adcub = ad1ins.ArduIO_UB;				// = ad1ins.AD13
// Test for UB voltage low condition:
      if (adcub < ADCVAL_UB_LOW) RP6ArduIOstatus.ubatLow = true;
      else RP6ArduIOstatus.ubatLow = false;
      status.bits = RP6ArduIOstatus.bits;
#endif
      break;
    case ADDA_2 :					//  ADDA_2
      Wire.beginTransmission(I2C_ARDUIO_AD_2_ADR);
      Wire.write(PCF8591_CONTROL_ARDUIO);
      Wire.endTransmission();
      Wire.requestFrom(I2C_ARDUIO_AD_2_ADR, 5);
      if (Wire.available()) Wire.read();
      if (4 <= Wire.available()) {
        ad2ins.AD20 = Wire.read();
        ad2ins.AD21 = Wire.read();
        ad2ins.AD22 = Wire.read();
        ad2ins.AD23 = Wire.read();
      }
      break;
    case ADDA_3 :					//  ADDA_3
      Wire.beginTransmission(I2C_ARDUIO_AD_3_ADR);
      Wire.write(PCF8591_CONTROL_ARDUIO);
      Wire.endTransmission();
      Wire.requestFrom(I2C_ARDUIO_AD_3_ADR, 5);
      if (Wire.available()) Wire.read();
      if (4 <= Wire.available()) {
        ad3ins.AD30 = Wire.read();
        ad3ins.AD31 = Wire.read();
        ad3ins.AD32 = Wire.read();
        ad3ins.AD33 = Wire.read();
      }
  }
}

/*~
 ~ This function sends an 8 bit value (aout) to
 ~ one of the three DA converters on the ArduIO
 ~ Board. After this the analog voltage [0..5V]
 ~ can be measured at the DAC output pin (AOUT)
 ~ of the addressed AD/DA-Expander.
 ~ The value aout is also stored in daxaout.
 ~
 ~ Input: da   -> AD/DA-Expander number [1..3]
 ~        aout -> Output value (8 bit)
 ~
 ~ There is also a macro write_DAx(aout),
 ~ which does exactly the same as this function,
 ~ where x = AD/DA-Expander number = [1..3].
 ~
 ~ Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 ~       ! THE ACCESS IS ENABLED (default): !
 ~       !   ==> enableDAs(); <==           !
 ~
 ~ Example:
 ~   write_DA1(127);   // Or write_DA(1,127);
 ~   // this sends the value 127 to the DAC of
 ~   // AD/DA-Expander 1. This DAC now generates
 ~   // an output voltage (Vo) of 2.5V:
 ~   //   Vo [V] = aout * 5 / 255
 ~   // ... or 250cV (1cV = one-hundreth of 1V):
 ~   //   Vo [cV] = aout * 500 / 255
 ~   write_DA1(AOUT_CV(250)); // 250cV = 2.5V
 ~   // does exactly the same!
 ~
 */
void RP6_ArduIO::write_DA(byte da, byte aout)
{
  if (RP6ArduIOstatus.dasEnable) {
    switch (da) {					// AD/DA-Expander number:
      case ADDA_1 :					//  ADDA_1
        Wire.beginTransmission(I2C_ARDUIO_AD_1_ADR);
        Wire.write(PCF8591_CONTROL_DAC_ENABLE);
        Wire.write(aout);
        Wire.endTransmission();
        da1aout = aout;
        break;
      case ADDA_2 :					//  ADDA_2
        Wire.beginTransmission(I2C_ARDUIO_AD_2_ADR);
        Wire.write(PCF8591_CONTROL_DAC_ENABLE);
        Wire.write(aout);
        Wire.endTransmission();
        da2aout = aout;
        break;
      case ADDA_3 :					//  ADDA_3
        Wire.beginTransmission(I2C_ARDUIO_AD_3_ADR);
        Wire.write(PCF8591_CONTROL_DAC_ENABLE);
        Wire.write(aout);
        Wire.endTransmission();
        da3aout = aout;
    }
  }
}

/*~
 ~ This function disables the DAC output (AOUT)
 ~ of the addressed AD/DA-Expander (set PCF8591
 ~ default mode).
 ~
 ~ Input: da  -> AD/DA-Expander number [1..3]
 ~
 ~ There is also a macro disable_DAx(),
 ~ which does exactly the same as this function,
 ~ where x = AD/DA-Expander number = [1..3].
 ~ The macro disableAll_DAs() disables the
 ~ DAC outputs (AOUT) of ALL 3 AD/DA-Expanders.
 ~
 ~ Hints: - The function read_AD(ad)
 ~          ENABLES the DAC output (AOUT) of the
 ~          addressed AD/DA-Expander!
 ~        - Access to the 3 DACs is NOT disabled
 ~          by this function! Pls. use function
 ~          disableDAs() for this!
 ~
 */
void RP6_ArduIO::disable_DA(byte da)
{
  switch (da) {						// AD/DA-Expander number:
    case ADDA_1 :					//  ADDA_1
      Wire.beginTransmission(I2C_ARDUIO_AD_1_ADR);
      Wire.write(PCF8591_CONTROL_DEFAULT);
      Wire.endTransmission();
      break;
    case ADDA_2 :					//  ADDA_2
      Wire.beginTransmission(I2C_ARDUIO_AD_2_ADR);
      Wire.write(PCF8591_CONTROL_DEFAULT);
      Wire.endTransmission();
      break;
    case ADDA_3 :					//  ADDA_3
      Wire.beginTransmission(I2C_ARDUIO_AD_3_ADR);
      Wire.write(PCF8591_CONTROL_DEFAULT);
      Wire.endTransmission();
  }
}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// UB Voltage Sensor:

/*~
 ~ This function reads and returns the ADC value of
 ~ the UB voltage sensor. The value is also stored
 ~ in adcub. Depending on adcub the UB voltage low
 ~ flag is SET/CLEARED in the ArduIO status byte
 ~ (status.ubatLow)!
 ~ There is also a macro isUbLow(), that may be
 ~ used instead of status.ubatLow.
 ~
 ~ Hint: Jumper JP_AD-UB must be closed in order to
 ~       measure the UB voltage!
 ~
 */
byte RP6_ArduIO::getUbSensor(void)
{
  read_AD(1);
  adcub = ad1ins.ArduIO_UB;				// ADDA_1:AIN3
  // Test for UB voltage low condition:
  if (adcub < ADCVAL_UB_LOW) RP6ArduIOstatus.ubatLow = true;
  else RP6ArduIOstatus.ubatLow = false;
  status.bits = RP6ArduIOstatus.bits;
  return adcub;
}

/*~
 ~ Calculates and returns the UB voltage value
 ~ by using the data read from the UB voltage
 ~ sensor with the function getUbSensor().
 ~
 ~ Hint: The calculation assumes a reference
 ~       voltage of 5.0V and a voltage divider
 ~       100k/100k at the sensor input!
 ~
 */
double RP6_ArduIO::calculateUb(void)
{
  return (10.0f / 255.0f * adcub);
}

/*~
 ~ Measures and returns the UB voltage value [V].
 ~ The ADC value of the UB voltage sensor is also
 ~ stored in adcub. Depending on adcub the UB
 ~ voltage low flag is SET/CLEARED in the ArduIO
 ~ status byte (status.ubatLow)!
 ~ There is also a macro isUbLow(), that may be
 ~ used instead of status.ubatLow.
 ~
 ~ Hints: - Jumper JP_AD-UB must be closed in
 ~          order to measure the UB voltage!
 ~        - The calculation assumes a reference
 ~          voltage of 5.0V and a voltage
 ~          divider 100k/100k at the sensor
 ~          input!
 ~
 */
double RP6_ArduIO::measureUb(void)
{
  read_AD(1);
  adcub = ad1ins.ArduIO_UB;				// ADDA_1:AIN3
  // Test for UB voltage low condition:
  if (adcub < ADCVAL_UB_LOW) RP6ArduIOstatus.ubatLow = true;
  else RP6ArduIOstatus.ubatLow = false;
  status.bits = RP6ArduIOstatus.bits;
  return (10.0f / 255.0f * adcub);
}

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

/*~ 
 ~ Set the 4 status LEDs of the ArduIO.
 ~
 ~ Example:
 ~          setLEDs(0b1010);
 ~          // this CLEARs LEDs 1 and 3
 ~          // and SETs LEDs 2 and 4!
 ~
 */
void RP6_ArduIO::setLEDs(byte 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 ArduIO.
 ~
 ~ Input: led  -> LED number [1..4]
 ~        duty -> Duty cycle [0..4095] = [0..100%]
 ~
 ~ There is also a macro dimLEDx(duty),
 ~ which does exactly the same as this function,
 ~ where x = LED number = [1..4].
 ~
 ~ Example:
 ~   dimLED2(DUTY_50);   // Or dimLED(2,2047);
 ~   // this dims LED2 with a
 ~   // duty cycle of 50%!
 ~   dimLED2(DUTY_PCT(50));   // Or dimLED2(2047);
 ~   // does exactly the same!
 ~
 */
void RP6_ArduIO::dimLED(byte led, unsigned int 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 RP6_ArduIO::setLED1(byte 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 RP6_ArduIO::setLED2(byte 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 RP6_ArduIO::setLED3(byte 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 RP6_ArduIO::setLED4(byte led)
{
  if (led > 0) PCA9685_set(CHLED4, 4095); 
  else PCA9685_set(CHLED4, 0);
}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// PWM Ports:

/*~ 
 ~ Set the 4 free PWM ports of the ArduIO to ON or
 ~ OFF (set the MAX/MIN [100%/0%] PWM duty cycle).
 ~
 ~ Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 ~       ! THE ACCESS IS ENABLED (default): !
 ~       !   ==> enablePWMs(); <==          !
 ~
 ~ Example:
 ~          setPWMs(0b1010);
 ~          // this CLEARs PWMs 1 and 3 [0%]
 ~          // and SETs PWMs 2 and 4 [100%]!
 ~
 */
void RP6_ArduIO::setPWMs(byte pwms)
{
  if (RP6ArduIOstatus.pwmsEnable) {
    if (pwms & 0b00000001) PCA9685_set(CHPWM1, 4095);
    else PCA9685_set(CHPWM1, 0);
    if (pwms & 0b00000010) PCA9685_set(CHPWM2, 4095);
    else PCA9685_set(CHPWM2, 0);
    if (pwms & 0b00000100) PCA9685_set(CHPWM3, 4095);
    else PCA9685_set(CHPWM3, 0);
    if (pwms & 0b00001000) PCA9685_set(CHPWM4, 4095);
    else PCA9685_set(CHPWM4, 0);
  }
}

/*~ 
 ~ Dim the 4 free PWM ports of the ArduIO (set the
 ~ PWM duty cycle).
 ~
 ~ Input: pwm  -> PWM number [1..4]
 ~        duty -> Duty cycle [0..4095] = [0..100%]
 ~
 ~ There is also a macro dimPWMx(duty),
 ~ which does exactly the same as this function,
 ~ where x = PWM number = [1..4].
 ~
 ~ Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 ~       ! THE ACCESS IS ENABLED (default): !
 ~       !   ==> enablePWMs(); <==          !
 ~
 ~ Example:
 ~   dimPWM2(DUTY_50);   // Or dimPWM(2,2047);
 ~   // this dims PWM2 with a
 ~   // PWM duty cycle of 50%!
 ~   dimPWM2(DUTY_PCT(50));   // Or dimPWM2(2047);
 ~   // does exactly the same!
 ~
 */
void RP6_ArduIO::dimPWM(byte pwm, unsigned int duty)
{
  if (RP6ArduIOstatus.pwmsEnable) {
    if (pwm == 1) PCA9685_set(CHPWM1, duty);
    if (pwm == 2) PCA9685_set(CHPWM2, duty);
    if (pwm == 3) PCA9685_set(CHPWM3, duty);
    if (pwm == 4) PCA9685_set(CHPWM4, duty);
  }
}

/*~ 
 ~ Set ONLY PWM1, don't change anything for the other PWMs.
 ~
 ~ Input: pwm -> 0 (false) = PWM off [0%]
 ~               >0 (true) = PWM max. duty cycle [100%]
 ~
 ~ Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 ~       ! THE ACCESS IS ENABLED (default): !
 ~       !   ==> enablePWMs(); <==          !
 ~
 */
void RP6_ArduIO::setPWM1(byte pwm)
{
  if (RP6ArduIOstatus.pwmsEnable) {
    if (pwm > 0) PCA9685_set(CHPWM1, 4095); 
    else PCA9685_set(CHPWM1, 0);
  }
}	

/*~ 
 ~ Set ONLY PWM2, don't change anything for the other PWMs.
 */
void RP6_ArduIO::setPWM2(byte pwm)
{
  if (RP6ArduIOstatus.pwmsEnable) {
    if (pwm > 0) PCA9685_set(CHPWM2, 4095); 
    else PCA9685_set(CHPWM2, 0);
  }	
}	

/*~ 
 ~ Set ONLY PWM3, don't change anything for the other PWMs.
 */
void RP6_ArduIO::setPWM3(byte pwm)
{
  if (RP6ArduIOstatus.pwmsEnable) {
    if (pwm > 0) PCA9685_set(CHPWM3, 4095); 
    else PCA9685_set(CHPWM3, 0);	
  }
}	

/*~ 
 ~ Set ONLY PWM4, don't change anything for the other PWMs.
 */
void RP6_ArduIO::setPWM4(byte pwm)
{
  if (RP6ArduIOstatus.pwmsEnable) {
    if (pwm > 0) PCA9685_set(CHPWM4, 4095); 
    else PCA9685_set(CHPWM4, 0);	
  }
}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Power PWM Ports & H-Bridges:

// Power PWM Ports:
/*~ 
 ~ Set the 8 power PWM ports of the ArduIO to be
 ~ used as 8 SINGLE power PWM ports and switch
 ~ all 8 power PWM ports off (0% PWM duty cycle).
 ~
 ~ Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 ~       ! THE ACCESS IS ENABLED (default): !
 ~       !   ==> enablePPWM_G(1); <==       !
 ~       !   ==> enablePPWM_G(2); <==       !
 ~
 */
void RP6_ArduIO::setPowerPWMMode(void)
{
  if (RP6ArduIOstatus.ppwm_g1Enable) {
    Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
    Wire.write(PCA9685_LED0_ON_H);
    Wire.write(0);
    Wire.endTransmission();
    PCA9685_set(CHPOWERPWM1_P, 0);
    Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
    Wire.write(PCA9685_LED1_ON_H);
    Wire.write(0);
    Wire.endTransmission();
    PCA9685_set(CHPOWERPWM2_N, 4095);
    Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
    Wire.write(PCA9685_LED2_ON_H);
    Wire.write(0);
    Wire.endTransmission();
    PCA9685_set(CHPOWERPWM3_P, 0);
    Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
    Wire.write(PCA9685_LED3_ON_H);
    Wire.write(0);
    Wire.endTransmission();
    PCA9685_set(CHPOWERPWM4_N, 4095);
  }
  if (RP6ArduIOstatus.ppwm_g2Enable) {
    Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
    Wire.write(PCA9685_LED4_ON_H);
    Wire.write(0);
    Wire.endTransmission();
    PCA9685_set(CHPOWERPWM5_P, 0);
    Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
    Wire.write(PCA9685_LED5_ON_H);
    Wire.write(0);
    Wire.endTransmission();
    PCA9685_set(CHPOWERPWM6_N, 4095);
    Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
    Wire.write(PCA9685_LED6_ON_H);
    Wire.write(0);
    Wire.endTransmission();
    PCA9685_set(CHPOWERPWM7_P, 0);
    Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
    Wire.write(PCA9685_LED7_ON_H);
    Wire.write(0);
    Wire.endTransmission();
    PCA9685_set(CHPOWERPWM8_N, 4095);
  }
}

/*~ 
 ~ Set the 8 power PWM ports of the ArduIO to ON or
 ~ OFF (set the MAX/MIN [100%/0%] PWM duty cycle).
 ~
 ~ Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 ~       ! THE ACCESS IS ENABLED (default): !
 ~       !   ==> enablePPWM_G(1); <==       !
 ~       !   ==> enablePPWM_G(2); <==       !
 ~
 ~ Example:
 ~          setPowerPWMs(0b00001010);
 ~          // this CLEARs power PWMs 1, 3, 5..8 [0%]
 ~          // and SETs power PWMs 2 and 4 [100%]!
 ~
 */
void RP6_ArduIO::setPowerPWMs(byte ppwms)
{
  if (RP6ArduIOstatus.ppwm_g1Enable) {
    if (ppwms & 0b00000001) PCA9685_set(CHPOWERPWM1_P, 4095);
    else PCA9685_set(CHPOWERPWM1_P, 0);
    if (ppwms & 0b00000010) PCA9685_set(CHPOWERPWM2_N, 0);
    else PCA9685_set(CHPOWERPWM2_N, 4095);
    if (ppwms & 0b00000100) PCA9685_set(CHPOWERPWM3_P, 4095);
    else PCA9685_set(CHPOWERPWM3_P, 0);
    if (ppwms & 0b00001000) PCA9685_set(CHPOWERPWM4_N, 0);
    else PCA9685_set(CHPOWERPWM4_N, 4095);
  }
  if (RP6ArduIOstatus.ppwm_g2Enable) {
    if (ppwms & 0b00010000) PCA9685_set(CHPOWERPWM5_P, 4095);
    else PCA9685_set(CHPOWERPWM5_P, 0);
    if (ppwms & 0b00100000) PCA9685_set(CHPOWERPWM6_N, 0);
    else PCA9685_set(CHPOWERPWM6_N, 4095);
    if (ppwms & 0b01000000) PCA9685_set(CHPOWERPWM7_P, 4095);
    else PCA9685_set(CHPOWERPWM7_P, 0);
    if (ppwms & 0b10000000) PCA9685_set(CHPOWERPWM8_N, 0);
    else PCA9685_set(CHPOWERPWM8_N, 4095);
  }
}

/*~ 
 ~ Dim the 8 power PWM ports of the ArduIO (set the
 ~ PWM duty cycle).
 ~
 ~ Input: ppwm -> Power PWM number [1..8]
 ~        duty -> Duty cycle [0..4095] = [0..100%]
 ~
 ~ There is also a macro dimPowerPWMx(duty),
 ~ which does exactly the same as this function,
 ~ where x = Power PWM number = [1..8].
 ~
 ~ Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 ~       ! THE ACCESS IS ENABLED (default): !
 ~       !   ==> enablePPWM_G(1); <==       !
 ~       !   ==> enablePPWM_G(2); <==       !
 ~
 ~ Example:
 ~   dimPowerPWM2(DUTY_50);   // Or dimPowerPWM(2,2047);
 ~   // this dims power PWM2 with a
 ~   // duty cycle of 50%!
 ~   dimPowerPWM2(DUTY_PCT(50));   // Or dimPowerPWM2(2047);
 ~   // does exactly the same!
 ~
 */
void RP6_ArduIO::dimPowerPWM(byte ppwm, unsigned int duty)
{
  if (RP6ArduIOstatus.ppwm_g1Enable) {
    if (ppwm == 1) PCA9685_set(CHPOWERPWM1_P, duty);
    if (ppwm == 2) PCA9685_set(CHPOWERPWM2_N, (4095 - duty));
    if (ppwm == 3) PCA9685_set(CHPOWERPWM3_P, duty);
    if (ppwm == 4) PCA9685_set(CHPOWERPWM4_N, (4095 - duty));
  }
  if (RP6ArduIOstatus.ppwm_g2Enable) {
    if (ppwm == 5) PCA9685_set(CHPOWERPWM5_P, duty);
    if (ppwm == 6) PCA9685_set(CHPOWERPWM6_N, (4095 - duty));
    if (ppwm == 7) PCA9685_set(CHPOWERPWM7_P, duty);
    if (ppwm == 8) PCA9685_set(CHPOWERPWM8_N, (4095 - duty));
  }
}

/*~ 
 ~ Set ONLY power PWM1, don't change anything for
 ~ the other power PWMs.
 ~
 ~ Input: ppwm -> 0 (false) = Power PWM off [0%]
 ~                >0 (true) = Power PWM max. duty cycle [100%]
 ~
 ~ Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 ~       ! THE ACCESS IS ENABLED (default): !
 ~       !   ==> enablePPWM_G(1); <==       !
 ~
 */
void RP6_ArduIO::setPowerPWM1(byte ppwm)
{
  if (RP6ArduIOstatus.ppwm_g1Enable) {
    if (ppwm > 0) PCA9685_set(CHPOWERPWM1_P, 4095); 
    else PCA9685_set(CHPOWERPWM1_P, 0);
  }
}	

/*~ 
 ~ Set ONLY power PWM2, don't change anything for
 ~ the other power PWMs.
 */
void RP6_ArduIO::setPowerPWM2(byte ppwm)
{
  if (RP6ArduIOstatus.ppwm_g1Enable) {
    if (ppwm > 0) PCA9685_set(CHPOWERPWM2_N, 0); 
    else PCA9685_set(CHPOWERPWM2_N, 4095);
  }
}	

/*~ 
 ~ Set ONLY power PWM3, don't change anything for
 ~ the other power PWMs.
 */
void RP6_ArduIO::setPowerPWM3(byte ppwm)
{
  if (RP6ArduIOstatus.ppwm_g1Enable) {
    if (ppwm > 0) PCA9685_set(CHPOWERPWM3_P, 4095); 
    else PCA9685_set(CHPOWERPWM3_P, 0);
  }
}

/*~ 
 ~ Set ONLY power PWM4, don't change anything for
 ~ the other power PWMs.
 */
void RP6_ArduIO::setPowerPWM4(byte ppwm)
{
  if (RP6ArduIOstatus.ppwm_g1Enable) {
    if (ppwm > 0) PCA9685_set(CHPOWERPWM4_N, 0); 
    else PCA9685_set(CHPOWERPWM4_N, 4095);
  }
}

/*~ 
 ~ Set ONLY power PWM5, don't change anything for
 ~ the other power PWMs.
 ~
 ~ Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 ~       ! THE ACCESS IS ENABLED (default): !
 ~       !   ==> enablePPWM_G(2); <==       !
 ~
 */
void RP6_ArduIO::setPowerPWM5(byte ppwm)
{
  if (RP6ArduIOstatus.ppwm_g2Enable) {
    if (ppwm > 0) PCA9685_set(CHPOWERPWM5_P, 4095); 
    else PCA9685_set(CHPOWERPWM5_P, 0);
  }
}	

/*~ 
 ~ Set ONLY power PWM6, don't change anything for
 ~ the other power PWMs.
 */
void RP6_ArduIO::setPowerPWM6(byte ppwm)
{
  if (RP6ArduIOstatus.ppwm_g2Enable) {
    if (ppwm > 0) PCA9685_set(CHPOWERPWM6_N, 0); 
    else PCA9685_set(CHPOWERPWM6_N, 4095);
  }
}	

/*~ 
 ~ Set ONLY power PWM7, don't change anything for
 ~ the other power PWMs.
 */
void RP6_ArduIO::setPowerPWM7(byte ppwm)
{
  if (RP6ArduIOstatus.ppwm_g2Enable) {
    if (ppwm > 0) PCA9685_set(CHPOWERPWM7_P, 4095); 
    else PCA9685_set(CHPOWERPWM7_P, 0);
  }
}	

/*~ 
 ~ Set ONLY power PWM8, don't change anything for
 ~ the other power PWMs.
 */
void RP6_ArduIO::setPowerPWM8(byte ppwm)
{
  if (RP6ArduIOstatus.ppwm_g2Enable) {
    if (ppwm > 0) PCA9685_set(CHPOWERPWM8_N, 0); 
    else PCA9685_set(CHPOWERPWM8_N, 4095);
  }
}

// H-Bridges:

byte last_hb, last_dir;

/*~ 
 ~ Adjust all functions of the two H-Bridges.
 ~
 ~ Input: hb   -> H-Bridge (HB) number [1 or 2]
 ~        dir  -> Direction [0, 1, 4, 5]
 ~        duty -> Duty cycle [0..4095] = [0..100%]
 ~ 
 ~ There are also 6 macros for each HB:
 ~   powerHBx(dir,duty);
 ~   powerHBxSTOP();
 ~   powerHBxFWD(duty);
 ~   powerHBxBWD(duty);
 ~   powerHBxBRK();
 ~   powerHBxOFF();
 ~ which do exactly the same as this function,
 ~ where x = H-Bridge number = [1 or 2].
 ~
 ~ Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 ~       ! THE ACCESS IS ENABLED:           !
 ~       !   ==> enableHB(1); <==           !
 ~       !   ==> enableHB(2); <==           !
 ~
 ~ Examples:
 ~   powerHB1(BWD,DUTY_50);   // Or adjustPowerHB(1,1,2047);
 ~   // this moves a motor at HB1 backward with
 ~   // a duty cycle of 50%!
 ~   powerHB1BWD(DUTY_PCT(50));
 ~   // does exactly the same!
 ~
 ~   powerHB2STOP();   // Or powerHB2(FWD,DUTY_0);
 ~   // this stops a motor at HB2 (duty cycle: 0%)
 ~   // and sets direction FWD!
 ~   // If you don't want direction FWD to be set,
 ~   // you have to use: powerHB2(BWD,DUTY_0)!
 ~
 ~   powerHB1BRK();
 ~   // this stops a motor at HB1 faster than the
 ~   // function powerHB1STOP() by shorting it!
 ~
 ~   powerHB2OFF();
 ~   // this stops a motor at HB2 by cutting off
 ~   // all four HB2 motor driver MOSFets!
 ~
 */
void RP6_ArduIO::adjustPowerHB(byte hb, byte dir, unsigned int duty)
{
  byte newcall = 1;
  if ((RP6ArduIOstatus.hb1Enable) || (RP6ArduIOstatus.hb2Enable)) {
    if ((hb == last_hb) && (dir == last_dir))
      newcall = 0;
    else {
      newcall = 1;
      last_hb = hb;					// Store last H-Bridge number
      last_dir = dir;					// Store last direction
    }
  }
							// H-Bridge 1
  if ((hb == 1) && (RP6ArduIOstatus.hb1Enable)) {
    switch (dir) {					//  Direction:
      case FWD :					//   Forwards
        if (newcall) {
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED1_OFF_H);
          Wire.write(0);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED1_ON_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED2_OFF_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED0_OFF_H);
          Wire.write(0);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED0_ON_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED3_ON_H);
          Wire.write(0);
          Wire.endTransmission();
        }
        PCA9685_set(CHHB1_N2, (4095 - duty));
        break;
      case BWD :					//   Backwards
        if (newcall) {
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED0_OFF_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED3_OFF_H);
          Wire.write(0);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED3_ON_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED2_OFF_H);
          Wire.write(0);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED2_ON_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED1_ON_H);
          Wire.write(0);
          Wire.endTransmission();
        }
        PCA9685_set(CHHB1_N1, (4095 - duty));
        break;
      case BRK :					//   Speed break
        if (newcall) {
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED0_OFF_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED2_OFF_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED1_OFF_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED3_OFF_H);
          Wire.write(0x10);
          Wire.endTransmission();
        }
        break;
      case OFF :					//   Power OFF
        if (newcall) {
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED0_OFF_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED2_OFF_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED1_OFF_H);
          Wire.write(0);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED1_ON_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED3_OFF_H);
          Wire.write(0);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED3_ON_H);
          Wire.write(0x10);
          Wire.endTransmission();
        }
    }
  }
							// H-Bridge 2
  else if ((hb == 2) && (RP6ArduIOstatus.hb2Enable)) {
    switch (dir) {					//  Direction:
      case FWD :					//   Forwards
        if (newcall) {
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED5_OFF_H);
          Wire.write(0);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED5_ON_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED6_OFF_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED4_OFF_H);
          Wire.write(0);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED4_ON_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED7_ON_H);
          Wire.write(0);
          Wire.endTransmission();
        }
        PCA9685_set(CHHB2_N2, (4095 - duty));
        break;
      case BWD :					//   Backwards
        if (newcall) {
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED4_OFF_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED7_OFF_H);
          Wire.write(0);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED7_ON_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED6_OFF_H);
          Wire.write(0);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED6_ON_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED5_ON_H);
          Wire.write(0);
          Wire.endTransmission();
        }
        PCA9685_set(CHHB2_N1, (4095 - duty));
        break;
      case BRK :					//   Speed break
        if (newcall) {
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED4_OFF_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED6_OFF_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED5_OFF_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED7_OFF_H);
          Wire.write(0x10);
          Wire.endTransmission();
        }
        break;
      case OFF :					//   Power OFF
        if (newcall) {
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED4_OFF_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED6_OFF_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED5_OFF_H);
          Wire.write(0);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED5_ON_H);
          Wire.write(0x10);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED7_OFF_H);
          Wire.write(0);
          Wire.endTransmission();
          Wire.beginTransmission(I2C_ARDUIO_PWM_ADR);
          Wire.write(PCA9685_LED7_ON_H);
          Wire.write(0x10);
          Wire.endTransmission();
        }
    }
  }
}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// ArduIO Board system control routine:

/*~
 ~ Call all important ArduIO Board system
 ~ functions.
 ~ This function will read:
 ~  - All ArduIO Board digital portpins
 ~    Result: io1ins.GP100..io1ins.GP117
 ~            io2ins.GP200..io2ins.GP217
 ~            io3ins.GP300..io3ins.GP317
 ~  - All ArduIO Board analog portpins
 ~    Result: ad1ins.AD10..ad1ins.AD13
 ~            ad2ins.AD20..ad2ins.AD23
 ~            ad3ins.AD30..ad3ins.AD33
 ~
 ~ Hints: - Do NOT use readArduino_Uno_Exp()
 ~          together with THIS function!
 ~        - You should only use this function,
 ~          if you have to read ALL ArduIO Board
 ~          input portpins!
 ~        - Digital portpins can be read, if they
 ~          were configured as INPUTs before:
 ~          config_IO1(0b1111111111111111);
 ~          config_IO2(0b1111111111111111);
 ~          config_IO3(0b1111111111111111);
 ~        - Digital portpin input values can be
 ~          inverted with the function
 ~          invert_IO(io,invrt)!
 ~
 */
void RP6_ArduIO::readSystem(void)
{
  readAllArduIO_IOs();
  readAllArduIO_ADs();
}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// ArduIO Board initialisation and shutdown:

/*~
 ~ You MUST call this function ONCE at the
 ~ beginning of a main program, that uses the
 ~ ArduIO Board.
 ~ DEFAULT initialisation settings are:
 ~ - Default access to ArduIO functions enable
 ~ - Default PWM frequency
 ~ - Power PWM mode enable
 ~ - H-Bridge mode disable
 ~ - All 8 power PWMs off
 ~ - All 4 free PWMs off
 ~ - All 4 LEDs off
 ~
 ~ Hints: - After power on the 48 ArduIO IOs are
 ~          configured as INPUTs (PCA9535
 ~          default!). This function does NOT
 ~          configurate the IOs!
 ~        - After power on the 3 ArduIO DACs are
 ~          disabled (PCF8591 default!). This
 ~          function does NOT affect the state or
 ~          the output voltage of the DACs!
 ~
 */
void RP6_ArduIO::init(void)
{
  // ArduIO Status (DEFAULT):
  setArduIODefaultStatus();			// ArduIO access default status
  // PWM Controller:
  PCA9685_init(PWM_FREQUENCY);			// Init PWM default frequency
  // Power PWM Ports & H-Bridges:
  setPowerPWMMode();				// ArduIO 8 power PWMs off
  // PWMs:
  setPWMs(0b0000);				// ArduIO 4 free PWMs off
  // LEDs:
  setLEDs(0b0000);				// ArduIO 4 LEDs off
  // I/O Expanders:
  io1config.port = 0xffff;
  io2config.port = 0xffff;
  io3config.port = 0xffff;			// ArduIO 48 IOs INPUTs
  io1invrt.port = 0;
  io2invrt.port = 0;
  io3invrt.port = 0;				// ArduIO 48 IOs NOT inverted
}

/*~
 ~ If you don't use any function of the ArduIO
 ~ Board, you can put the ArduIO Board into
 ~ "SHUTDOWN MODE". In this mode the electric
 ~ power consumption is very low to save energy.
 ~ If DISABLE_ON_SHUTDOWN is defined (default),
 ~ access to ArduIO functions is disabled in
 ~ SHUTDOWN mode.
 ~ SHUTDOWN settings are:
 ~ - Power PWM mode enable
 ~ - H-Bridge mode disable
 ~ - All 8 power PWMs off
 ~ - All 4 free PWMs off
 ~ - All 4 LEDs off
 ~ - All 48 IOs INPUTs
 ~ - All 3 DACs disable
 ~ - Access to ArduIO functions disable
 ~   (if DISABLE_ON_SHUTDOWN is defined!)
 ~
 */
void RP6_ArduIO::shutdown(void)
{
  // ArduIO Status (DEFAULT):
  setArduIODefaultStatus();			// ArduIO access default status
  // Power PWM Ports & H-Bridges:
  setPowerPWMMode();				// ArduIO 8 power PWMs off
  // PWMs:
  setPWMs(0b0000);				// ArduIO 4 free PWMs off
  // LEDs:
  setLEDs(0b0000);				// ArduIO 4 LEDs off
  // I/O Expanders:
  config_IO(1,0b1111111111111111);
  config_IO(2,0b1111111111111111);
  config_IO(3,0b1111111111111111);		// ArduIO 48 IOs INPUTs
  // A/D and D/A Converters:
  disableAllArduIO_DAs();			// ArduIO 3 DACs disable
#ifdef DISABLE_ON_SHUTDOWN
  // ArduIO Status (SHUTDOWN):
  setArduIOShutdownStatus();			// ArduIO access shutdown status
#endif
}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/


/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Arduino Uno Expander special functions:

/*~
 ~ Update the IO_2 port with current value from
 ~ the global io2outs variable.
 ~ The 16 IO_2 portpins will be SET (high, ON)
 ~ or CLEARED (low, OFF). 14 of these IO_2
 ~ portpins are connected with the digital 
 ~ Arduino Uno Expander portpins D0..D13.
 ~
 ~ Bit positions of the Arduino Uno Expander
 ~ portpins in the io2outs port:
 ~          0b0000000000000000
 ~            |||    ||      |
 ~   Arduino: ||D8   |D7     D0
 ~            n.c.   D13 
 ~
 ~ Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 ~       ! THE ACCESS IS ENABLED (default): !
 ~       !   ==> enableOuts(); <==          !
 ~
 ~ Examples:
 ~   io2outs.port = 0b0000000100101001;
 ~   updateArduino_Uno_Exp_IO();
 ~   // this CLEARs the port and SETs the
 ~   // Arduino Uno Expander portpins D0, D3,
 ~   // D5 and D13!
 ~
 ~   // Other possibility:
 ~   io2outs.ARD_D8 = true;   // Or io2outs.P15 = true;
 ~   updateArduino_Uno_Exp_IO();
 ~   // this SETs the Arduino Uno Expander
 ~   // portpin D8 and does not affect any
 ~   // other portpin!
 ~
 */
void RP6_ArduIO::updateArduino_Uno_Exp_IO(void)
{
  if (RP6ArduIOstatus.outsEnable) {
    Wire.beginTransmission(I2C_ARDUIO_IO_2_ADR);
    Wire.write(PCA9535_OUTPUT_P0);
    Wire.write(io2outs.port & 0x00ff);
    Wire.write(io2outs.port >> 8);
    Wire.endTransmission();
  }
}

/*~
 ~ This function SETs (high, ON) or CLEARs
 ~ (low, OFF) the 16 IO_2 portpins. 14 of these
 ~ IO_2 portpins are connected with the digital 
 ~ Arduino Uno Expander portpins D0..D13.
 ~
 ~ Input: out -> Output value (16 bit)
 ~
 ~ Bit positions of the Arduino Uno Expander
 ~ portpins in the output value (out):
 ~          0b0000000000000000
 ~            |||    ||      |
 ~   Arduino: ||D8   |D7     D0
 ~            n.c.   D13 
 ~
 ~ Hint: ! THIS FUNCTION WILL ONLY WORK, IF !
 ~       ! THE ACCESS IS ENABLED (default): !
 ~       !   ==> enableOuts(); <==          !
 ~
 ~ Example:
 ~   setArduino_Uno_Exp_IO(0b0010000000101001);
 ~   // this CLEARs the port and SETs the
 ~   // Arduino Uno Expander portpins D0, D3,
 ~   // D5 and D8!
 ~
 */
void RP6_ArduIO::setArduino_Uno_Exp_IO(unsigned int out)
{
  if (RP6ArduIOstatus.outsEnable) {
    io2outs.port = out;
    updateArduino_Uno_Exp_IO();
  }
}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// ArduIO Board Arduino Uno Expander control routine:

/*~
 ~ Call all important Arduino Uno Expander read
 ~ functions.
 ~ This function will read:
 ~  - All Arduino digital portpins D0..D13
 ~    Result: io2ins.ARD_D0..io2ins.ARD_D13
 ~  - The Arduino analog portpins A0..A3
 ~    Result: ad3ins.ARD_A0..ad3ins.ARD_A3
 ~
 ~ Hints: - You can use function readSystem()
 ~          instead of THIS function! Do NOT use
 ~          both functions together!
 ~        - You should only use this function,
 ~          if you have to read ALL digital and
 ~          analog Arduino Uno Expander input
 ~          portpins!
 ~        - Digital portpins can be read, if they
 ~          were configured as INPUTs before:
 ~          config_IO2(0b1111111111111111);
 ~        - Digital portpin input values can be
 ~          inverted with the function
 ~          invert_IO(2,invrt)!
 ~
 */
void RP6_ArduIO::readArduino_Uno_Exp(void)
{
  read_IO(2);
  read_AD(3);
}

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

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
Library Keywords

Datei keywords.txt:

#######################################
# Syntax Coloring Map For RP6_ArduIO
#######################################

#######################################
# Datatypes, Classes & C++ Keywords
# (KEYWORD1)
#######################################

RP6_ArduIO	KEYWORD1
arduio	KEYWORD1
status_t	KEYWORD1
ioexp_1_t	KEYWORD1
ioexp_2_t	KEYWORD1
ioexp_3_t	KEYWORD1
addaexp_1_t	KEYWORD1
addaexp_2_t	KEYWORD1
addaexp_3_t	KEYWORD1

#######################################
# Methods and Functions (KEYWORD2)
#######################################
enableHB	KEYWORD2
disableHB	KEYWORD2
enablePPWM_G	KEYWORD2
disablePPWM_G	KEYWORD2
enablePWMs	KEYWORD2
disablePWMs	KEYWORD2
enableOuts	KEYWORD2
disableOuts	KEYWORD2
enableDAs	KEYWORD2
disableDAs	KEYWORD2
PCA9685_init	KEYWORD2
PCA9685_set	KEYWORD2
config_IO	KEYWORD2
update_IO	KEYWORD2
set_IO	KEYWORD2
invert_IO	KEYWORD2
read_IO	KEYWORD2
read_AD	KEYWORD2
write_DA	KEYWORD2
disable_DA	KEYWORD2
getUbSensor	KEYWORD2
calculateUb	KEYWORD2
measureUb	KEYWORD2
setLEDs	KEYWORD2
dimLED	KEYWORD2
setLED1	KEYWORD2
setLED2	KEYWORD2
setLED3	KEYWORD2
setLED4	KEYWORD2
setPWMs	KEYWORD2
dimPWM	KEYWORD2
setPWM1	KEYWORD2
setPWM2	KEYWORD2
setPWM3	KEYWORD2
setPWM4	KEYWORD2
setPowerPWMMode	KEYWORD2
setPowerPWMs	KEYWORD2
dimPowerPWM	KEYWORD2
setPowerPWM1	KEYWORD2
setPowerPWM2	KEYWORD2
setPowerPWM3	KEYWORD2
setPowerPWM4	KEYWORD2
setPowerPWM5	KEYWORD2
setPowerPWM6	KEYWORD2
setPowerPWM7	KEYWORD2
setPowerPWM8	KEYWORD2
adjustPowerHB	KEYWORD2
readSystem	KEYWORD2
init	KEYWORD2
shutdown	KEYWORD2
updateArduino_Uno_Exp_IO	KEYWORD2
setArduino_Uno_Exp_IO	KEYWORD2
readArduino_Uno_Exp	KEYWORD2

#######################################
# Setup & Loop Functions, the Serial
# Keywords (KEYWORD3)
#######################################


#######################################
# Constants (LITERAL1)
#######################################
PWM_FREQUENCY	LITERAL1
ADCVAL_UB_LOW	LITERAL1
DISABLE_ON_SHUTDOWN	LITERAL1
READ_ADCUB	LITERAL1
DUTY_0	LITERAL1
DUTY_10	LITERAL1
DUTY_25	LITERAL1
DUTY_50	LITERAL1
DUTY_75	LITERAL1
DUTY_90	LITERAL1
DUTY_100	LITERAL1
FWD	LITERAL1
BWD	LITERAL1
BRK	LITERAL1
OFF	LITERAL1

#######################################
# Built-in Variables (LITERAL2)
#######################################
Definitionen Header

Datei RP6_ArduIO_Defines.h:

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*                                               ___   ___                   */
/*                 _______________________      /   \ /   \                  */
/*                 \| RP6  ROBOT SYSTEM |/     (  -  X  +  )                 */
/*                  \_-_-_-_-_-_-_-_-_-_/       \___/ \___/                  */
/*                                                ARDUINO                    */
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*------------------------------ [c]2014 - Dirk -----------------------------*/
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*~
 ~ Target:    Arduino UNO with RP6 ArduIO Board (Shield)
 ~ Library:   RP6_ArduIO Defines Header
 ~ Version:   1.0
 ~ Author(s): Dirk
 ~
 ~ Description:
 ~ This is the RP6_ArduIO Libaray Defines header file. In this header you
 ~ will find additional defines, that will help to make your program better
 ~ readable. You can also use the RP6_ArduIO Library WITHOUT this header.
 */
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// RP6_ArduIO Library additional defines:
// (For a better user program readability!)
// Hint: This header assumes, that you include this file in your program
//       exactly like this:
//         #define CLASS_OBJECT arduio
//         #include <RP6_ArduIO_Defines.h>
//         RP6_ArduIO arduio;      // class object
//       Of course you may choose another object name than "arduio"!

#define isUbLow() (CLASS_OBJECT.status.bits & 1)
#define isHB1Enable() (CLASS_OBJECT.status.bits & 2)
#define isHB2Enable() (CLASS_OBJECT.status.bits & 4)
#define isPPWM_G1Enable() (CLASS_OBJECT.status.bits & 8)
#define isPPWM_G2Enable() (CLASS_OBJECT.status.bits & 16)
#define isPWMsEnable() (CLASS_OBJECT.status.bits & 32)
#define isOutsEnable() (CLASS_OBJECT.status.bits & 64)
#define isDAsEnable() (CLASS_OBJECT.status.bits & 128)

#define enableHB1() {CLASS_OBJECT.enableHB(1);}
#define enableHB2() {CLASS_OBJECT.enableHB(2);}
#define disableHB1() {CLASS_OBJECT.disableHB(1);}
#define disableHB2() {CLASS_OBJECT.disableHB(2);}
#define enablePPWM_G1() {CLASS_OBJECT.enablePPWM_G(1);}
#define enablePPWM_G2() {CLASS_OBJECT.enablePPWM_G(2);}
#define disablePPWM_G1() {CLASS_OBJECT.disablePPWM_G(1);}
#define disablePPWM_G2() {CLASS_OBJECT.disablePPWM_G(2);}
#define setDefaultStatus() {CLASS_OBJECT.enablePPWM_G(1); \
 CLASS_OBJECT.enablePPWM_G(2);CLASS_OBJECT.enablePWMs(); \
 CLASS_OBJECT.enableOuts();CLASS_OBJECT.enableDAs();}
#define setShutdownStatus() {CLASS_OBJECT.disableHB(1); \
 CLASS_OBJECT.disableHB(2);CLASS_OBJECT.disablePPWM_G(1); \
 CLASS_OBJECT.disablePPWM_G(2);CLASS_OBJECT.disablePWMs(); \
 CLASS_OBJECT.disableOuts();CLASS_OBJECT.disableDAs();}

#define initPWM(__FREQ__) {PCA9685_init(__FREQ__);}
#define setPWM(__CHANNEL__,__DUTY__) {PCA9685_set(__CHANNEL__,__DUTY__);}

#define config_IO1(__INOUT__) {CLASS_OBJECT.config_IO(1,__INOUT__);}
#define config_IO2(__INOUT__) {CLASS_OBJECT.config_IO(2,__INOUT__);}
#define config_IO3(__INOUT__) {CLASS_OBJECT.config_IO(3,__INOUT__);}
#define update_IO1() {CLASS_OBJECT.update_IO(1);}
#define update_IO2() {CLASS_OBJECT.update_IO(2);}
#define update_IO3() {CLASS_OBJECT.update_IO(3);}
#define set_IO1(__OUT__) {CLASS_OBJECT.set_IO(1,__OUT__);}
#define set_IO2(__OUT__) {CLASS_OBJECT.set_IO(2,__OUT__);}
#define set_IO3(__OUT__) {CLASS_OBJECT.set_IO(3,__OUT__);}
#define invert_IO1(__INVRT__) {CLASS_OBJECT.invert_IO(1,__INVRT__);}
#define invert_IO2(__INVRT__) {CLASS_OBJECT.invert_IO(2,__INVRT__);}
#define invert_IO3(__INVRT__) {CLASS_OBJECT.invert_IO(3,__INVRT__);}
#define read_IO1() {CLASS_OBJECT.read_IO(1);}
#define read_IO2() {CLASS_OBJECT.read_IO(2);}
#define read_IO3() {CLASS_OBJECT.read_IO(3);}
#define readAll_IOs() {CLASS_OBJECT.read_IO(1); \
 CLASS_OBJECT.read_IO(2);CLASS_OBJECT.read_IO(3);}

#define read_AD1() {CLASS_OBJECT.read_AD(1);}
#define read_AD2() {CLASS_OBJECT.read_AD(2);}
#define read_AD3() {CLASS_OBJECT.read_AD(3);}
#define readAll_ADs() {CLASS_OBJECT.read_AD(1); \
 CLASS_OBJECT.read_AD(2);CLASS_OBJECT.read_AD(3);}
#define write_DA1(__AOUT__) {CLASS_OBJECT.write_DA(1,__AOUT__);}
#define write_DA2(__AOUT__) {CLASS_OBJECT.write_DA(2,__AOUT__);}
#define write_DA3(__AOUT__) {CLASS_OBJECT.write_DA(3,__AOUT__);}
#define disable_DA1() {CLASS_OBJECT.disable_DA(1);}
#define disable_DA2() {CLASS_OBJECT.disable_DA(2);}
#define disable_DA3() {CLASS_OBJECT.disable_DA(3);}
#define disableAll_DAs() {CLASS_OBJECT.disable_DA(1); \
 CLASS_OBJECT.disable_DA(2);CLASS_OBJECT.disable_DA(3);}

#define dimLED1(__DUTY__) {CLASS_OBJECT.dimLED(1,__DUTY__);}
#define dimLED2(__DUTY__) {CLASS_OBJECT.dimLED(2,__DUTY__);}
#define dimLED3(__DUTY__) {CLASS_OBJECT.dimLED(3,__DUTY__);}
#define dimLED4(__DUTY__) {CLASS_OBJECT.dimLED(4,__DUTY__);}
#define dimPWM1(__DUTY__) {CLASS_OBJECT.dimPWM(1,__DUTY__);}
#define dimPWM2(__DUTY__) {CLASS_OBJECT.dimPWM(2,__DUTY__);}
#define dimPWM3(__DUTY__) {CLASS_OBJECT.dimPWM(3,__DUTY__);}
#define dimPWM4(__DUTY__) {CLASS_OBJECT.dimPWM(4,__DUTY__);}

#define dimPowerPWM1(__DUTY__) {CLASS_OBJECT.dimPowerPWM(1,__DUTY__);}
#define dimPowerPWM2(__DUTY__) {CLASS_OBJECT.dimPowerPWM(2,__DUTY__);}
#define dimPowerPWM3(__DUTY__) {CLASS_OBJECT.dimPowerPWM(3,__DUTY__);}
#define dimPowerPWM4(__DUTY__) {CLASS_OBJECT.dimPowerPWM(4,__DUTY__);}
#define dimPowerPWM5(__DUTY__) {CLASS_OBJECT.dimPowerPWM(5,__DUTY__);}
#define dimPowerPWM6(__DUTY__) {CLASS_OBJECT.dimPowerPWM(6,__DUTY__);}
#define dimPowerPWM7(__DUTY__) {CLASS_OBJECT.dimPowerPWM(7,__DUTY__);}
#define dimPowerPWM8(__DUTY__) {CLASS_OBJECT.dimPowerPWM(8,__DUTY__);}

#define powerHB1(__DIR__,__DUTY__) {CLASS_OBJECT.adjustPowerHB(1,__DIR__,__DUTY__);}
#define powerHB1STOP() {CLASS_OBJECT.adjustPowerHB(1,FWD,DUTY_0);}
#define powerHB1FWD(__DUTY__) {CLASS_OBJECT.adjustPowerHB(1,FWD,__DUTY__);}
#define powerHB1BWD(__DUTY__) {CLASS_OBJECT.adjustPowerHB(1,BWD,__DUTY__);}
#define powerHB1BRK() {CLASS_OBJECT.adjustPowerHB(1,BRK,0);}
#define powerHB1OFF() {CLASS_OBJECT.adjustPowerHB(1,OFF,0);}
#define powerHB2(__DIR__,__DUTY__) {CLASS_OBJECT.adjustPowerHB(2,__DIR__,__DUTY__);}
#define powerHB2STOP() {CLASS_OBJECT.adjustPowerHB(2,FWD,DUTY_0);}
#define powerHB2FWD(__DUTY__) {CLASS_OBJECT.adjustPowerHB(2,FWD,__DUTY__);}
#define powerHB2BWD(__DUTY__) {CLASS_OBJECT.adjustPowerHB(2,BWD,__DUTY__);}
#define powerHB2BRK() {CLASS_OBJECT.adjustPowerHB(2,BRK,0);}
#define powerHB2OFF() {CLASS_OBJECT.adjustPowerHB(2,OFF,0);}

#define readArduino_Uno_Exp_IO() {CLASS_OBJECT.read_IO(2);}
#define readArduino_Uno_Exp_AD() {CLASS_OBJECT.read_AD(3);}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
Erklärung

Demo 1

Die Demo 1 besteht eigentlich aus ZWEI Testprogrammen. Wird sie so kompiliert, wie sie hier steht, erfolgt ein SCHREIB-Test (Output) auf allen Funktionen der ArduIO. Wird die Definition "WRITE_TEST" auskommentiert, erfolgt ein LESE-Test (Input).

Datei RP6_ArduIO_Demo_01.ino:

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*------------------------------ [c]2014 - Dirk -----------------------------*/
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*~
 ~ Target:    Arduino UNO with RP6 ArduIO Board (Shield)
 ~ Example:   RP6_ArduIO_Demo_01
 ~ Version:   1.0
 ~ Author(s): Dirk
 ~
 ~ Description:
 ~ In this example we show a first test for the RP6 ArduIO Board.
 */
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Defines:
#define CLASS_OBJECT arduio
// Define the kind of demo:
// (If you don't define WRITE_TEST the READ TEST will be performed!)
#define WRITE_TEST

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Includes:
#include <RP6_ArduIO.h>
#include <RP6_ArduIO_Defines.h>
#include <Wire.h>

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Constants:
const int buttonPin = 2;     // the number of the pushbutton pin

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Variables:
byte onoff = 0;

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Class object:
RP6_ArduIO arduio;

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
void setup() {
  // Initialize serial and wait for port to open:
  Serial.begin(9600); 
//  while (!Serial) {
//    ; // wait for serial port to connect. Needed for Leonardo only
//  }

  // Wire init
  Wire.begin();      // wake up I2C bus

  // initialize the pushbutton pin as an input:
  pinMode(buttonPin, INPUT);     

  // First test (executed once):
  Serial.println("Arduino UNO ArduIO Test 1!");
#ifdef WRITE_TEST
  Serial.println("");
  Serial.println("PLEASE ENSURE THAT NO PINS OF PLUG SV_H-BRIDGES ARE CONNECTED!!!");
#endif
  Serial.println("");

  arduio.init();      // ArduIO init!!!
#ifdef WRITE_TEST
  Serial.println("Test -> LED1");
  arduio.setLED1(1);
  delay(500);
  arduio.setLED1(0);
  delay(500);
  arduio.setLED1(1);
  delay(1000);
  Serial.println("Test -> LED2");
  arduio.setLED2(1);
  delay(500);
  arduio.setLED2(0);
  delay(500);
  arduio.setLED2(1);
  delay(1000);
  Serial.println("Test -> LED3");
  arduio.setLED3(1);
  delay(500);
  arduio.setLED3(0);
  delay(500);
  arduio.setLED3(1);
  delay(1000);
  Serial.println("Test -> LED4");
  arduio.setLED4(1);
  delay(500);
  arduio.setLED4(0);
  delay(500);
  arduio.setLED4(1);
  delay(500);

  arduio.setLEDs(0b0000);

  arduio.config_IO(1, 0);
  arduio.config_IO(2, 0);
  arduio.config_IO(3, 0);      // All IOs OUTPUTs
  delay(100);
#else
  arduio.config_IO(1, 0b1111111111111111);
  arduio.config_IO(2, 0b1111111111111111);
  arduio.config_IO(3, 0b1111111111111111);      // All IOs INPUTs
  delay(100);
#endif
  Serial.println("===> PRESS BUTTON TO STOP THE DEMO!!! <===");
  Serial.println("");
}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
void loop() {
  delay(1000);
  if (onoff) onoff = 0;
  else onoff = 1;
#ifndef WRITE_TEST
  // UB voltage sensor ADC test:
  arduio.ubv = arduio.measureUb();
  Serial.println("");
  Serial.print("UB Voltage: ");
  Serial.print(arduio.ubv, 1);
  Serial.println("V");
  Serial.print("ADC UB: ");
  Serial.print(arduio.adcub, DEC);
  Serial.println("");
#else
  // PWM controller test:
  //   LEDs & IOs & free PWMs & power PWMs ON/OFF:
  if (onoff) {
    Serial.println("Test -> LEDs: 1001, IOs: 1, PWMs: 1001, HBs N-MOSFets: 1");
    arduio.set_IO(1, 0xffff);
    arduio.set_IO(2, 0xffff);
    arduio.set_IO(3, 0xffff);      // All IOs high
    arduio.setLED1(1);
    arduio.setLED2(0);
    arduio.setLED3(0);
    arduio.setLED4(1);
    arduio.setPWM1(1);
    arduio.setPWM2(0);
    arduio.setPWM3(0);
    arduio.setPWM4(1);
    arduio.setPowerPWMs(0b10101010);
  }
  else {
    Serial.println("Test -> LEDs: 0110, IOs: 0, PWMs: 0110, HBs P-MOSFets: 1");
    arduio.set_IO(1, 0);
    arduio.set_IO(2, 0);
    arduio.set_IO(3, 0);      // All IOs low
    arduio.setLEDs(0b0110);
    arduio.setPWMs(0b0110);
    arduio.setPowerPWMs(0b01010101);
  }
#endif
#ifndef WRITE_TEST
  // I/O Expander 1 read test:
  arduio.read_IO(1);      // Read GP100..GP117
  Serial.println("");
  Serial.print("IO_1: ");
  Serial.print(arduio.io1ins.port, BIN);
  Serial.println("");
  // I/O Expander 2 read test:
  arduio.read_IO(2);      // Read GP200..GP217
  Serial.println("");
  Serial.print("IO_2: ");
  Serial.print(arduio.io2ins.port, BIN);
  Serial.println("");
  //Serial.println(" ARD:     1111");
  //Serial.println("        89012376543210");
  // I/O Expander 3 read test:
  arduio.read_IO(3);      // Read GP300..GP317
  Serial.println("");
  Serial.print("IO_3: ");
  Serial.print(arduio.io3ins.port, BIN);
  Serial.println("");

  // AD/DA Converter 1 ADC test:
  arduio.read_AD(1);      // Read AD10..AD13
  Serial.println("");
  Serial.print("ADDA_1: ");
  Serial.print(arduio.ad1ins.AD10, DEC);
  Serial.print(" | ");
  Serial.print(arduio.ad1ins.AD11, DEC);
  Serial.print(" | ");
  Serial.print(arduio.ad1ins.AD12, DEC);
  Serial.print(" | ");
  Serial.print(arduio.ad1ins.AD13, DEC);
  Serial.println("");
  Serial.print(" U[cV]: ");
  Serial.print(UCV_AD(arduio.ad1ins.AD10), DEC);
  Serial.print(" | ");
  Serial.print(UCV_AD(arduio.ad1ins.AD11), DEC);
  Serial.print(" | ");
  Serial.print(UCV_AD(arduio.ad1ins.AD12), DEC);
  Serial.print(" | ");
  Serial.print(UCV_AD(arduio.ad1ins.AD13), DEC);
  Serial.println("");
  Serial.println("        A0  | A1  | A2  | A3");
  // AD/DA Converter 2 ADC test:
  arduio.read_AD(2);      // Read AD20..AD23
  Serial.print("ADDA_2: ");
  Serial.print(arduio.ad2ins.AD20, DEC);
  Serial.print(" | ");
  Serial.print(arduio.ad2ins.AD21, DEC);
  Serial.print(" | ");
  Serial.print(arduio.ad2ins.AD22, DEC);
  Serial.print(" | ");
  Serial.print(arduio.ad2ins.AD23, DEC);
  Serial.println("");
  Serial.print(" U[cV]: ");
  Serial.print(UCV_AD(arduio.ad2ins.AD20), DEC);
  Serial.print(" | ");
  Serial.print(UCV_AD(arduio.ad2ins.AD21), DEC);
  Serial.print(" | ");
  Serial.print(UCV_AD(arduio.ad2ins.AD22), DEC);
  Serial.print(" | ");
  Serial.print(UCV_AD(arduio.ad2ins.AD23), DEC);
  Serial.println("");
  Serial.println("        A0  | A1  | A2  | A3");
  // AD/DA Converter 3 ADC test:
  arduio.read_AD(3);      // Read AD30..AD33
  Serial.print("ADDA_3: ");
  Serial.print(arduio.ad3ins.ARD_A0, DEC);
  Serial.print(" | ");
  Serial.print(arduio.ad3ins.ARD_A1, DEC);
  Serial.print(" | ");
  Serial.print(arduio.ad3ins.ARD_A2, DEC);
  Serial.print(" | ");
  Serial.print(arduio.ad3ins.ARD_A3, DEC);
  Serial.println("");
  Serial.print(" U[cV]: ");
  Serial.print(UCV_AD(arduio.ad3ins.ARD_A0), DEC);
  Serial.print(" | ");
  Serial.print(UCV_AD(arduio.ad3ins.ARD_A1), DEC);
  Serial.print(" | ");
  Serial.print(UCV_AD(arduio.ad3ins.ARD_A2), DEC);
  Serial.print(" | ");
  Serial.print(UCV_AD(arduio.ad3ins.ARD_A3), DEC);
  Serial.println("");
  Serial.println("   ARD: A0  | A1  | A2  | A3");
#else
  // AD/DA Converter 1..3 DAC test:
  if (onoff) {
    Serial.println("Test -> DA1..3: 1.50V");
    Serial.println("");
    arduio.write_DA(1, AOUT_CV(150));      // DA1: 1.5V
    arduio.write_DA(2, AOUT_CV(150));      // DA2: 1.5V
    arduio.write_DA(3, AOUT_CV(150));      // DA3: 1.5V
  }
  else {
    Serial.println("Test -> DA1..3: 3.50V");
    Serial.println("");
    arduio.write_DA(1, AOUT_CV(350));      // DA1: 3.5V
    arduio.write_DA(2, AOUT_CV(350));      // DA2: 3.5V
    arduio.write_DA(3, AOUT_CV(350));      // DA3: 3.5V
  }
#endif
/*
  // ArduIO shutdown:
  byte key = digitalRead(buttonPin); 
  if (key == HIGH) {
    Serial.println("");
    Serial.println("Press button again for ArduIO SHUTDOWN");
    Serial.println("");
    do {
      delay(10);
      key = digitalRead(buttonPin);
    } while (key == HIGH);
    do {
      delay(10);
      key = digitalRead(buttonPin);
    } while (key == LOW);
    Serial.println("");
    Serial.println("Please wait for ArduIO SHUTDOWN...");
    arduio.shutdown();
    delay(3000);
    Serial.println("");
    Serial.println("The ArduIO now is in SHUTDOWN MODE!!!");
    delay(1000);
    Serial.println("");
    Serial.println("RESET the microcontroller now...");
    Serial.println("");
    while(true) {};
  }
*/
}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
Erklärung

Demo 2

Die Demo 2 zeigt, wie die LEDs, freien PWMs und Power PWMs gedimmt werden können.

Datei RP6_ArduIO_Demo_02.ino:

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*------------------------------ [c]2014 - Dirk -----------------------------*/
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*~
 ~ Target:    Arduino UNO with RP6 ArduIO Board (Shield)
 ~ Example:   RP6_ArduIO_Demo_02
 ~ Version:   1.0
 ~ Author(s): Dirk
 ~
 ~ Description:
 ~ In this example we show a second test for the RP6 ArduIO Board.
 */
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Defines:
#define CLASS_OBJECT arduio

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Includes:
#include <RP6_ArduIO.h>
#include <RP6_ArduIO_Defines.h>
#include <Wire.h>

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Constants:
const int buttonPin = 2;     // the number of the pushbutton pin

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Variables:
byte duty_pct = 0;

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Class object:
RP6_ArduIO arduio;

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
void setup() {
  // Initialize serial and wait for port to open:
  Serial.begin(9600); 
//  while (!Serial) {
//    ; // wait for serial port to connect. Needed for Leonardo only
//  }

  // Wire init
  Wire.begin();      // wake up I2C bus

  // initialize the pushbutton pin as an input:
  pinMode(buttonPin, INPUT);     

  Serial.println("Arduino UNO ArduIO Test 2!");
  Serial.println("");
  Serial.println("PLEASE ENSURE THAT NO PINS OF PLUG SV_H-BRIDGES ARE CONNECTED!!!");
  Serial.println("");

  arduio.init();      // ArduIO init!!!
  delay(5000);

  Serial.println("===> PRESS BUTTON TO STOP THE DEMO!!! <===");
  Serial.println("");
}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
void loop() {
  delay(1000);
  // PWM controller test:
  //   LEDs & free PWMs & power PWMs dim UP:
  Serial.println("==> DIM Tests: ");
  Serial.print(duty_pct, DEC);
  Serial.println(" % Duty Cycle");
  arduio.dimLED(1, DUTY_PCT(duty_pct));
  arduio.dimLED(2, DUTY_PCT(duty_pct));
  arduio.dimLED(3, DUTY_PCT(duty_pct));
  arduio.dimLED(4, DUTY_PCT(duty_pct));
  arduio.dimPWM(1, DUTY_PCT(duty_pct));
  arduio.dimPWM(2, DUTY_PCT(duty_pct));
  arduio.dimPWM(3, DUTY_PCT(duty_pct));
  arduio.dimPWM(4, DUTY_PCT(duty_pct));
  arduio.dimPowerPWM(1, DUTY_PCT(duty_pct));
  arduio.dimPowerPWM(2, DUTY_PCT(duty_pct));
  arduio.dimPowerPWM(3, DUTY_PCT(duty_pct));
  arduio.dimPowerPWM(4, DUTY_PCT(duty_pct));
  arduio.dimPowerPWM(5, DUTY_PCT(duty_pct));
  arduio.dimPowerPWM(6, DUTY_PCT(duty_pct));
  arduio.dimPowerPWM(7, DUTY_PCT(duty_pct));
  arduio.dimPowerPWM(8, DUTY_PCT(duty_pct));
  duty_pct += 10;
  if (duty_pct > 100) {
    duty_pct = 0;
    Serial.println("");
  }
/*
  // ArduIO shutdown:
  byte key = digitalRead(buttonPin); 
  if (key == HIGH) {
    Serial.println("");
    Serial.println("Press button again for ArduIO SHUTDOWN");
    Serial.println("");
    do {
      delay(10);
      key = digitalRead(buttonPin);
    } while (key == HIGH);
    do {
      delay(10);
      key = digitalRead(buttonPin);
    } while (key == LOW);
    Serial.println("");
    Serial.println("Please wait for ArduIO SHUTDOWN...");
    arduio.shutdown();
    delay(3000);
    Serial.println("");
    Serial.println("The ArduIO now is in SHUTDOWN MODE!!!");
    delay(1000);
    Serial.println("");
    Serial.println("RESET the microcontroller now...");
    Serial.println("");
    while(true) {};
  }
*/
}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
Erklärung

Demo 3

Die Demo 3 demonstriert die Ansteuerung der H-Brücken.

Datei RP6_ArduIO_Demo_03.ino:

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*------------------------------ [c]2014 - Dirk -----------------------------*/
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*~
 ~ Target:    Arduino UNO with RP6 ArduIO Board (Shield)
 ~ Example:   RP6_ArduIO_Demo_03
 ~ Version:   1.0
 ~ Author(s): Dirk
 ~
 ~ Description:
 ~ In this example we show a third test for the RP6 ArduIO Board.
 */
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Defines:
#define CLASS_OBJECT arduio

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Includes:
#include <RP6_ArduIO.h>
#include <RP6_ArduIO_Defines.h>
#include <Wire.h>

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Constants:
const int buttonPin = 2;     // the number of the pushbutton pin

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Variables:
byte duty_pct = 0;
byte cnt_sec = 0;

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
// Class object:
RP6_ArduIO arduio;

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
void setup() {
  // Initialize serial and wait for port to open:
  Serial.begin(9600); 
//  while (!Serial) {
//    ; // wait for serial port to connect. Needed for Leonardo only
//  }

  // Wire init
  Wire.begin();      // wake up I2C bus

  // initialize the pushbutton pin as an input:
  pinMode(buttonPin, INPUT);     

  Serial.println("Arduino UNO ArduIO Test 3!");
  Serial.println("");
  Serial.println("YOU MAY WATCH THE RED & GREEN MOSFET-LEDS AND/OR");
  Serial.println("CONNECT  A DC-MOTOR TO THE PLUG  SV_H-BRIDGES!!!");
  Serial.println("");

  arduio.init();      // ArduIO init!!!
  enableHB1();      // Enable HB1!!!
  enableHB2();      // Enable HB2!!!

  Serial.println("Test -> HB1 OFF");
  powerHB1OFF();
  delay(5000);
  Serial.println("Test -> HB1 FWD 10%");
  powerHB1FWD(DUTY_PCT(10));
  delay(5000);
  Serial.println("Test -> HB1 STOP");
  powerHB1STOP();
  delay(5000);
  Serial.println("Test -> HB1 BWD 10%");
  powerHB1BWD(DUTY_PCT(10));
  delay(5000);
  Serial.println("Test -> HB1 BRK");
  powerHB1BRK();
  delay(5000);
  Serial.println("Test -> HB1 OFF");
  powerHB1OFF();
  delay(5000);

  Serial.println("Test -> HB2 OFF");
  powerHB2OFF();
  delay(5000);
  Serial.println("Test -> HB2 FWD 10%");
  powerHB2FWD(DUTY_PCT(10));
  delay(5000);
  Serial.println("Test -> HB2 STOP");
  powerHB2STOP();
  delay(5000);
  Serial.println("Test -> HB2 BWD 10%");
  powerHB2BWD(DUTY_PCT(10));
  delay(5000);
  Serial.println("Test -> HB2 BRK");
  powerHB2BRK();
  delay(5000);
  Serial.println("Test -> HB2 OFF");
  powerHB2OFF();
  delay(5000);
  Serial.println("");

  Serial.println("===> PRESS BUTTON TO STOP THE DEMO!!! <===");
  Serial.println("");
}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
void loop() {
  delay(1000);
  // PWM controller test:
  //   H-Bridges:
  Serial.println("==> HB1/2 DIM Tests: ");
  Serial.print(duty_pct, DEC);
  Serial.print(" % Duty Cycle");
  if (cnt_sec < 22) {      // 2 cycles FWD
    Serial.println(" Dir: FWD");
    powerHB1FWD(DUTY_PCT(duty_pct));
    powerHB2FWD(DUTY_PCT(duty_pct));
  }
  else {      // 2 cycles BWD
    Serial.println(" Dir: BWD");
    powerHB1BWD(DUTY_PCT(duty_pct));
    powerHB2BWD(DUTY_PCT(duty_pct));
  }
  cnt_sec++;
  if (cnt_sec > 43) cnt_sec = 0;
  duty_pct += 10;
  if (duty_pct > 100) {
    duty_pct = 0;
    Serial.println("");
  }
/*
  // ArduIO shutdown:
  byte key = digitalRead(buttonPin); 
  if (key == HIGH) {
    Serial.println("");
    Serial.println("Press button again for ArduIO SHUTDOWN");
    Serial.println("");
    do {
      delay(10);
      key = digitalRead(buttonPin);
    } while (key == HIGH);
    do {
      delay(10);
      key = digitalRead(buttonPin);
    } while (key == LOW);
    Serial.println("");
    Serial.println("Please wait for ArduIO SHUTDOWN...");
    arduio.shutdown();
    delay(3000);
    Serial.println("");
    Serial.println("The ArduIO now is in SHUTDOWN MODE!!!");
    delay(1000);
    Serial.println("");
    Serial.println("RESET the microcontroller now...");
    Serial.println("");
    while(true) {};
  }
*/
}

/*~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~*/
Erklärung



Technische Informationen

I2C-Adressen

I2C-Adressen der ArduIO:

I2C-Portexpander-Baustein RP6-System (RP6I2CmasterTWI): Arduino-System (Wire): Verwendung
I2C-
Adresse *
Alternative
I2C-Adressen
I2C-
Adresse *
Alternative
I2C-Adressen
I2C PWM Controller (IC3: PCA9685) 0x84 0x86, 0x8c, 0x8e, 0xe0 0x42 0x43, 0x46, 0x47, 0x70 PWM Controller
I2C I/O Expander 1 5V (IC8: PCA9535) 0x44 0x46, 0x4c, 0x4e 0x22 0x23, 0x26, 0x27 I/O Expander 1
I2C I/O Expander 2 5V (IC13: PCA9535) 0x46 0x44, 0x4c, 0x4e 0x23 0x22, 0x26, 0x27 I/O Expander 2
I2C I/O Expander 3 3V3 (IC12: PCA9535) 0x4c 0x44, 0x46, 0x4e 0x26 0x22, 0x23, 0x27 I/O Expander 3
I2C A/D und D/A Converter 1 (IC11: PCF8591) 0x94 0x96, 0x9c, 0x9e 0x4a 0x4b, 0x4e, 0x4f A/D und D/A Converter 1
I2C A/D und D/A Converter 2 (IC10: PCF8591) 0x96 0x94, 0x9c, 0x9e 0x4b 0x4a, 0x4e, 0x4f A/D und D/A Converter 2
I2C A/D und D/A Converter 3 (IC9: PCF8591) 0x9c 0x94, 0x96, 0x9e 0x4e 0x4a, 0x4b, 0x4f A/D und D/A Converter 3

Zu *) Standard-Adresse.

Zu ²) Adress-Konflikt mit dem RP6-System möglich (siehe hier)!

Stecker-Belegungen

PWM Controller

Stecker SV_H-BRIDGES (MOSFETs):

Stecker-Pin PWM Controller-Port Power PWM-
Kanal
Power PWM-
Ausgang
H-Brücken-
Ausgang
ArduIO-Funktion
1 +UB (FUSED)
2 GND
3 PWM1 2 N-Drain 1 Motor 1 PLUS
4 PWM0 1 P-Drain 1
5 PWM3 4 N-Drain 2 Motor 1 MINUS
6 PWM2 3 P-Drain 2
7 PWM5 6 N-Drain 3 Motor 2 PLUS
8 PWM4 5 P-Drain 3
9 PWM7 8 N-Drain 4 Motor 2 MINUS
10 PWM6 7 P-Drain 4

Jumper JP_LEDS (PWMs 8-11):

Jumper-Pin PWM Controller-Port LED-
Kanal
8 PWM8 4
9 PWM9 3
10 PWM10 2
11 PWM11 1

HINWEIS: Wenn auf Jumper JP_LEDS keine Steckbrücken gesetzt werden, sind die Status-LEDs 1..4 nicht mit den PWM Controller-Ports PWM11..8 verbunden. An den unteren Pins dieses Jumpers (beschriftet mit "8" bis "11") können dann die 4 PWM Kanäle kontaktiert und für andere Anwendungen genutzt werden.

Stecker P_PWM4 und Jumper JP_PWM1-3 (PWMs 12-15):

Jumper-Pin PWM Controller-Port PWM-
Kanal
12 PWM12 4
13 PWM13 3
14 PWM14 2
15 PWM15 1

HINWEIS: Wenn auf Jumper JP_PWM1-3 keine Steckbrücken gesetzt werden, sind die PWM Controller-Ports PWM15..13 nicht mit dem Arduino Expander Sockel verbunden. An den mittleren Pins dieser Jumper (beschriftet mit "13" bis "15") können dann die 3 PWM Kanäle kontaktiert und für andere Anwendungen genutzt werden. An P_PWM4 (beschriftet mit "12") kann der PWM Controller-Port PWM12 frei genutzt werden.

I/O Expander 1

Stecker SV_IO1_0 (5V_CH00-07):

Stecker-Pin I/O Expander-Port ArduIO-Funktion
1 +5V
2 GND
3 GP100
4 GP101
5 GP102
6 GP103
7 GP104
8 GP105
9 GP106
10 GP107

Stecker SV_IO1_1 (5V_CH10-17):

Stecker-Pin I/O Expander-Port ArduIO-Funktion RP6-Beleuchtung *
1 +5V +5V
2 GND GND
3 GP110 Abblend-/Standlicht
4 GP111 Fernlicht
5 GP112 Blinker links
6 GP113 Blinker rechts
7 GP114 Bremslicht
8 GP115 Blaues Blinklicht
9 GP116 (Rückfahrlicht)
10 GP117 (Nebellicht)

Zu *) Optional anschließbar!

I/O Expander 3

Stecker SV_IO3_0 (3,3V_CH00-07):

Stecker-Pin I/O Expander-Port ArduIO-Funktion
1 +3,3V
2 GND
3 GP300
4 GP301
5 GP302
6 GP303
7 GP304
8 GP305
9 GP306
10 GP307

Stecker SV_IO3_1 (3,3V_CH10-17):

Stecker-Pin I/O Expander-Port ArduIO-Funktion
1 +3,3V
2 GND
3 GP310
4 GP311
5 GP312
6 GP313
7 GP314
8 GP315
9 GP316
10 GP317

AD/DA Converter 1 und 2

Stecker SV_ADC (5V-ADC):

Stecker-Pin AD/DA Converter-Port ArduIO-Funktion
1 +5V
2 GND
3 AD23
4 AD10
5 AD22
6 AD11
7 AD21
8 AD12
9 AD20
10 AD13 +UB Spannungsmessung *

Zu *) Wenn Jumper JP_AD-UB geschlossen ist! Dann kann AD13 nicht für externe Spannungsmessungen verwendet werden und Pin 10 muss frei bleiben!

I/O Expander 2 und AD/DA Converter 3

Arduino Expander Sockel:

RP6 ArduIO Arduino Expander Sockel
Arduino UNO: ATmega328: RP6_ArduIO:
Sockel-Pin Funktion Pin Funktion Pin Name IO ADDA
0 D0 RX PD0 RXD_PCINT16 P00 GP200 2
1 D1 TX PD1 TXD_PCINT17 P01 GP201 2
2 D2 PD2 INT0_PCINT18 P02 GP202 2
3 D3 PWM PD3 INT1_OC2B_PCINT19 P03 GP203 2
4 D4 PD4 T0_XCK_PCINT20 P04 GP204 2
5 D5 PWM PD5 T1_OC0B_PCINT21 P05 GP205 2
6 D6 PWM PD6 AIN0_OC0A_PCINT22 P06 GP206 2
7 D7 PD7 AIN1_PCINT23 P07 GP207 2
8 D8 PB0 ICP1_CLKO_PCINT0 P15 GP215 2
9 D9 PWM PB1 OC1A_PCINT1 P14 GP214 2
10 D10 PWM PB2 SS_OC1B_PCINT2 P13 GP213 2
11 D11 PWM PB3 MOSI_OC2A_PCINT13 P12 GP212 2
12 D12 PB4 MISO_PCINT4 P11 GP211 2
13 D13 PB5 SCK_PCINT5 P10 GP210 2
0 A0 PC0 ADC0_PCINT8 AIN0 AD30 3
1 A1 PC1 ADC1_PCINT9 AIN1 AD31 3
2 A2 PC2 ADC2_PCINT10 AIN2 AD32 3
3 A3 PC3 ADC3_PCINT11 AIN3 AD33 3
4 A4 SDA PC4 ADC4_SDA_PCINT12 SDA
5 A5 SCL PC5 ADC5_SCL_PCINT13 SCL

Stecker P_IO-ARD (GP16 GP17):

Stecker-Pin I/O Expander-Port IO
1 GP216 2
2 GP217 2

Besondere PWM Controller-Port Verbindungen (PWMs 13-15):

Arduino UNO: ATmega328: RP6_ArduIO:
Sockel-Pin Funktion Pin Funktion Name JP_ Pins *
3 D3 PWM PD3 INT1_OC2B_PCINT19 PWM13 PWM3 2-3
5 D5 PWM PD5 T1_OC0B_PCINT21 PWM15 PWM1 1-2
6 D6 PWM PD6 AIN0_OC0A_PCINT22 PWM15 PWM1 2-3
9 D9 PWM PB1 OC1A_PCINT1 PWM14 PWM2 1-2
10 D10 PWM PB2 SS_OC1B_PCINT2 PWM14 PWM2 2-3
11 D11 PWM PB3 MOSI_OC2A_PCINT13 PWM13 PWM3 1-2

Zu *) Pins von JP_PWMx, die geschlossen (mit einem Jumper überbrückt) werden müssen. ACHTUNG: Wenn auf JP_PWMx Pins überbrückt sind, muss UNBEDINGT der zugehörige Jumper am Expander Sockel (Pin 3, 5, 6, 9..11) auf JP_ARD2 ABGEZOGEN werden!

Arduino-Welt und RP6-System

RP6 ArduIO Arduino Expander Sockel

Mit dem Arduino Expander Sockel auf dem ArduIO Board (Stecker-Belegung siehe hier!) ist es erstmals möglich, Arduino Shields im RP6-System zu nutzen, indem sie auf das ArduIO Board aufgesteckt werden, das wiederum auf dem RP6(v2) sitzt und mit ihm über den XBUS und (optional) den USRBUS verbunden ist. Wenn man Arduino Shields auf dem ArduIO Board nutzt, steuert der Prozessor der RP6 BASE (oder einer der Zusatzplatinen CONTROL M32 oder M256 WIFI) die Funktionen der ArduIO und des/der darauf sitzenden Arduino Shields.

Dabei erfolgt diese Steuerung der ArduIO Funktionen über den I2C Bus. Das Arduino Shield, das auf der ArduIO sitzt, kann dann ebenfalls über I2C und/oder über die digitalen und analogen Portpins des Arduino Expander Sockels angesteuert werden. Wie ein Shield angesteuert wird, hängt von der Art des Shields ab.


Eine weitere Option ist das Aufstecken des ArduIO Boards auf einen Arduino UNO. Optional können noch weitere Arduino Shields auf das ArduIO Board aufgesteckt werden. Der Arduino UNO steuert dabei alle Funktionen der ArduIO und des/der optional darauf sitzenden Arduino Shields.

Dabei erfolgt diese Steuerung der ArduIO Funktionen über den I2C Bus. Das Arduino Shield, das auf der ArduIO sitzt, kann dann ebenfalls über I2C und/oder über die digitalen und analogen Portpins des Arduino Expander Sockels angesteuert werden. Wie ein Shield angesteuert wird, hängt von der Art des Shields ab.


Zuletzt gibt es auch noch die Option, die Kombination aus ArduIO Board und Arduino UNO auf dem RP6(v2) einzusetzen und zusätzlich optional weitere Arduino Shields auf die ArduIO aufzustecken. Dadurch entsteht quasi ein "Multi-Prozessor-System". Man kann völlig frei entscheiden, welches Prozessor-System (aus dem RP6-System oder Arduino UNO) das ArduIO Board und die weiteren Arduino Shields ansteuert.

Was gibt es bei diesen drei Anschluss Optionen des ArduIO Boards zu beachten? Hier soll versucht werden, die wesentlichen Aspekte zu beschreiben.

RP6, ArduIO und Arduino Shield(s)

Dies ist die typische Nutzung des ArduIO Boards und mindestens eines (weiteren) Arduino Shields im RP6-System. Ein Arduino UNO ist dabei NICHT angeschlossen. In dieser Konfiguration steuert der Prozessor des RP6-Systems (auf der RP6 BASE, CONTROL M32 oder M256 WIFI) die ArduIO über den I2C Bus. Das Arduino Shield wird -je nach Art des Shields- ggf. auch über den I2C Bus angesteuert bzw. ausgelesen. Darüber hinaus "simuliert" das ArduIO Board die digitalen und analogen Portpins am Arduino Expander Sockel, die das Shield braucht und die sonst vom Arduino UNO belegt würden. Zur Ansteuerung der ArduIO kann man die ArduIO Library für die RP6 BASE, CONTROL M32 oder M256 WIFI verwenden. Die dazu gehörigen Demos zeigen, wie das geht. Die Software zur Ansteuerung des (zusätzlichen) Arduino Shields muss man natürlich selbst schreiben.

Hinweise zum Betrieb der ArduIO und mindestens eines (weiteren) Arduino Shields im RP6-System:

  • Jumper wie im Abschnitt der Library unter "Standard-Jumperstellung" setzen.
  • Bitte beachten, dass zunächst KEINE Jumper auf JP_ARD2 (digitale Portpins) und JP_ARD3 (analoge Portpins) gesetzt werden.
  • Wichtig ist die Art der Stromversorgung:
    • Die Versorgung des Arduino Shields erfolgt über 3,3V, 5V oder Vin?
    • Diese Jumperstellungen werden hier nicht beschrieben. Siehe Hardware-Artikel!
ACHTUNG: Bei der Festlegung der Stromversorgung sehr sorgfältig vorgehen!!!
  • Es ist je nach Art der weiteren Shields zu entscheiden, wie diese angesteuert bzw. genutzt werden:
    • Wird das (zusätzliche) Shield über den I2C-Bus angesteuert?
    • Wird das (zusätzliche) Shield über die serielle Schnittstelle oder SPI angesteuert?
    • Welche digitalen Portpins des (zusätzlichen) Shields werden WIE (Eingang, Ausgang, PWM...) genutzt?
    • Welche analogen Portpins des (zusätzlichen) Shields werden genutzt?
    • Abhängig vom (zusätzlichen) Arduino Shield sind nach Beantwortung der o.g. Fragen verschiedene Jumperstellungen von JP_ARD2 und JP_ARD3 erforderlich. Grundsätzlich sollten nur DIE Jumper auf JP_ARD2 und JP_ARD3 aufgesteckt werden, die AUSSCHLIESSLICH für die Kommunikation zwischen ArduIO Board und dem/den (zusätzlichen) Shield(s) erforderlich sind!
    • Braucht das (zusätzliche) Shield PWM-Ausgänge für seine Funktion, sind auch ggf. Jumper auf JP_PWM1..3 zu setzen.
HINWEIS:
Immer wenn Jumper auf JP_ARD2, JP_ARD3 oder JP_PWM1..3 aufgesteckt sind, sind
Hardware-Konflikte zwischen Portpins des ArduIO Boards und des/der
(zusätzlichen) Arduino Shields möglich! Diese Konflikte können zu
Beschädigungen aller Platinen führen!   

Ist die Hardware-Konfiguration -wie oben beschrieben- abgeschlossen, kann die ArduIO vom RP6-System über den I2C Bus angesteuert bzw. ausgelesen werden. Das (zusätzliche) Arduino Shield wird ggf. ebenfalls über den I2C Bus angesteuert, zusätzlich "simuliert" das ArduIO Bord -wie gesagt- die digitalen und analogen Portpins am Arduino Expander Sockel, die das Shield braucht.

Arduino UNO, ArduIO und (optional) Arduino Shield(s)

Wenn man das ArduIO Board als reines Arduino Shield nutzen will, dann ist das natürlich gut möglich. Es werden dann keinerlei Bestandteile des RP6-Systems angeschlossen. Der Arduino UNO steuert das ArduIO Board komplett über den I2C Bus. Zur Ansteuerung kann man die ArduIO Library für den Arduino UNO verwenden. Die dazu gehörigen Demos zeigen, wie das geht.

Hinweise zum Betrieb der ArduIO als reines Arduino Shield (ohne RP6 und OHNE weitere Shields):

  • Jumper wie im Abschnitt der Library unter "Standard-Jumperstellung" setzen.
  • Bitte beachten, dass zunächst KEINE Jumper auf JP_ARD2 (digitale Portpins) und JP_ARD3 (analoge Portpins) gesetzt werden.
  • Wichtig ist die Art der Stromversorgung:
    • ArduIO wird vom Arduino UNO versorgt oder umgekehrt?
    • Die Versorgung erfolgt über 3,3V, 5V oder Vin?
    • Diese Jumperstellungen werden hier nicht beschrieben. Siehe Hardware-Artikel!
ACHTUNG: Bei der Festlegung der Stromversorgung sehr sorgfältig vorgehen!!!

Ist die Hardware-Konfiguration -wie oben beschrieben- abgeschlossen, kann die ArduIO vom Arduino UNO über den I2C Bus angesteuert bzw. ausgelesen werden.


Wie bei jedem Arduino Shield können auf das ArduIO Board weitere Arduino Shields aufgesteckt werden.

Hinweise zum Betrieb der ArduIO als reines Arduino Shield (ohne RP6 und MIT weiteren Shields):

  • Es gelten die selben Hinweise wie oben für den Betrieb der ArduIO als reines Arduino Shield (ohne RP6 und OHNE weitere Shields) beschrieben.
  • Es ist je nach Art der weiteren Shields zu entscheiden, wie diese angesteuert bzw. genutzt werden:
    • Wird das (zusätzliche) Shield über den I2C-Bus angesteuert?
    • Wird das (zusätzliche) Shield über die serielle Schnittstelle oder SPI angesteuert?
    • Welche digitalen Portpins des (zusätzlichen) Shields werden WIE (Eingang, Ausgang, PWM...) genutzt?
    • Welche analogen Portpins des (zusätzlichen) Shields werden genutzt?
    • Sollen die digitalen bzw. analogen Portpins des (zusätzlichen) Shields durch den Arduino UNO oder vom ArduIO Board angesteuert bzw. ausgelesen werden? HINWEIS: In der Regel wird das der Arduino UNO machen!
    • Abhängig vom (zusätzlichen) Arduino Shield sind nach Beantwortung der o.g. Fragen verschiedene Jumperstellungen von JP_ARD2 und JP_ARD3 erforderlich. Grundsätzlich sollten nur DIE Jumper auf JP_ARD2 und JP_ARD3 aufgesteckt werden, die AUSSCHLIESSLICH für die Kommunikation zwischen ArduIO Board und dem/den (zusätzlichen) Shield(s) und/oder dem Arduino UNO erforderlich sind!
    • Braucht das (zusätzliche) Shield PWM-Ausgänge für seine Funktion, sind auch ggf. Jumper auf JP_PWM1..3 zu setzen.
HINWEIS:
Immer wenn Jumper auf JP_ARD2, JP_ARD3 oder JP_PWM1..3 aufgesteckt sind, sind
Hardware-Konflikte zwischen Portpins des Arduino UNO, des ArduIO Boards und
des/der (zusätzlichen) Arduino Shields möglich! Diese Konflikte können zu
Beschädigungen aller Platinen führen!

RP6, Arduino UNO, ArduIO und (optional) Arduino Shield(s)

Das ist dann das schon erwähnte "Multi-Prozessor-System". Über das ArduIO Board können alle Prozessoren des RP6-Systems (auf der RP6 BASE, CONTROL M32 oder M256 WIFI) mit dem Prozessor des Arduino UNO zusammen arbeiten. Diese Zusammenarbeit erfolgt primär über den I2C Bus.

Wenn man diese Konfiguration nutzen will, gibt es neben den schon oben angeführten Punkten zu beachten bzw. zu klären:

  • Nutzung des I2 Bus:
    • Soll ein GEMEINSAMER I2C Bus (des Arduino UNO und des RP6-Systems) benutzt werden?
    • Welches Prozessorsystem ist der I2C Master?
    • Welche Aufgabe haben die einzelnen Prozessorsysteme?
    • Welches Prozessorsystem steuert die Funktionen des ArduIO Boards?
  • Ansteuerung des/der (zusätzlichen) Arduino Shields:
    • Abhängig von der Art des Arduino Shields.
    • Hinweise dazu siehe z.B. oben unter "Hinweise zum Betrieb der ArduIO und mindestens eines (weiteren) Arduino Shields ..."!



Siehe auch


Weblinks

Umfangreiche Dokumentation, sämtliche Beispielprogramme und Bibliotheken, Daten, Teilelisten und eine Lötanleitung finden sich HIER.

HIER findet ihr den Hardware-Artikel.



Autoren

--Dirk 01:43, 1. Mär 2015 (CET)


LiFePO4 Speicher Test