aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorMDC Service <michael.schmid@mdc-service.de>2022-05-25 13:10:39 +0200
committerGitHub <noreply@github.com>2022-05-25 13:10:39 +0200
commit385a3627114686d2caadc8f2c0c80e5f04a70f55 (patch)
tree857647a279d4794006af9586df7f7319510ce9e6
parentfc161e7e0692d07ae80f92e8d50a2ec3839c7cf8 (diff)
added drivers in own folder
-rw-r--r--software/drivers/AW9523B.cpp338
-rw-r--r--software/drivers/AW9523B.hpp150
-rw-r--r--software/drivers/board_rev_A.cpp53
-rw-r--r--software/drivers/board_rev_A.hpp61
-rw-r--r--software/drivers/board_rev_B.cpp117
-rw-r--r--software/drivers/board_rev_B.hpp72
-rw-r--r--software/drivers/component.mk4
7 files changed, 795 insertions, 0 deletions
diff --git a/software/drivers/AW9523B.cpp b/software/drivers/AW9523B.cpp
new file mode 100644
index 0000000..ff96f2d
--- /dev/null
+++ b/software/drivers/AW9523B.cpp
@@ -0,0 +1,338 @@
+/*
+ * AW9523B.cpp
+ *
+ * Created on: 26.02.2022
+ * Author: michi
+ * SPDX-FileCopyrightText: 2022 MDC Service <info@mdc-service.de>
+ * SPDX-License-Identifier: GPL-3.0-or-later
+ */
+
+
+
+#ifdef STM32
+ #include "stm32l4xx_hal.h"
+#else
+ #include <sys/types.h>
+ #include <stdio.h>
+ #include "driver/i2c.h"
+ #define I2C_MASTER_TIMEOUT_MS 1000
+#endif
+#include "AW9523B.hpp"
+
+
+//#include <stdint.h>
+//#include <stdbool.h>
+
+
+#define _REG(port, reg) (port == P0 ? reg : reg + 1)
+
+AW9523B *i2c_gpio;
+
+/**
+ * readI2C: read a register of the AW9523B
+ *
+ * @param reg Register to be read.
+ * @returns Value of the register.
+ * @note The STM32 code need to be removed, because V3 will not use an STM32
+ */
+
+uint8_t AW9523B::readI2C(uint8_t reg)
+{
+ //AW9523B_REG_ID
+ uint8_t gelesen = 0;
+ uint16_t MemAddress;
+ MemAddress = reg;
+//HAL_StatusTypeDef HAL_I2C_Mem_Read(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress, uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout)
+#ifdef STM32
+ HAL_StatusTypeDef ret;
+ ret = HAL_I2C_Mem_Read( &(this->i2c_handle), _addr, MemAddress, 1, &gelesen, 1, HAL_MAX_DELAY);
+ if (ret != HAL_OK)
+#else
+ esp_err_t res1;
+ printf("I2C read I2C-Bus:%d Addr:%d Register: %d BEGIN \n", this->i2c_num, _addr, reg );
+ //res1 = i2c_master_read_from_device(this->i2c_num, _addr, /*i2c_buf*/&gelesen, 1, I2C_MASTER_TIMEOUT_MS / portTICK_RATE_MS);
+ res1 = i2c_master_write_read_device(this->i2c_num, _addr, &reg, 1, &gelesen, 2, I2C_MASTER_TIMEOUT_MS / portTICK_RATE_MS);
+ printf(" --> gelesen Byte: %d \n", gelesen );
+ if (res1 != ESP_OK)
+#endif
+ { printf("ERROR I2C read I2C -------------------------- \n"); ESP_ERROR_CHECK_WITHOUT_ABORT(res1); return 0; }
+ else { printf(" I2C read I2C-Bus OK \n"); return gelesen; }
+}
+
+/**
+ * writeI2C: read a register of the AW9523B
+ *
+ * @param reg Register to be written.
+ * @param val Value to be written
+ * @returns true if ok. Otherwise false
+ * @note The STM32 code need to be removed, because V3 will not use an STM32
+ */
+
+uint8_t AW9523B::writeI2C(uint8_t reg, uint8_t val)
+{
+ //AW9523B_REG_ID
+ uint16_t MemAddress;
+ MemAddress = reg;
+ //HAL_I2C_Mem_Write(I2C_HandleTypeDef *hi2c, uint16_t DevAddress, uint16_t MemAddress,
+ //uint16_t MemAddSize, uint8_t *pData, uint16_t Size, uint32_t Timeout)
+#ifdef STM32
+ HAL_StatusTypeDef ret;
+ ret = HAL_I2C_Mem_Write( &(this->i2c_handle), _addr, MemAddress, 1, &val, 1, HAL_MAX_DELAY);
+ if (ret != HAL_OK)
+#else
+ uint8_t I2C_buf[3];
+ esp_err_t res1 = ESP_OK;
+ I2C_buf[0] = reg; //0x02; // write to register 0x02
+ I2C_buf[1] = 255;
+ I2C_buf[2] = 255;
+ //res1 = i2c_master_write_to_device(I2C_MASTER_NUM, I2C_PORTEXP1, I2C_buf, 3, I2C_MASTER_TIMEOUT_MS / portTICK_PERIOD_MS);
+ //ESP_ERROR_CHECK(res1 );
+ if (res1 != ESP_OK)
+#endif
+ { printf("ERROR I2C write I2C -------------------------- \n"); ESP_ERROR_CHECK_WITHOUT_ABORT(res1); return false; }
+ else { printf(" I2C write I2C OK \n"); return true; }
+}
+
+
+#ifdef STM32
+AW9523B::AW9523B(uint8_t address, I2C_HandleTypeDef _i2c_handle) //AD[1:0] address offset
+{
+ i2c_handle = _i2c_handle;
+ _addr = AW9523B_I2C_ADDRESS + (address & 0x03);
+#else
+AW9523B::AW9523B(uint8_t address, int _i2c_num) //AD[1:0] address offset
+{
+ i2c_num = _i2c_num; //I2C number, 0 or 1 on ESP32
+ _addr = 0x58;/*AW9523B_I2C_ADDRESS; 0x58 for first AW9523, 0x58 for the second */
+#endif
+}
+
+/**
+ * begin: initialize the AW9523B
+ *
+ * @returns true if ok. Otherwise false
+ * @note The STM32 code need to be removed, because V3 will not use an STM32
+ */
+
+bool AW9523B::begin()
+{
+// Wire.begin();
+// return readI2C(AW9523B_REG_ID) == AW9523B_ID;
+#ifdef STM32
+ HAL_StatusTypeDef ret;
+ ret = HAL_I2C_IsDeviceReady (&i2c_handle, _addr, 1, 1000);
+ if (ret == HAL_OK)
+#else
+ uint8_t I2C_buf[3];
+ esp_err_t res1 = ESP_OK, res2 = ESP_OK;
+ I2C_buf[0] = 0x7F; // write to soft-RESET register on AW9523
+ I2C_buf[1] = 0x00; // write 0 to reset the AW9523
+// res1 = i2c_master_write_to_device(I2C_MASTER_NUM, I2C_PORTEXP1, I2C_buf, 2, I2C_MASTER_TIMEOUT_MS / portTICK_PERIOD_MS);
+// res2 = i2c_master_write_to_device(I2C_MASTER_NUM, I2C_PORTEXP2, I2C_buf, 2, I2C_MASTER_TIMEOUT_MS / portTICK_PERIOD_MS);
+ printf("\nMaster wrote %d %d %02X\n", res1,res2,I2C_buf[0]);
+
+ if ( readI2C(AW9523B_REG_ID) == AW9523B_ID )
+#endif
+ {
+ return true;
+ } else { return false; }
+}
+
+
+/**
+ * scanAllAddress: scan the I2C bus
+ *
+ * @note writes to the console
+ */
+
+void AW9523B::scanAllAddress(void)
+{
+ esp_err_t res1;
+ uint8_t gelesen = 0;
+ uint8_t reg_addr = AW9523B_REG_ID;
+ printf("Scanning I2C bus for devices:\n");
+ fflush(stdout);
+ for (int i=0; i<255; i++)
+ {
+ //i2c_master_write_read_device(I2C_MASTER_NUM, slave_addr, &reg_addr, 1, data, 2, I2C_MASTER_TIMEOUT_MS / portTICK_RATE_MS);
+ //res1 = i2c_master_read_from_device(0, i, AW9523B_REG_ID, 1, &gelesen, 1, I2C_MASTER_TIMEOUT_MS / portTICK_RATE_MS);
+ res1 = i2c_master_write_read_device(0, i, &reg_addr, 1, &gelesen, 1, I2C_MASTER_TIMEOUT_MS / portTICK_RATE_MS);
+ if (res1 == ESP_OK)
+ {
+ printf("\ndevice found on I2C-address %d, read value: %d AW9523=16 \n", i, gelesen);
+
+ }
+ else { printf("."); }
+ fflush(stdout);
+ gelesen = 0;
+ }
+ printf("\nfinish I2C Bus scan\n");
+}
+
+/**
+ * configInOut: configure port 0 or 1 as Input or Output
+ *
+ * @param port port to configure. Ether 0 or 1
+ * @param inout input or output, type AW9523B_P0_CONF_STATE
+ */
+
+void AW9523B::configInOut(AW9523BPort port, uint8_t inout)
+{
+ writeI2C(_REG(port, AW9523B_P0_CONF_STATE), inout);
+}
+
+/**
+ * configLedGPIO: configure port 0 or 1 as Input or Output
+ *
+ * @param port port to configure. Ether 0 or 1
+ * @param inout input or output, type AW9523B_P0_CONF_STATE
+ */
+
+void AW9523B::configLedGPIO(AW9523BPort port, uint8_t ledGpio)
+{
+ writeI2C(_REG(port, AW9523B_P0_LED_MODE), ledGpio);
+}
+
+/**
+ * setPort0Mode: set the mode of port0
+ *
+ * @param mode ether GPIO or LED
+ */
+
+void AW9523B::setPort0Mode(AW9523BPortMode mode)
+{
+ writeI2C(AW9523B_REG_GLOB_CTR, mode | ledsDim);
+}
+
+/**
+ * setLedsDim: set dim value of the LED mode
+ *
+ * @param dim dimming value
+ */
+
+void AW9523B::setLedsDim(AW9523BLedsDim dim)
+{
+ writeI2C(AW9523B_REG_GLOB_CTR, dim | portMode);
+}
+
+/**
+ * setLed: set dim value of the LED mode
+ *
+ * @param led number of LED to set
+ * @param value dimming value of the LED
+ */
+
+
+void AW9523B::setLed(AW9523BLedDimCtrl led, uint8_t value)
+{
+ writeI2C(led, value);
+}
+
+/**
+ * portIn: set port 0 or 1 as input
+ *
+ * @param port number of port to read. Ether 0 or 1
+ */
+
+void AW9523B::portIn(AW9523BPort port)
+{
+ _portIn = _REG(port, AW9523B_P0_IN_STATE);
+}
+
+/**
+ * portOut:set port 0 or 1 as output
+ *
+ * @param port number of port to write. Ether 0 or 1
+ */
+
+void AW9523B::portOut(AW9523BPort port)
+{
+ _portOut = _REG(port, AW9523B_P0_OUT_STATE);
+}
+
+/**
+ * read: read from port
+ *
+ * @param port number of port to read. Use the previous set _portIn.
+ * @returns the value read as Byte
+ */
+
+uint8_t AW9523B::read()
+{
+ return readI2C(_portIn);
+}
+
+/**
+ * read: read from port 0 or 1
+ *
+ * @param port number of port to read. Ether 0 or 1
+ * @returns the value read as Byte
+ */
+
+uint8_t AW9523B::read(AW9523BPort port)
+{
+ return readI2C(AW9523B_P0_IN_STATE + port);
+}
+
+/**
+ * read: write to port
+ *
+ * @param data value to be written to the port, previously set by _portOut.
+ * @returns the value read as Byte
+ */
+
+uint8_t AW9523B::write(uint8_t data)
+{
+ return writeI2C(_portOut, data);
+}
+
+/**
+ * write: write to port
+ *
+ * @param port the port to write, ether 0 or 1
+ * @param data value to be written to the port.
+ * @returns the value read as Byte
+ */
+
+uint8_t AW9523B::write(AW9523BPort port, uint8_t data)
+{
+ return writeI2C(AW9523B_P0_OUT_STATE + port, data);
+}
+
+
+/**
+ * reset: software reset of the AW9523B
+ *
+ * @note remove the STM32 code
+ */
+
+void AW9523B::reset()
+{
+ writeI2C(AW9523B_REG_SOFT_RST, 0);
+}
+
+#ifdef STM32
+ extern "C" bool AW9523B_init(uint8_t address, I2C_HandleTypeDef _i2c_handle)
+ {
+ i2c_gpio = new AW9523B(address, _i2c_handle);
+ if (!i2c_gpio->begin() )
+ {
+ //Serial.println("Error: AW9523B not found!");
+ return false;
+ } else
+ {
+ i2c_gpio->reset();
+ i2c_gpio->setPort0Mode(PUSH_PULL);
+ return true;
+ }
+ }
+ extern "C" void AW9523B_destroy(void)
+ {
+ delete i2c_gpio;
+ }
+ extern "C" void AW9523B_setAllOutputHigh(void)
+ {
+ i2c_gpio->write(P0, 255);
+ i2c_gpio->write(P1, 255);
+ }
+#endif
diff --git a/software/drivers/AW9523B.hpp b/software/drivers/AW9523B.hpp
new file mode 100644
index 0000000..bf6d1df
--- /dev/null
+++ b/software/drivers/AW9523B.hpp
@@ -0,0 +1,150 @@
+/*
+ * AW9523B.h
+ *
+ * Created on: 26.02.2022
+ * Author: michi
+ * SPDX-FileCopyrightText: 2022 MDC Service <info@mdc-service.de>
+ * SPDX-License-Identifier: GPL-3.0-or-later
+ */
+
+#ifndef _AW9523B_H_
+#define _AW9523B_H_
+
+//#include <Arduino.h>
+//#include <stdint.h>
+//#include <stdbool.h>
+
+#ifdef STM32
+ #include "stm32l4xx_hal.h"
+#endif
+
+
+/** Registers */
+#define AW9523B_I2C_ADDRESS 0x58 ///< I2C base address for AW9523B
+#define AW9523B_REG_ID 0x10 ///< id register
+#define AW9523B_ID 0x23 ///< id value
+#define AW9523B_P0_IN_STATE 0x00 ///< P0 port input state
+#define AW9523B_P1_IN_STATE 0x01 ///< P1 port input state
+#define AW9523B_P0_OUT_STATE 0x02 ///< P0 port output state
+#define AW9523B_P1_OUT_STATE 0x03 ///< P1 port output state
+#define AW9523B_P0_CONF_STATE 0x04 ///< P0 port config state
+#define AW9523B_P1_CONF_STATE 0x05 ///< P1 port config state
+#define AW9523B_REG_GLOB_CTR 0x11 ///< Global control register
+#define AW9523B_P0_LED_MODE 0x12 ///< P0 port led mode switch register
+#define AW9523B_P1_LED_MODE 0x13 ///< P1 port led mode switch register
+#define AW9523B_REG_SOFT_RST 0x7F ///< Soft reset register
+
+
+
+/** AW9523B Port constants */
+enum AW9523BPort
+{
+ P0 = 0x00, // Port 0
+ P1 = 0x01, // Port 1
+};
+
+enum AW9523BPortMode
+{
+ OPEN_DRAIN = 0x00, // Port 0 open drain mode
+ PUSH_PULL = 1 << 4 // Port 0 push pull mode
+};
+
+/** AW9523B Port0 LED dimmer constants: 256 step dimming range select*/
+enum AW9523BLedsDim
+{
+ DIM_MAX = 0x00,//B00, // 0~IMAX 37mA(typical)
+ DIM_MED = 0x01,//B01, // 0~(IMAX×3/4)
+ DIM_LOW = 0x02,//B10, // 0~(IMAX×2/4)
+ DIM_MIN = 0x03,//B11, // 0~(IMAX×1/4)
+};
+
+/** AW9523B LED dimm current control registers*/
+enum AW9523BLedDimCtrl
+{
+ P1_0 = 0x20, // DIM0
+ P1_1 = 0x21, // DIM1
+ P1_2 = 0x22, // DIM2
+ P1_3 = 0x23, // DIM3
+ P0_0 = 0x24, // DIM4
+ P0_1 = 0x25, // DIM5
+ P0_2 = 0x26, // DIM6
+ P0_3 = 0x27, // DIM7
+ P0_4 = 0x28, // DIM8
+ P0_5 = 0x29, // DIM9
+ P0_6 = 0x2A, // DIM10
+ P0_7 = 0x2B, // DIM11
+ P1_4 = 0x2C, // DIM12
+ P1_5 = 0x2D, // DIM13
+ P1_6 = 0x2E, // DIM14
+ P1_7 = 0x2F, // DIM15
+};
+
+// Uncomment to enable debug messages
+//#define AW9523B_DEBUG
+
+// Define where debug output will be printed
+#define DEBUG_PRINTER Serial
+
+// Setup debug printing macros
+#ifdef AW9523B_DEBUG
+#define DEBUG_PRINT(...) \
+ { \
+ DEBUG_PRINTER.print(__VA_ARGS__); \
+ }
+#define DEBUG_PRINTLN(...) \
+ { \
+ DEBUG_PRINTER.println(__VA_ARGS__); \
+ }
+#else
+#define DEBUG_PRINT(...) \
+ { \
+ }
+#define DEBUG_PRINTLN(...) \
+ { \
+ }
+#endif
+
+/**************************************************************************/
+/*!
+ @brief AW9523B I2C 16bit GPIO expander and LED driver
+*/
+/**************************************************************************/
+class AW9523B
+{
+
+public:
+#ifdef STM32
+ AW9523B(uint8_t address, I2C_HandleTypeDef _i2c_handle); //AD[1:0] address offset
+#else
+ AW9523B(uint8_t address, int _i2c_num); //AD[1:0] address offset
+#endif
+ bool begin();
+ void configInOut(AW9523BPort port, uint8_t inout);
+ void configLedGPIO(AW9523BPort port, uint8_t ledGpio);
+ void setPort0Mode(AW9523BPortMode mode);
+ void setLedsDim(AW9523BLedsDim value);
+ void setLed(AW9523BLedDimCtrl led, uint8_t value);
+ void portIn(AW9523BPort port);
+ void portOut(AW9523BPort port);
+ uint8_t read();
+ uint8_t read(AW9523BPort port);
+ uint8_t write(uint8_t data);
+ uint8_t write(AW9523BPort port, uint8_t data);
+ void reset();
+ void scanAllAddress(void);
+private:
+ uint8_t writeI2C(uint8_t reg, uint8_t val);
+ uint8_t readI2C(uint8_t reg);
+ uint8_t _addr;
+ uint8_t _portIn = AW9523B_P0_IN_STATE;
+ uint8_t _portOut = AW9523B_P0_OUT_STATE;
+ AW9523BPortMode portMode = OPEN_DRAIN;
+ AW9523BLedsDim ledsDim = DIM_MAX;
+#ifdef STM32
+ I2C_HandleTypeDef i2c_handle;//Michi
+#else
+ /*i2c_port_t*/int i2c_num;
+#endif
+};
+
+#endif // _AW9523B_H_
diff --git a/software/drivers/board_rev_A.cpp b/software/drivers/board_rev_A.cpp
new file mode 100644
index 0000000..29aa81d
--- /dev/null
+++ b/software/drivers/board_rev_A.cpp
@@ -0,0 +1,53 @@
+/*
+ * board_rev_A.cpp
+ *
+ * Created on: 26.02.2022
+ * Author: michi
+ * SPDX-FileCopyrightText: 2022 MDC Service <info@mdc-service.de>
+ * SPDX-License-Identifier: GPL-3.0-or-later
+ */
+
+
+#include <stdio.h>
+#include <string.h>
+#include <stdlib.h>
+#include "freertos/FreeRTOS.h"
+#include "freertos/task.h"
+#include "freertos/queue.h"
+#include "driver/gpio.h"
+#include "schrank_ant_pcb.h" //contains setting of board revision
+
+#ifndef ESP32_BOARD_REV_B
+
+/**
+ * io_init: initialize Rev. A board
+ *
+ */
+
+void io_init(void)
+{
+
+#define GPO_BIT_MASK (1ULL << PHY_PWR)
+ gpio_config_t o_conf;
+ o_conf.intr_type = GPIO_INTR_DISABLE;
+ o_conf.mode = GPIO_MODE_OUTPUT;
+ o_conf.pin_bit_mask = GPO_BIT_MASK;
+ o_conf.pull_down_en = GPIO_PULLDOWN_ENABLE;
+ o_conf.pull_up_en = GPIO_PULLUP_DISABLE;
+ gpio_config(&o_conf);
+ gpio_set_level((gpio_num_t) PHY_PWR, 1);
+
+ // inputs
+ /*
+ #define GPI_BIT_MASK ((1ULL << SWITCH)|(1ULL << SWITCH))
+ gpio_config_t i_conf;
+ i_conf.intr_type = GPIO_INTR_DISABLE;
+ i_conf.mode = GPIO_MODE_INPUT;
+ i_conf.pin_bit_mask = GPI_BIT_MASK;
+ i_conf.pull_down_en = GPIO_PULLDOWN_DISABLE;
+ i_conf.pull_up_en = GPIO_PULLUP_DISABLE;
+ gpio_config(&i_conf);
+ */
+}
+
+#endif
diff --git a/software/drivers/board_rev_A.hpp b/software/drivers/board_rev_A.hpp
new file mode 100644
index 0000000..9c359cc
--- /dev/null
+++ b/software/drivers/board_rev_A.hpp
@@ -0,0 +1,61 @@
+/*
+ * board_rev_A.hpp
+ *
+ * Created on: 26.02.2022
+ * Author: michi
+ * SPDX-FileCopyrightText: 2022 MDC Service <info@mdc-service.de>
+ * SPDX-License-Identifier: GPL-3.0-or-later
+ */
+
+
+
+
+#ifndef _BOARD_REV_A_H_
+#define _BOARD_REV_A_H_
+
+#include "schrank_ant_pcb.h" //contains setting of board revision
+
+//board definitions for Rev A board (LAN8720 module)
+
+// +3,3V // Pin 1
+// GND // Pin 2
+// ESP_EN // Pin 3
+#define UHF_RXD_MISO 36 // pin 4 UART
+#define LCD_RXD_MISO 39 // pin 5 UART
+// NC pin 6
+#define I2Cint 35 // pin 7 EXP
+//#define SCL 33 // pin 8 EXP disabled Michi, all boards have SCL on 32
+//#define SDA 32 // pin 9 EXP disabled Michi, all boards have SDA on 33
+#define SCL 32 //new Michi 01.05.2022
+#define SDA 33 //new Michi 01.05.2022
+#define EMAC_RXD0_RMII 25 // pin 10 ETH
+#define EMAC_RXD1_RMII 26 // pin 11 ETH
+#define EMAC_RX_CRS_DV 27 // pin 12 ETH
+#define HS2_CLK 14 // pin 13 ETH
+#define PHY_PWR 12 // pin 14 ETH
+// // pin 15 GND
+#define I2C_SDA_40p 13 // pin 16 40p
+// NC pin 17 bis 22
+#define HS2_CMD 15 // pin 23 ETH
+#define HS2_DATA0 02 // pin 24 ETH
+#define ETH_CLKREF 0 // pin 25 ETH
+#define UHF_TXD_MOSI 04 // pin 26 UART
+#define LCD_TXD_MOSI 16 // pin 27 UART
+#define EMAC_CLK_OUT_180 17 // pin 28 ETH
+#define SPI_CS 05 // pin 29 40p
+#define MDIO_RMII 18 // pin 30 ETH
+#define EMAC_TXD0_RMII 19 // pin 31 ETH
+//NC pin 32
+#define EMAC_TX_EN_RMII 21 // pin 33 ETH
+#define RDR_RXD_MISO 03 // pin 34 UART
+#define RDR_TXD_MOSI 01 // pin 35 UART
+#define EMAC_TXD1_RMII 22 // pin 36 ETH
+#define MDC_RMII 23 // pin 37 ETH
+//GND pin 38, 39
+#define I2C_PORTEXP 0x22
+
+
+void io_init(void);
+
+#endif
+
diff --git a/software/drivers/board_rev_B.cpp b/software/drivers/board_rev_B.cpp
new file mode 100644
index 0000000..da2b00e
--- /dev/null
+++ b/software/drivers/board_rev_B.cpp
@@ -0,0 +1,117 @@
+/*
+ * board_rev_B.cpp
+ *
+ * Created on: 26.02.2022
+ * Author: michi
+ * SPDX-FileCopyrightText: 2022 MDC Service <info@mdc-service.de>
+ * SPDX-License-Identifier: GPL-3.0-or-later
+ */
+
+
+#include <stdio.h>
+#include <string.h>
+#include <stdlib.h>
+#include "freertos/FreeRTOS.h"
+#include "freertos/task.h"
+#include "freertos/queue.h"
+#include "driver/gpio.h"
+#include "driver/i2c.h"
+#include "schrank_ant_pcb.h" //contains setting of board revision
+
+#ifdef ESP32_BOARD_REV_B
+#include "board_rev_B.hpp"
+
+/**
+ * io_init: initalize Rev. B boards
+ *
+ */
+
+void io_init(void)
+{
+ #define GPO_BIT_MASK 0 //we dont have GPIO as outputs, all output is done via I2C Port Expander
+/* as we have not ouput, leave default settings
+ gpio_config_t o_conf;
+ o_conf.intr_type = GPIO_INTR_DISABLE;
+ o_conf.mode = GPIO_MODE_OUTPUT;
+ o_conf.pin_bit_mask = GPO_BIT_MASK;
+ o_conf.pull_down_en = GPIO_PULLDOWN_ENABLE;
+ o_conf.pull_up_en = GPIO_PULLUP_DISABLE;
+ gpio_config(&o_conf);
+*/
+ //gpio_set_level((gpio_num_t) PHY_PWR, 1);
+
+ // inputs
+
+ #define IRQ2Esp 34
+ #define I2Cext_INT 35
+ #define GPI_BIT_MASK ((1ULL<<IRQ2Esp) | (1ULL<<I2Cext_INT))
+ //io_conf.pin_bit_mask = (1ULL<<15);//bit mask of the pins that you want to set,e.g.GPIO15
+ gpio_config_t i_conf;
+ i_conf.intr_type = GPIO_INTR_DISABLE;
+ i_conf.mode = GPIO_MODE_INPUT;
+ i_conf.pin_bit_mask = GPI_BIT_MASK;
+ i_conf.pull_down_en = GPIO_PULLDOWN_DISABLE;
+ i_conf.pull_up_en = GPIO_PULLUP_DISABLE;
+ gpio_config(&i_conf);
+
+}
+
+
+
+
+esp_err_t i2c_init(void) {
+ int res1,res2;
+ int I2C_master_port = I2C_MASTER_NUM;
+ uint8_t I2C_buf[5];
+ i2c_config_t I2C_conf = { .mode = I2C_MODE_MASTER, .sda_io_num = I2C_MASTER_SDA_IO, .scl_io_num = I2C_MASTER_SCL_IO, .sda_pullup_en = GPIO_PULLUP_ENABLE, .scl_pullup_en = GPIO_PULLUP_ENABLE, .master { .clk_speed = I2C_MASTER_FREQ_HZ, } };
+ i2c_param_config(I2C_master_port, &I2C_conf);
+
+ printf("\nInstall i2c_driver: Mode=%d sda_io_num=%d scl_io_num=%d\n", I2C_MODE_MASTER, I2C_MASTER_SDA_IO, I2C_MASTER_SCL_IO);
+ res1=i2c_driver_install(I2C_master_port, I2C_conf.mode,
+ I2C_MASTER_RX_BUF_DISABLE, I2C_MASTER_TX_BUF_DISABLE, 0);
+ ESP_ERROR_CHECK_WITHOUT_ABORT(res1);
+ printf("After i2c_driver_install\n");
+ vTaskDelay(500 / portTICK_PERIOD_MS);
+
+//1. Init AW9523 on address 0x00
+ I2C_buf[0] = 0x7F; // write to AW9523 Soft Reset register
+ I2C_buf[1] = 0x00; // write data to output port 1
+ I2C_buf[2] = 0x00; // write data to output port 1
+ printf("I2C write to bus %d to I2C-Adress %d byte0 = %d byte 1 = %d\n", I2C_MASTER_NUM, I2C_PORTEXP1, I2C_buf[0], I2C_buf[1] );
+ res1 = i2c_master_write_to_device(I2C_MASTER_NUM, I2C_PORTEXP1, I2C_buf, 3, I2C_MASTER_TIMEOUT_MS / portTICK_PERIOD_MS);
+ printf("I2C write to bus %d to I2C-Adress %d byte0 = %d byte 1 = %d\n", I2C_MASTER_NUM, I2C_PORTEXP2, I2C_buf[0], I2C_buf[1] );
+ res2 = i2c_master_write_to_device(I2C_MASTER_NUM, I2C_PORTEXP2, I2C_buf, 3, I2C_MASTER_TIMEOUT_MS / portTICK_PERIOD_MS);
+ printf("\nMaster wrote %d %d %02X\n", res1,res2,I2C_buf[0]);
+ printf("After AW9523 soft-RESET\n");
+ vTaskDelay(500 / portTICK_PERIOD_MS);
+
+//2. Set outputs push pull in AW9523 Global Control Register
+ I2C_buf[0] = 0x11; // write data to Global Control Register
+ I2C_buf[1] = 0x10; // write data to Global Control Register, set Bit4 to Push Pull
+ res1 = i2c_master_write_to_device(I2C_MASTER_NUM, I2C_PORTEXP1, I2C_buf, 2, I2C_MASTER_TIMEOUT_MS / portTICK_PERIOD_MS);
+ res2 = i2c_master_write_to_device(I2C_MASTER_NUM, I2C_PORTEXP2, I2C_buf, 2, I2C_MASTER_TIMEOUT_MS / portTICK_PERIOD_MS);
+ printf("\nMaster wrote %d %d %02X\n", res1,res2,I2C_buf[0]);
+
+ I2C_buf[0] = 0x02; // write data to output port 1
+ I2C_buf[1] = 0xFF; // write data to output port 1
+ I2C_buf[2] = 0xFF; // write data to output port 1
+ I2C_buf[3] = 0x00; // write data to output port 1
+ I2C_buf[4] = 0x00; // write data to output port 1
+ res1 = i2c_master_write_to_device(I2C_MASTER_NUM, I2C_PORTEXP1, I2C_buf, 5, I2C_MASTER_TIMEOUT_MS / portTICK_PERIOD_MS);
+ res2 = i2c_master_write_to_device(I2C_MASTER_NUM, I2C_PORTEXP2, I2C_buf, 5, I2C_MASTER_TIMEOUT_MS / portTICK_PERIOD_MS);
+ printf("\nMaster wrote %d %d %02X\n", res1,res2,I2C_buf[0]);
+ printf("After AW9523 all GPIOs HIGH\n");
+ vTaskDelay(500 / portTICK_PERIOD_MS);
+
+
+
+//2. Set AW9523-PhyPower to high
+/* I2C_buf[0] = 0x02; // write to register 0x02
+ I2C_buf[1] = 255; // set all pins high
+ I2C_buf[2] = 255; // set all pins high
+ res1 = i2c_master_write_to_device(I2C_MASTER_NUM, I2C_PORTEXP2, I2C_buf, 3, I2C_MASTER_TIMEOUT_MS / portTICK_PERIOD_MS);
+*/
+ return res1;
+}
+
+#endif
diff --git a/software/drivers/board_rev_B.hpp b/software/drivers/board_rev_B.hpp
new file mode 100644
index 0000000..d890fef
--- /dev/null
+++ b/software/drivers/board_rev_B.hpp
@@ -0,0 +1,72 @@
+/*
+ * board_rev_B.hpp
+ *
+ * Created on: 26.02.2022
+ * Author: michi
+ * SPDX-FileCopyrightText: 2022 MDC Service <info@mdc-service.de>
+ * SPDX-License-Identifier: GPL-3.0-or-later
+ */
+
+#ifndef _BOARD_REV_B_H_
+#define _BOARD_REV_B_H_
+
+//board definitions for Rev B board (LAN8720 on board)
+#include "schrank_ant_pcb.h" //contains setting of board revision
+
+
+#define UHF_RXD_MISO 36 // pin 4 UART
+#define LCD_RXD_MISO 39 // pin 5 UART
+
+#define SCL 32 //new Michi 01.05.2022
+#define SDA 33 //new Michi 01.05.2022
+
+
+#define I2C_MASTER_SCL_IO SCL
+#define I2C_MASTER_SDA_IO SDA
+#define I2C_MASTER_NUM 0 /*!< I2C master i2c port number, the number of i2c peripheral interfaces available will depend on the chip */
+#define I2C_MASTER_FREQ_HZ 100000 /*!< I2C master clock frequency */
+#define I2C_MASTER_TX_BUF_DISABLE 0 /*!< I2C master doesn't need buffer */
+#define I2C_MASTER_RX_BUF_DISABLE 0 /*!< I2C master doesn't need buffer */
+#define I2C_MASTER_TIMEOUT_MS 1000
+#define I2C_PORTEXP 0x22
+#define I2Cint 35
+#define EMAC_RXD0_RMII 25 // pin 10 ETH
+#define EMAC_RXD1_RMII 26 // pin 11 ETH
+#define EMAC_RX_CRS_DV 27
+#define HS2_CLK 14
+//#define PHY_PWR is in Rev B handled by I2C port expander, no longer a GPIO
+//#define I2C_SDA_40p 13 // the I2C to the RasPi 40 port header is switched with the second port expander
+#define HS2_CMD 15
+#define HS2_DATA0 02
+#define ETH_CLKREF 0
+#define UHF_TXD_MOSI 04
+#define LCD_TXD_MOSI 5
+//#define EMAC_CLK_OUT_180 17 // there is no GPIO17 on the WROVER module
+#define SPI_CS 13// was: 05
+#define MDIO_RMII 18
+#define EMAC_TXD0_RMII 19
+#define EMAC_TX_EN_RMII 21
+#define RDR_RXD_MISO 03
+#define RDR_TXD_MOSI 01
+#define EMAC_TXD1_RMII 22
+#define MDC_RMII 23
+//#define I2C_PORTEXP 0x22
+
+#define I2C_MASTER_NUM 0 /*!< I2C master i2c port number, the number of i2c peripheral interfaces available will depend on the chip */
+
+// AW9523 I2C adress P40 1011000 = 88, 0x58
+// AW9523 I2C adress 10110 AD1 AD0 RW
+//#define AW9523B_I2C_ADDRESS_MAIN 88 //0x58
+#define AW9523B_I2C_ADDRESS_MAIN 0x58
+
+// AW9523 I2C adress P40 10110100 = 90, 0x5A
+#define AW9523B_I2C_ADDRESS_ETH 0x5A //90dec
+#define I2C_PORTEXP1 0x58
+#define I2C_PORTEXP2 0x5A
+
+void io_init(void);
+esp_err_t i2c_init(void);
+void kolban_i2cscanner(void );
+
+#endif
+
diff --git a/software/drivers/component.mk b/software/drivers/component.mk
new file mode 100644
index 0000000..a98f634
--- /dev/null
+++ b/software/drivers/component.mk
@@ -0,0 +1,4 @@
+#
+# "main" pseudo-component makefile.
+#
+# (Uses default behaviour of compiling all source files in directory, adding 'include' to include path.)