Added calls to sunxi functions

This commit is contained in:
Tony Kuker 2022-10-29 22:49:46 -05:00
parent 535634d848
commit 97e63a7b01
3 changed files with 381 additions and 447 deletions

View File

@ -22,6 +22,24 @@
"limits": "cpp",
"new": "cpp",
"string": "cpp",
"string_view": "cpp"
"string_view": "cpp",
"bit": "cpp",
"*.tcc": "cpp",
"cctype": "cpp",
"clocale": "cpp",
"cmath": "cpp",
"concepts": "cpp",
"cstdio": "cpp",
"cstdlib": "cpp",
"cwctype": "cpp",
"map": "cpp",
"exception": "cpp",
"initializer_list": "cpp",
"iosfwd": "cpp",
"memory": "cpp",
"numbers": "cpp",
"streambuf": "cpp",
"system_error": "cpp",
"typeinfo": "cpp"
}
}

View File

@ -30,13 +30,14 @@
//
//---------------------------------------------------------------------------
#include <memory>
#include <string.h>
#include <sys/epoll.h>
#include <sys/ioctl.h>
#include <sys/mman.h>
#include "hal/gpiobus_allwinner.h"
#include "hal/gpiobus.h"
#include "hal/gpiobus_allwinner.h"
#include "hal/pi_defs/bpi-gpio.h"
#include "log.h"
@ -49,13 +50,13 @@ extern int wiringPiMode;
// #pragma GCC diagnostic ignored "-Wformat-truncation"
#define GPIO_BANK(pin) ((pin) >> 5)
#define GPIO_NUM(pin) ((pin) & 0x1F)
#define GPIO_NUM(pin) ((pin)&0x1F)
#define GPIO_CFG_INDEX(pin) (((pin) & 0x1F) >> 3)
#define GPIO_CFG_OFFSET(pin) ((((pin) & 0x1F) & 0x7) << 2)
#define GPIO_CFG_INDEX(pin) (((pin)&0x1F) >> 3)
#define GPIO_CFG_OFFSET(pin) ((((pin)&0x1F) & 0x7) << 2)
#define GPIO_PUL_INDEX(pin) (((pin) & 0x1F )>> 4)
#define GPIO_PUL_OFFSET(pin) (((pin) & 0x0F) << 1)
#define GPIO_PUL_INDEX(pin) (((pin)&0x1F) >> 4)
#define GPIO_PUL_OFFSET(pin) (((pin)&0x0F) << 1)
#define SUNXI_R_GPIO_BASE 0x01F02000
#define SUNXI_R_GPIO_REG_OFFSET 0xC00
@ -66,27 +67,26 @@ extern int wiringPiMode;
#define SUNXI_PUD_OFFSET 0x1C
#define SUNXI_BANK_SIZE 0x24
#define MAP_SIZE (4096*2)
#define MAP_SIZE (4096 * 2)
#define MAP_MASK (MAP_SIZE - 1)
// TODO: Delete these. They're just to make things compile for now
int pinToGpio_BPI_M1P [64] = {0};
int pinToGpio_BPI_M2 [64] = {0};
int pinToGpio_BPI_M2M [64] = {0};
int pinToGpio_BPI_M2M_1P1 [64] = {0};
int pinToGpio_BPI_M2P [64] = {0};
int pinToGpio_BPI_M2U [64] = {0};
int pinToGpio_BPI_M3 [64] = {0};
int pinToGpio_BPI_M64 [64] = {0};
int pinTobcm_BPI_M1P [64] = {0};
int pinTobcm_BPI_M2 [64] = {0};
int pinTobcm_BPI_M2M [64] = {0};
int pinTobcm_BPI_M2M_1P1 [64] = {0};
int pinTobcm_BPI_M2P [64] = {0};
int pinTobcm_BPI_M2U [64] = {0};
int pinTobcm_BPI_M3 [64] = {0};
int pinTobcm_BPI_M64 [64] = {0};
int pinToGpio_BPI_M1P[64] = {0};
int pinToGpio_BPI_M2[64] = {0};
int pinToGpio_BPI_M2M[64] = {0};
int pinToGpio_BPI_M2M_1P1[64] = {0};
int pinToGpio_BPI_M2P[64] = {0};
int pinToGpio_BPI_M2U[64] = {0};
int pinToGpio_BPI_M3[64] = {0};
int pinToGpio_BPI_M64[64] = {0};
int pinTobcm_BPI_M1P[64] = {0};
int pinTobcm_BPI_M2[64] = {0};
int pinTobcm_BPI_M2M[64] = {0};
int pinTobcm_BPI_M2M_1P1[64] = {0};
int pinTobcm_BPI_M2P[64] = {0};
int pinTobcm_BPI_M2U[64] = {0};
int pinTobcm_BPI_M3[64] = {0};
int pinTobcm_BPI_M64[64] = {0};
// #define BCM2708_PERI_BASE_DEFAULT 0x20000000
// #define BCM2709_PERI_BASE_DEFAULT 0x3f000000
@ -103,125 +103,117 @@ int pinTobcm_BPI_M64 [64] = {0};
#define PULLUPDN_OFFSET 37 // 0x0094 / 4
#define PULLUPDNCLK_OFFSET 38 // 0x0098 / 4
#define PAGE_SIZE (4*1024)
#define BLOCK_SIZE (4*1024)
#define PAGE_SIZE (4 * 1024)
#define BLOCK_SIZE (4 * 1024)
// BpiBoardsType bpiboard[];
GPIOBUS_Allwinner::BpiBoardsType GPIOBUS_Allwinner::bpiboard [] =
{
{ "bpi-0", -1, 0, 1, 2, 5, 0, NULL, NULL, NULL },
{ "bpi-1", -1, 1, 1, 2, 5, 0, NULL, NULL, NULL },
{ "bpi-2", -1, 2, 1, 2, 5, 0, NULL, NULL, NULL },
{ "bpi-3", -1, 3, 1, 2, 5, 0, NULL, NULL, NULL },
{ "bpi-4", -1, 4, 1, 2, 5, 0, NULL, NULL, NULL },
{ "bpi-5", -1, 5, 1, 2, 5, 0, NULL, NULL, NULL },
{ "bpi-6", -1, 6, 1, 2, 5, 0, NULL, NULL, NULL },
{ "bpi-7", -1, 7, 1, 2, 5, 0, NULL, NULL, NULL },
{ "bpi-8", -1, 8, 1, 2, 5, 0, NULL, NULL, NULL },
{ "bpi-9", -1, 9, 1, 2, 5, 0, NULL, NULL, NULL },
{ "bpi-10", -1, 10, 1, 2, 5, 0, NULL, NULL, NULL },
{ "bpi-11", -1, 11, 1, 2, 5, 0, NULL, NULL, NULL },
{ "bpi-12", -1, 12, 1, 2, 5, 0, NULL, NULL, NULL },
{ "bpi-13", -1, 13, 1, 2, 5, 0, NULL, NULL, NULL },
{ "bpi-14", -1, 14, 1, 2, 5, 0, NULL, NULL, NULL },
{ "bpi-15", -1, 15, 1, 2, 5, 0, NULL, NULL, NULL },
{ "bpi-new", -1, 16, 1, 2, 5, 0, NULL, NULL, NULL },
{ "bpi-x86", -1, 17, 1, 2, 5, 0, NULL, NULL, NULL },
{ "bpi-rpi", -1, 18, 1, 2, 5, 0, NULL, NULL, NULL },
{ "bpi-rpi2", -1, 19, 1, 2, 5, 0, NULL, NULL, NULL },
{ "bpi-rpi3", -1, 20, 1, 2, 5, 0, NULL, NULL, NULL },
{ "bpi-m1", 10001, 21, 1, 2, 5, 0, pinToGpio_BPI_M1P, physToGpio_BPI_M1P, pinTobcm_BPI_M1P },
{ "bpi-m1p", 10001, 22, 1, 2, 5, 0, pinToGpio_BPI_M1P, physToGpio_BPI_M1P, pinTobcm_BPI_M1P },
{ "bpi-r1", 10001, 23, 1, 2, 5, 0, pinToGpio_BPI_M1P, physToGpio_BPI_M1P, pinTobcm_BPI_M1P },
{ "bpi-m2", 10101, 24, 1, 2, 5, 0, pinToGpio_BPI_M2, physToGpio_BPI_M2, pinTobcm_BPI_M2 },
{ "bpi-m3", 10201, 25, 1, 3, 5, 0, pinToGpio_BPI_M3, physToGpio_BPI_M3, pinTobcm_BPI_M3 },
{ "bpi-m2p", 10301, 26, 1, 2, 5, 0, pinToGpio_BPI_M2P, physToGpio_BPI_M2P, pinTobcm_BPI_M2P },
{ "bpi-m64", 10401, 27, 1, 3, 5, 0, pinToGpio_BPI_M64, physToGpio_BPI_M64, pinTobcm_BPI_M64 },
{ "bpi-m2u", 10501, 28, 1, 3, 5, 0, pinToGpio_BPI_M2U, physToGpio_BPI_M2U, pinTobcm_BPI_M2U },
{ "bpi-m2m", 10601, 29, 1, 1, 5, 0, pinToGpio_BPI_M2M, physToGpio_BPI_M2M, pinTobcm_BPI_M2M },
{ "bpi-m2p_H2+", 10701, 30, 1, 2, 5, 0, pinToGpio_BPI_M2P, physToGpio_BPI_M2P, pinTobcm_BPI_M2P },
{ "bpi-m2p_H5", 10801, 31, 1, 2, 5, 0, pinToGpio_BPI_M2P, physToGpio_BPI_M2P, pinTobcm_BPI_M2P },
{ "bpi-m2u_V40", 10901, 32, 1, 3, 5, 0, pinToGpio_BPI_M2U, physToGpio_BPI_M2U, pinTobcm_BPI_M2U },
{ "bpi-m2z", 11001, 33, 1, 1, 5, 0, pinToGpio_BPI_M2P, physToGpio_BPI_M2P, pinTobcm_BPI_M2P },
// { "bpi-r2", 11101, 34, 1, 3, 5, 0, pinToGpio_BPI_R2, physToGpio_BPI_R2, pinTobcm_BPI_R2 },
{ NULL, 0, 0, 1, 2, 5, 0, NULL, NULL, NULL },
} ;
GPIOBUS_Allwinner::BpiBoardsType GPIOBUS_Allwinner::bpiboard[] = {
{"bpi-0", -1, 0, 1, 2, 5, 0, NULL, NULL, NULL},
{"bpi-1", -1, 1, 1, 2, 5, 0, NULL, NULL, NULL},
{"bpi-2", -1, 2, 1, 2, 5, 0, NULL, NULL, NULL},
{"bpi-3", -1, 3, 1, 2, 5, 0, NULL, NULL, NULL},
{"bpi-4", -1, 4, 1, 2, 5, 0, NULL, NULL, NULL},
{"bpi-5", -1, 5, 1, 2, 5, 0, NULL, NULL, NULL},
{"bpi-6", -1, 6, 1, 2, 5, 0, NULL, NULL, NULL},
{"bpi-7", -1, 7, 1, 2, 5, 0, NULL, NULL, NULL},
{"bpi-8", -1, 8, 1, 2, 5, 0, NULL, NULL, NULL},
{"bpi-9", -1, 9, 1, 2, 5, 0, NULL, NULL, NULL},
{"bpi-10", -1, 10, 1, 2, 5, 0, NULL, NULL, NULL},
{"bpi-11", -1, 11, 1, 2, 5, 0, NULL, NULL, NULL},
{"bpi-12", -1, 12, 1, 2, 5, 0, NULL, NULL, NULL},
{"bpi-13", -1, 13, 1, 2, 5, 0, NULL, NULL, NULL},
{"bpi-14", -1, 14, 1, 2, 5, 0, NULL, NULL, NULL},
{"bpi-15", -1, 15, 1, 2, 5, 0, NULL, NULL, NULL},
{"bpi-new", -1, 16, 1, 2, 5, 0, NULL, NULL, NULL},
{"bpi-x86", -1, 17, 1, 2, 5, 0, NULL, NULL, NULL},
{"bpi-rpi", -1, 18, 1, 2, 5, 0, NULL, NULL, NULL},
{"bpi-rpi2", -1, 19, 1, 2, 5, 0, NULL, NULL, NULL},
{"bpi-rpi3", -1, 20, 1, 2, 5, 0, NULL, NULL, NULL},
{"bpi-m1", 10001, 21, 1, 2, 5, 0, pinToGpio_BPI_M1P, physToGpio_BPI_M1P, pinTobcm_BPI_M1P},
{"bpi-m1p", 10001, 22, 1, 2, 5, 0, pinToGpio_BPI_M1P, physToGpio_BPI_M1P, pinTobcm_BPI_M1P},
{"bpi-r1", 10001, 23, 1, 2, 5, 0, pinToGpio_BPI_M1P, physToGpio_BPI_M1P, pinTobcm_BPI_M1P},
{"bpi-m2", 10101, 24, 1, 2, 5, 0, pinToGpio_BPI_M2, physToGpio_BPI_M2, pinTobcm_BPI_M2},
{"bpi-m3", 10201, 25, 1, 3, 5, 0, pinToGpio_BPI_M3, physToGpio_BPI_M3, pinTobcm_BPI_M3},
{"bpi-m2p", 10301, 26, 1, 2, 5, 0, pinToGpio_BPI_M2P, physToGpio_BPI_M2P, pinTobcm_BPI_M2P},
{"bpi-m64", 10401, 27, 1, 3, 5, 0, pinToGpio_BPI_M64, physToGpio_BPI_M64, pinTobcm_BPI_M64},
{"bpi-m2u", 10501, 28, 1, 3, 5, 0, pinToGpio_BPI_M2U, physToGpio_BPI_M2U, pinTobcm_BPI_M2U},
{"bpi-m2m", 10601, 29, 1, 1, 5, 0, pinToGpio_BPI_M2M, physToGpio_BPI_M2M, pinTobcm_BPI_M2M},
{"bpi-m2p_H2+", 10701, 30, 1, 2, 5, 0, pinToGpio_BPI_M2P, physToGpio_BPI_M2P, pinTobcm_BPI_M2P},
{"bpi-m2p_H5", 10801, 31, 1, 2, 5, 0, pinToGpio_BPI_M2P, physToGpio_BPI_M2P, pinTobcm_BPI_M2P},
{"bpi-m2u_V40", 10901, 32, 1, 3, 5, 0, pinToGpio_BPI_M2U, physToGpio_BPI_M2U, pinTobcm_BPI_M2U},
{"bpi-m2z", 11001, 33, 1, 1, 5, 0, pinToGpio_BPI_M2P, physToGpio_BPI_M2P, pinTobcm_BPI_M2P},
// { "bpi-r2", 11101, 34, 1, 3, 5, 0, pinToGpio_BPI_R2, physToGpio_BPI_R2, pinTobcm_BPI_R2 },
{NULL, 0, 0, 1, 2, 5, 0, NULL, NULL, NULL},
};
bool GPIOBUS_Allwinner::Init(mode_e mode, board_type::rascsi_board_type_e rascsi_type)
{
GPIOBUS::Init(mode, rascsi_type);
// Hard-coding to banana pi m2 plus for now
phys_to_gpio_map = make_shared<Banana_Pi_Gpio_Mapping>(banana_pi_m2p_map);
sunxi_setup();
// wiringPiSetup();
// wiringPiMode = WPI_MODE_GPIO;
// LOGTRACE("%s Set Drive Strength", __PRETTY_FUNCTION__);
// // Set Drive Strength to 16mA
// DrvConfig(7);
// wiringPiSetup();
// wiringPiMode = WPI_MODE_GPIO;
// // Set pull up/pull down
// LOGTRACE("%s Set pull up/down....", __PRETTY_FUNCTION__);
// #if SIGNAL_CONTROL_MODE == 0
// int pullmode = GPIO_PULLNONE;
// #elif SIGNAL_CONTROL_MODE == 1
// int pullmode = GPIO_PULLUP;
// #else
// int pullmode = GPIO_PULLDOWN;
// #endif
// LOGTRACE("%s Set Drive Strength", __PRETTY_FUNCTION__);
// // Set Drive Strength to 16mA
// DrvConfig(7);
// // Initialize all signals
// LOGTRACE("%s Initialize all signals....", __PRETTY_FUNCTION__);
// // Set pull up/pull down
// LOGTRACE("%s Set pull up/down....", __PRETTY_FUNCTION__);
// for (int i = 0; SignalTable[i] >= 0; i++) {
// int j = SignalTable[i];
// PinSetSignal(j, OFF);
// PinConfig(j, board_type::gpio_high_low_e::GPIO_INPUT);
// PullConfig(j, pullmode);
// }
// #if SIGNAL_CONTROL_MODE == 0
// int pullmode = GPIO_PULLNONE;
// #elif SIGNAL_CONTROL_MODE == 1
// int pullmode = GPIO_PULLUP;
// #else
// int pullmode = GPIO_PULLDOWN;
// #endif
// // Set control signals
// LOGTRACE("%s Set control signals....", __PRETTY_FUNCTION__);
// PinSetSignal(PIN_ACT, OFF);
// PinSetSignal(PIN_TAD, OFF);
// PinSetSignal(PIN_IND, OFF);
// PinSetSignal(PIN_DTD, OFF);
// PinConfig(PIN_ACT, board_type::gpio_high_low_e::GPIO_OUTPUT);
// PinConfig(PIN_TAD, board_type::gpio_high_low_e::GPIO_OUTPUT);
// PinConfig(PIN_IND, board_type::gpio_high_low_e::GPIO_OUTPUT);
// PinConfig(PIN_DTD, board_type::gpio_high_low_e::GPIO_OUTPUT);
// // Initialize all signals
// LOGTRACE("%s Initialize all signals....", __PRETTY_FUNCTION__);
// // Set the ENABLE signal
// // This is used to show that the application is running
// PinSetSignal(PIN_ENB, ENB_OFF);
// PinConfig(PIN_ENB, board_type::gpio_high_low_e::GPIO_OUTPUT);
// for (int i = 0; SignalTable[i] >= 0; i++) {
// int j = SignalTable[i];
// PinSetSignal(j, OFF);
// PinConfig(j, board_type::gpio_high_low_e::GPIO_INPUT);
// PullConfig(j, pullmode);
// }
// // Create work table
// // Set control signals
// LOGTRACE("%s Set control signals....", __PRETTY_FUNCTION__);
// PinSetSignal(PIN_ACT, OFF);
// PinSetSignal(PIN_TAD, OFF);
// PinSetSignal(PIN_IND, OFF);
// PinSetSignal(PIN_DTD, OFF);
// PinConfig(PIN_ACT, board_type::gpio_high_low_e::GPIO_OUTPUT);
// PinConfig(PIN_TAD, board_type::gpio_high_low_e::GPIO_OUTPUT);
// PinConfig(PIN_IND, board_type::gpio_high_low_e::GPIO_OUTPUT);
// PinConfig(PIN_DTD, board_type::gpio_high_low_e::GPIO_OUTPUT);
// LOGTRACE("%s MakeTable....", __PRETTY_FUNCTION__);
// MakeTable();
// // Set the ENABLE signal
// // This is used to show that the application is running
// PinSetSignal(PIN_ENB, ENB_OFF);
// PinConfig(PIN_ENB, board_type::gpio_high_low_e::GPIO_OUTPUT);
// // Finally, enable ENABLE
// LOGTRACE("%s Finally, enable ENABLE....", __PRETTY_FUNCTION__);
// // Show the user that this app is running
// SetControl(PIN_ENB, ENB_ON);
// // Create work table
// LOGTRACE("%s MakeTable....", __PRETTY_FUNCTION__);
// MakeTable();
// // Finally, enable ENABLE
// LOGTRACE("%s Finally, enable ENABLE....", __PRETTY_FUNCTION__);
// // Show the user that this app is running
// SetControl(PIN_ENB, ENB_ON);
// // if(!SetupPollSelectEvent()){
// // LOGERROR("Failed to setup SELECT poll event");
// // return false;
// // }
// // if(!SetupPollSelectEvent()){
// // LOGERROR("Failed to setup SELECT poll event");
// // return false;
// // }
return true;
// SetMode(PIN_IND, OUTPUT);
// SetMode(PIN_TAD, OUTPUT);
// SetMode(PIN_DTD, OUTPUT);
@ -229,7 +221,6 @@ bool GPIOBUS_Allwinner::Init(mode_e mode, board_type::rascsi_board_type_e rascsi
// PullConfig(PIN_IND, GPIO_PULLUP);
// PullConfig(PIN_IND, GPIO_PULLUP);
// SetMode(PIN_DT0, OUTPUT);
// SetMode(PIN_DT1, OUTPUT);
// SetMode(PIN_DT2, OUTPUT);
@ -254,13 +245,12 @@ bool GPIOBUS_Allwinner::Init(mode_e mode, board_type::rascsi_board_type_e rascsi
// PullConfig(PIN_IO, GPIO_PULLNONE);
// PullConfig(PIN_TAD, GPIO_PULLNONE);
// PullConfig(PIN_IND, GPIO_PULLNONE);
}
void GPIOBUS_Allwinner::Cleanup()
{
LOGTRACE("%s", __PRETTY_FUNCTION__);
munmap((void *)gpio_map, BLOCK_SIZE);
#if defined(__x86_64__) || defined(__X86__)
return;
#else
@ -298,96 +288,11 @@ void GPIOBUS_Allwinner::Cleanup()
LOGWARN("%s NOT IMPLEMENTED", __PRETTY_FUNCTION__)
}
void GPIOBUS_Allwinner::Reset()
{
// #if defined(__x86_64__) || defined(__X86__)
return;
// #else
// int i;
// int j;
// // Turn off active signal
// SetControl(PIN_ACT, ACT_OFF);
// // Set all signals to off
// for (i = 0;; i++) {
// j = SignalTable[i];
// if (j < 0) {
// break;
// }
// SetSignal(j, board_type::gpio_high_low_e::GPIO_STATE_LOW);
// }
// if (actmode == mode_e::TARGET) {
// // Target mode
// // Set target signal to input
// SetControl(PIN_TAD, TAD_IN);
// SetMode(PIN_BSY, RASCSI_PIN_IN);
// SetMode(PIN_MSG, RASCSI_PIN_IN);
// SetMode(PIN_CD, RASCSI_PIN_IN);
// SetMode(PIN_REQ, RASCSI_PIN_IN);
// SetMode(PIN_IO, RASCSI_PIN_IN);
// // Set the initiator signal to input
// SetControl(PIN_IND, IND_IN);
// SetMode(PIN_SEL, RASCSI_PIN_IN);
// SetMode(PIN_ATN, RASCSI_PIN_IN);
// SetMode(PIN_ACK, RASCSI_PIN_IN);
// SetMode(PIN_RST, RASCSI_PIN_IN);
// // Set data bus signals to input
// SetControl(PIN_DTD, DTD_IN);
// SetMode(PIN_DT0, RASCSI_PIN_IN);
// SetMode(PIN_DT1, RASCSI_PIN_IN);
// SetMode(PIN_DT2, RASCSI_PIN_IN);
// SetMode(PIN_DT3, RASCSI_PIN_IN);
// SetMode(PIN_DT4, RASCSI_PIN_IN);
// SetMode(PIN_DT5, RASCSI_PIN_IN);
// SetMode(PIN_DT6, RASCSI_PIN_IN);
// SetMode(PIN_DT7, RASCSI_PIN_IN);
// SetMode(PIN_DP, RASCSI_PIN_IN);
// } else {
// // Initiator mode
// // Set target signal to input
// SetControl(PIN_TAD, TAD_IN);
// SetMode(PIN_BSY, RASCSI_PIN_IN);
// SetMode(PIN_MSG, RASCSI_PIN_IN);
// SetMode(PIN_CD, RASCSI_PIN_IN);
// SetMode(PIN_REQ, RASCSI_PIN_IN);
// SetMode(PIN_IO, RASCSI_PIN_IN);
// // Set the initiator signal to output
// SetControl(PIN_IND, IND_OUT);
// SetMode(PIN_SEL, RASCSI_PIN_OUT);
// SetMode(PIN_ATN, RASCSI_PIN_OUT);
// SetMode(PIN_ACK, RASCSI_PIN_OUT);
// SetMode(PIN_RST, RASCSI_PIN_OUT);
// // Set the data bus signals to output
// SetControl(PIN_DTD, DTD_OUT);
// SetMode(PIN_DT0, RASCSI_PIN_OUT);
// SetMode(PIN_DT1, RASCSI_PIN_OUT);
// SetMode(PIN_DT2, RASCSI_PIN_OUT);
// SetMode(PIN_DT3, RASCSI_PIN_OUT);
// SetMode(PIN_DT4, RASCSI_PIN_OUT);
// SetMode(PIN_DT5, RASCSI_PIN_OUT);
// SetMode(PIN_DT6, RASCSI_PIN_OUT);
// SetMode(PIN_DT7, RASCSI_PIN_OUT);
// SetMode(PIN_DP, RASCSI_PIN_OUT);
// }
// // Initialize all signals
// signals = 0;
// #endif // ifdef __x86_64__ || __X86__
}
BYTE GPIOBUS_Allwinner::GetDAT()
{
LOGWARN("%s NOT IMPLEMENTED", __PRETTY_FUNCTION__)
// LOGDEBUG("0:%02X 1:%02X 2:%02X 3:%02X 4:%02X 5:%02X 6:%02X 7:%02X P:%02X", GetSignal(PIN_DT0), GetSignal(PIN_DT1),GetSignal(PIN_DT2),GetSignal(PIN_DT3),GetSignal(PIN_DT4),GetSignal(PIN_DT5),GetSignal(PIN_DT6),GetSignal(PIN_DT7),GetSignal(PIN_DP));
// LOGDEBUG("0:%02X 1:%02X 2:%02X 3:%02X 4:%02X 5:%02X 6:%02X 7:%02X P:%02X", GetSignal(PIN_DT0),
// GetSignal(PIN_DT1),GetSignal(PIN_DT2),GetSignal(PIN_DT3),GetSignal(PIN_DT4),GetSignal(PIN_DT5),GetSignal(PIN_DT6),GetSignal(PIN_DT7),GetSignal(PIN_DP));
// // TODO: This is crazy inefficient...
// DWORD data =
// ((GetSignal(PIN_DT0) ? 0x01: 0x00)<< 0) |
@ -415,7 +320,6 @@ void GPIOBUS_Allwinner::SetDAT(BYTE dat)
// SetSignal(PIN_DT6, dat & (1 << 6));
// SetSignal(PIN_DT7, dat & (1 << 7));
LOGWARN("%s NOT IMPLEMENTED", __PRETTY_FUNCTION__)
}
void GPIOBUS_Allwinner::MakeTable(void)
@ -425,13 +329,16 @@ void GPIOBUS_Allwinner::MakeTable(void)
void GPIOBUS_Allwinner::SetControl(board_type::pi_physical_pin_e pin, board_type::gpio_high_low_e ast)
{
// GPIOBUS_Allwinner::SetSignal(pin, ast);
GPIOBUS_Allwinner::SetSignal(pin, ast);
LOGWARN("%s NOT IMPLEMENTED", __PRETTY_FUNCTION__)
}
void GPIOBUS_Allwinner::SetMode(board_type::pi_physical_pin_e pin, board_type::gpio_direction_e mode)
{
int gpio_num = phys_to_gpio_map->phys_to_gpio_map.at(pin);
int sunxi_gpio_direction = (mode == board_type::gpio_direction_e::GPIO_INPUT) ? INPUT : OUTPUT;
sunxi_setup_gpio(gpio_num, sunxi_gpio_direction, -1);
// LOGWARN("%s NOT IMPLEMENTED", __PRETTY_FUNCTION__)
// if(mode == board_type::gpio_high_low_e::GPIO_INPUT){
// pinMode(pin, INPUT);
@ -439,23 +346,31 @@ void GPIOBUS_Allwinner::SetMode(board_type::pi_physical_pin_e pin, board_type::g
// }else{
// pinMode(pin, OUTPUT);
// }
LOGWARN("%s NOT IMPLEMENTED", __PRETTY_FUNCTION__)
// LOGWARN("%s NOT IMPLEMENTED", __PRETTY_FUNCTION__)
}
bool GPIOBUS_Allwinner::GetSignal(board_type::pi_physical_pin_e pin) const
bool GPIOBUS_Allwinner::GetSignal(board_type::pi_physical_pin_e pin)
{
LOGWARN("%s NOT IMPLEMENTED", __PRETTY_FUNCTION__)
int gpio_num = phys_to_gpio_map->phys_to_gpio_map.at(pin);
int sunxi_gpio_state = sunxi_input_gpio(gpio_num);
if (sunxi_gpio_state == HIGH) {
return true;
} else {
return false;
}
// return (digitalRead(pin) != 0);
}
void GPIOBUS_Allwinner::SetSignal(board_type::pi_physical_pin_e pin, board_type::gpio_high_low_e ast)
{
LOGWARN("%s NOT IMPLEMENTED", __PRETTY_FUNCTION__)
int gpio_num = phys_to_gpio_map->phys_to_gpio_map.at(pin);
int sunxi_gpio_state = (ast == board_type::gpio_high_low_e::GPIO_STATE_HIGH) ? HIGH : LOW;
sunxi_output_gpio(gpio_num, sunxi_gpio_state);
// LOGWARN("%s NOT IMPLEMENTED", __PRETTY_FUNCTION__)
// digitalWrite(pin, ast);
}
//---------------------------------------------------------------------------
//
// Wait for signal change
@ -466,33 +381,31 @@ bool GPIOBUS_Allwinner::WaitSignal(board_type::pi_physical_pin_e pin, board_type
{
LOGERROR("%s not implemented!!", __PRETTY_FUNCTION__)
// {
// // Get current time
// uint32_t now = SysTimer::instance().GetTimerLow();
// {
// // Get current time
// uint32_t now = SysTimer::instance().GetTimerLow();
// // Calculate timeout (3000ms)
// uint32_t timeout = 3000 * 1000;
// // Calculate timeout (3000ms)
// uint32_t timeout = 3000 * 1000;
// // end immediately if the signal has changed
// do {
// // Immediately upon receiving a reset
// Acquire();
// if (GetRST()) {
// return false;
// }
// // end immediately if the signal has changed
// do {
// // Immediately upon receiving a reset
// Acquire();
// if (GetRST()) {
// return false;
// }
// // Check for the signal edge
// if (((signals >> pin) ^ ~ast) & 1) {
// return true;
// }
// } while ((SysTimer::instance().GetTimerLow() - now) < timeout);
// // Check for the signal edge
// if (((signals >> pin) ^ ~ast) & 1) {
// return true;
// }
// } while ((SysTimer::instance().GetTimerLow() - now) < timeout);
// We timed out waiting for the signal
return false;
}
void GPIOBUS_Allwinner::DisableIRQ()
{
LOGERROR("%s not implemented!!", __PRETTY_FUNCTION__)
@ -505,7 +418,9 @@ void GPIOBUS_Allwinner::EnableIRQ()
void GPIOBUS_Allwinner::PinConfig(board_type::pi_physical_pin_e pin, board_type::gpio_direction_e mode)
{
LOGERROR("%s not implemented!!", __PRETTY_FUNCTION__)
int gpio_num = phys_to_gpio_map->phys_to_gpio_map.at(pin);
int sunxi_gpio_state = (mode == board_type::gpio_direction_e::GPIO_INPUT) ? INPUT : OUTPUT;
sunxi_output_gpio(gpio_num, sunxi_gpio_state);
// if(mode == board_type::gpio_high_low_e::GPIO_INPUT){
// pinMode(pin, INPUT);
@ -515,33 +430,36 @@ void GPIOBUS_Allwinner::PinConfig(board_type::pi_physical_pin_e pin, board_type:
// }
}
void GPIOBUS_Allwinner::PullConfig(board_type::pi_physical_pin_e pin, board_type::gpio_pull_up_down_e mode)
{
// Note: this will throw an exception if an invalid pin is specified
int gpio_num = phys_to_gpio_map->phys_to_gpio_map.at(pin);
// switch (mode)
// {
// case GPIO_PULLNONE:
// pullUpDnControl(pin,PUD_OFF);
// break;
// case GPIO_PULLUP:
// pullUpDnControl(pin,PUD_UP);
// break;
// case GPIO_PULLDOWN:
// pullUpDnControl(pin,PUD_DOWN);
// break;
// default:
// LOGERROR("%s INVALID PIN MODE", __PRETTY_FUNCTION__);
// return;
// }
switch (mode) {
case board_type::gpio_pull_up_down_e::GPIO_PULLNONE:
sunxi_set_pullupdn(gpio_num, PUD_OFF);
break;
case board_type::gpio_pull_up_down_e::GPIO_PULLUP:
sunxi_set_pullupdn(gpio_num, PUD_UP);
break;
case board_type::gpio_pull_up_down_e::GPIO_PULLDOWN:
sunxi_set_pullupdn(gpio_num, PUD_DOWN);
break;
default:
LOGERROR("%s INVALID PIN MODE", __PRETTY_FUNCTION__);
return;
}
LOGERROR("%s not implemented!!", __PRETTY_FUNCTION__)
}
void GPIOBUS_Allwinner::PinSetSignal(board_type::pi_physical_pin_e pin, board_type::gpio_high_low_e ast)
{
int gpio_num = phys_to_gpio_map->phys_to_gpio_map.at(pin);
int sunxi_gpio_state = (ast == board_type::gpio_high_low_e::GPIO_STATE_HIGH) ? HIGH : LOW;
sunxi_output_gpio(gpio_num, sunxi_gpio_state);
// digitalWrite(pin, ast);
LOGERROR("%s not implemented!!", __PRETTY_FUNCTION__)
// LOGERROR("%s not implemented!!", __PRETTY_FUNCTION__)
}
void GPIOBUS_Allwinner::DrvConfig(DWORD drive)
@ -560,43 +478,40 @@ uint32_t GPIOBUS_Allwinner::Acquire()
#pragma GCC diagnostic pop
uint32_t GPIOBUS_Allwinner::sunxi_readl(volatile uint32_t *addr)
{
#ifndef __arm__
#ifndef __arm__
(void)addr;
return 0;
#else
#else
printf("sunxi_readl\n");
uint32_t val = 0;
uint32_t mmap_base = (uint32_t)addr & (~MAP_MASK);
uint32_t mmap_seek = ((uint32_t)addr - mmap_base) >> 2;
val = *(gpio_map + mmap_seek);
return val;
#endif
#endif
}
void GPIOBUS_Allwinner::sunxi_writel(volatile uint32_t *addr, uint32_t val)
{
#ifndef __arm__
#ifndef __arm__
(void)addr;
(void)val;
return;
#else
#else
printf("sunxi_writel\n");
uint32_t mmap_base = (uint32_t)addr & (~MAP_MASK);
uint32_t mmap_seek =( (uint32_t)addr - mmap_base) >> 2;
uint32_t mmap_seek = ((uint32_t)addr - mmap_base) >> 2;
*(gpio_map + mmap_seek) = val;
#endif
#endif
}
int GPIOBUS_Allwinner::sunxi_setup(void)
{
#ifndef __arm__
#ifndef __arm__
return SETUP_MMAP_FAIL;
#else
#else
int mem_fd;
uint8_t *gpio_mem;
// uint8_t *r_gpio_mem;
@ -610,79 +525,82 @@ int GPIOBUS_Allwinner::sunxi_setup(void)
printf("enter to sunxi_setup\n");
// mmap the GPIO memory registers
if ((mem_fd = open("/dev/mem", O_RDWR|O_SYNC) ) < 0)
if ((mem_fd = open("/dev/mem", O_RDWR | O_SYNC)) < 0)
return SETUP_DEVMEM_FAIL;
if ((gpio_mem = (uint8_t*)malloc(BLOCK_SIZE + (PAGE_SIZE-1))) == NULL)
if ((gpio_mem = (uint8_t *)malloc(BLOCK_SIZE + (PAGE_SIZE - 1))) == NULL)
return SETUP_MALLOC_FAIL;
if ((uint32_t)gpio_mem % PAGE_SIZE)
gpio_mem += PAGE_SIZE - ((uint32_t)gpio_mem % PAGE_SIZE);
gpio_map = (uint32_t *)mmap( (caddr_t)gpio_mem, BLOCK_SIZE, PROT_READ|PROT_WRITE, MAP_SHARED|MAP_FIXED, mem_fd, SUNXI_GPIO_BASE);
pio_map = gpio_map + (SUNXI_GPIO_REG_OFFSET>>2);
//printf("gpio_mem[%x] gpio_map[%x] pio_map[%x]\n", gpio_mem, gpio_map, pio_map);
//R_PIO GPIO LMN
r_gpio_map = (uint32_t *)mmap( (caddr_t)0, BLOCK_SIZE, PROT_READ|PROT_WRITE, MAP_SHARED, mem_fd, SUNXI_R_GPIO_BASE);
r_pio_map = r_gpio_map + (SUNXI_R_GPIO_REG_OFFSET>>2);
//printf("r_gpio_map[%x] r_pio_map[%x]\n", r_gpio_map, r_pio_map);
gpio_map = (uint32_t *)mmap((caddr_t)gpio_mem, BLOCK_SIZE, PROT_READ | PROT_WRITE, MAP_SHARED | MAP_FIXED, mem_fd,
SUNXI_GPIO_BASE);
pio_map = gpio_map + (SUNXI_GPIO_REG_OFFSET >> 2);
// printf("gpio_mem[%x] gpio_map[%x] pio_map[%x]\n", gpio_mem, gpio_map, pio_map);
// R_PIO GPIO LMN
r_gpio_map =
(uint32_t *)mmap((caddr_t)0, BLOCK_SIZE, PROT_READ | PROT_WRITE, MAP_SHARED, mem_fd, SUNXI_R_GPIO_BASE);
r_pio_map = r_gpio_map + (SUNXI_R_GPIO_REG_OFFSET >> 2);
// printf("r_gpio_map[%x] r_pio_map[%x]\n", r_gpio_map, r_pio_map);
if ((int32_t)gpio_map < 0)
return SETUP_MMAP_FAIL;
return SETUP_OK;
#endif
#endif
}
void GPIOBUS_Allwinner::sunxi_set_pullupdn(int gpio, int pud)
{
#ifndef __arm__
#ifndef __arm__
(void)gpio;
(void)pud;
return;
#else
#else
uint32_t regval = 0;
int bank = GPIO_BANK(gpio); //gpio >> 5
int bank = GPIO_BANK(gpio); // gpio >> 5
int index = GPIO_PUL_INDEX(gpio); // (gpio & 0x1f) >> 4
int offset = GPIO_PUL_OFFSET(gpio); // (gpio) & 0x0F) << 1
printf("sunxi_set_pullupdn\n");
sunxi_gpio_t *pio = &((sunxi_gpio_reg_t *) pio_map)->gpio_bank[bank];
/* DK, for PL and PM */
if(bank >= 11) {
sunxi_gpio_t *pio = &((sunxi_gpio_reg_t *)pio_map)->gpio_bank[bank];
/* DK, for PL and PM */
if (bank >= 11) {
bank -= 11;
pio = &((sunxi_gpio_reg_t *) r_pio_map)->gpio_bank[bank];
pio = &((sunxi_gpio_reg_t *)r_pio_map)->gpio_bank[bank];
}
regval = *(&pio->PULL[0] + index);
regval &= ~(3 << offset);
regval |= pud << offset;
*(&pio->PULL[0] + index) = regval;
#endif
#endif
}
void GPIOBUS_Allwinner::sunxi_setup_gpio(int gpio, int direction, int pud)
{
#ifndef __arm__
#ifndef __arm__
(void)gpio;
(void)direction;
(void)pud;
return;
#else
#else
uint32_t regval = 0;
int bank = GPIO_BANK(gpio); //gpio >> 5
int bank = GPIO_BANK(gpio); // gpio >> 5
int index = GPIO_CFG_INDEX(gpio); // (gpio & 0x1F) >> 3
int offset = GPIO_CFG_OFFSET(gpio); // ((gpio & 0x1F) & 0x7) << 2
printf("sunxi_setup_gpio\n");
sunxi_gpio_t *pio = &((sunxi_gpio_reg_t *) pio_map)->gpio_bank[bank];
/* DK, for PL and PM */
if(bank >= 11) {
sunxi_gpio_t *pio = &((sunxi_gpio_reg_t *)pio_map)->gpio_bank[bank];
/* DK, for PL and PM */
if (bank >= 11) {
bank -= 11;
pio = &((sunxi_gpio_reg_t *) r_pio_map)->gpio_bank[bank];
pio = &((sunxi_gpio_reg_t *)r_pio_map)->gpio_bank[bank];
}
if (pud != -1) {
set_pullupdn(gpio, pud);
}
regval = *(&pio->CFG[0] + index);
regval &= ~(0x7 << offset); // 0xf?
if (INPUT == direction) {
@ -691,24 +609,24 @@ void GPIOBUS_Allwinner::sunxi_setup_gpio(int gpio, int direction, int pud)
regval |= (1 << offset);
*(&pio->CFG[0] + index) = regval;
} else {
printf("line:%dgpio number error\n",__LINE__);
printf("line:%dgpio number error\n", __LINE__);
}
#endif
#endif
}
// Contribution by Eric Ptak <trouch@trouch.com>
int GPIOBUS_Allwinner::sunxi_gpio_function(int gpio)
{
uint32_t regval = 0;
int bank = GPIO_BANK(gpio); //gpio >> 5
int bank = GPIO_BANK(gpio); // gpio >> 5
int index = GPIO_CFG_INDEX(gpio); // (gpio & 0x1F) >> 3
int offset = GPIO_CFG_OFFSET(gpio); // ((gpio & 0x1F) & 0x7) << 2
printf("sunxi_gpio_function\n");
sunxi_gpio_t *pio = &((sunxi_gpio_reg_t *) pio_map)->gpio_bank[bank];
/* DK, for PL and PM */
if(bank >= 11) {
sunxi_gpio_t *pio = &((sunxi_gpio_reg_t *)pio_map)->gpio_bank[bank];
/* DK, for PL and PM */
if (bank >= 11) {
bank -= 11;
pio = &((sunxi_gpio_reg_t *) r_pio_map)->gpio_bank[bank];
pio = &((sunxi_gpio_reg_t *)r_pio_map)->gpio_bank[bank];
}
regval = *(&pio->CFG[0] + index);
@ -719,15 +637,15 @@ int GPIOBUS_Allwinner::sunxi_gpio_function(int gpio)
void GPIOBUS_Allwinner::sunxi_output_gpio(int gpio, int value)
{
int bank = GPIO_BANK(gpio); //gpio >> 5
int bank = GPIO_BANK(gpio); // gpio >> 5
int num = GPIO_NUM(gpio); // gpio & 0x1F
printf("gpio(%d) bank(%d) num(%d)\n", gpio, bank, num);
sunxi_gpio_t *pio = &((sunxi_gpio_reg_t *) pio_map)->gpio_bank[bank];
/* DK, for PL and PM */
if(bank >= 11) {
sunxi_gpio_t *pio = &((sunxi_gpio_reg_t *)pio_map)->gpio_bank[bank];
/* DK, for PL and PM */
if (bank >= 11) {
bank -= 11;
pio = &((sunxi_gpio_reg_t *) r_pio_map)->gpio_bank[bank];
pio = &((sunxi_gpio_reg_t *)r_pio_map)->gpio_bank[bank];
}
if (value == 0)
@ -739,15 +657,15 @@ void GPIOBUS_Allwinner::sunxi_output_gpio(int gpio, int value)
int GPIOBUS_Allwinner::sunxi_input_gpio(int gpio)
{
uint32_t regval = 0;
int bank = GPIO_BANK(gpio); //gpio >> 5
int bank = GPIO_BANK(gpio); // gpio >> 5
int num = GPIO_NUM(gpio); // gpio & 0x1F
printf("gpio(%d) bank(%d) num(%d)\n", gpio, bank, num);
sunxi_gpio_t *pio = &((sunxi_gpio_reg_t *) pio_map)->gpio_bank[bank];
/* DK, for PL and PM */
if(bank >= 11) {
sunxi_gpio_t *pio = &((sunxi_gpio_reg_t *)pio_map)->gpio_bank[bank];
/* DK, for PL and PM */
if (bank >= 11) {
bank -= 11;
pio = &((sunxi_gpio_reg_t *) r_pio_map)->gpio_bank[bank];
pio = &((sunxi_gpio_reg_t *)r_pio_map)->gpio_bank[bank];
}
regval = *(&pio->DAT);
@ -756,48 +674,48 @@ int GPIOBUS_Allwinner::sunxi_input_gpio(int gpio)
return regval;
}
int GPIOBUS_Allwinner::bpi_piGpioLayout (void)
int GPIOBUS_Allwinner::bpi_piGpioLayout(void)
{
FILE *bpiFd ;
FILE *bpiFd;
char buffer[1024];
char hardware[1024];
struct BPIBoards *board = nullptr;
static int gpioLayout = -1 ;
static int gpioLayout = -1;
if (gpioLayout != -1) // No point checking twice
return gpioLayout ;
return gpioLayout;
bpi_found = 0; // -1: not init, 0: init but not found, 1: found
if ((bpiFd = fopen("/var/lib/bananapi/board.sh", "r")) == NULL) {
return -1;
}
while(!feof(bpiFd)) {
while (!feof(bpiFd)) {
// TODO: check the output of fgets()
char *ret = fgets(buffer, sizeof(buffer), bpiFd);
(void)ret;
sscanf(buffer, "BOARD=%s", hardware);
LOGDEBUG("BPI: buffer[%s] hardware[%s]\n",buffer, hardware);
LOGDEBUG("BPI: buffer[%s] hardware[%s]\n", buffer, hardware);
//Search for board:
for (board = bpiboard ; board->name != NULL ; ++board) {
LOGDEBUG("BPI: name[%s] hardware[%s]\n",board->name, hardware);
if (strcmp (board->name, hardware) == 0) {
//gpioLayout = board->gpioLayout;
// Search for board:
for (board = bpiboard; board->name != NULL; ++board) {
LOGDEBUG("BPI: name[%s] hardware[%s]\n", board->name, hardware);
if (strcmp(board->name, hardware) == 0) {
// gpioLayout = board->gpioLayout;
gpioLayout = board->model; // BPI: use model to replace gpioLayout
LOGDEBUG("BPI: name[%s] gpioLayout(%d)\n",board->name, gpioLayout);
if(gpioLayout >= 21) {
LOGDEBUG("BPI: name[%s] gpioLayout(%d)\n", board->name, gpioLayout);
if (gpioLayout >= 21) {
bpi_found = 1;
break;
}
}
}
if(bpi_found == 1) {
if (bpi_found == 1) {
break;
}
}
fclose(bpiFd);
LOGDEBUG("BPI: name[%s] gpioLayout(%d)\n",board->name, gpioLayout);
return gpioLayout ;
LOGDEBUG("BPI: name[%s] gpioLayout(%d)\n", board->name, gpioLayout);
return gpioLayout;
}
// int GPIOBUS_Allwinner::bpi_get_rpi_info(rpi_info *info)
@ -844,37 +762,36 @@ int GPIOBUS_Allwinner::bpi_piGpioLayout (void)
// return -1;
// }
void GPIOBUS_Allwinner::set_pullupdn(int gpio, int pud)
{
int clk_offset = PULLUPDNCLK_OFFSET + (gpio/32);
int shift = (gpio%32);
int clk_offset = PULLUPDNCLK_OFFSET + (gpio / 32);
int shift = (gpio % 32);
#ifdef BPI
if( bpi_found == 1 ) {
if (bpi_found == 1) {
gpio = *(pinTobcm_BP + gpio);
return sunxi_set_pullupdn(gpio, pud);
}
#endif
if (pud == PUD_DOWN)
*(gpio_map+PULLUPDN_OFFSET) = (*(gpio_map+PULLUPDN_OFFSET) & ~3) | PUD_DOWN;
*(gpio_map + PULLUPDN_OFFSET) = (*(gpio_map + PULLUPDN_OFFSET) & ~3) | PUD_DOWN;
else if (pud == PUD_UP)
*(gpio_map+PULLUPDN_OFFSET) = (*(gpio_map+PULLUPDN_OFFSET) & ~3) | PUD_UP;
*(gpio_map + PULLUPDN_OFFSET) = (*(gpio_map + PULLUPDN_OFFSET) & ~3) | PUD_UP;
else // pud == PUD_OFF
*(gpio_map+PULLUPDN_OFFSET) &= ~3;
*(gpio_map + PULLUPDN_OFFSET) &= ~3;
short_wait();
*(gpio_map+clk_offset) = 1 << shift;
*(gpio_map + clk_offset) = 1 << shift;
short_wait();
*(gpio_map+PULLUPDN_OFFSET) &= ~3;
*(gpio_map+clk_offset) = 0;
*(gpio_map + PULLUPDN_OFFSET) &= ~3;
*(gpio_map + clk_offset) = 0;
}
void GPIOBUS_Allwinner::short_wait(void)
{
int i;
for (i=0; i<150; i++) { // wait 150 cycles
for (i = 0; i < 150; i++) { // wait 150 cycles
asm volatile("nop");
}
}

View File

@ -15,6 +15,7 @@
#include "config.h"
#include "hal/gpiobus.h"
#include "hal/board_type.h"
#include "hal/pi_defs/bpi-gpio.h"
#include "log.h"
#include "scsi.h"
@ -33,11 +34,7 @@ class GPIOBUS_Allwinner : public GPIOBUS
bool Init(mode_e mode = mode_e::TARGET, board_type::rascsi_board_type_e
rascsi_type = board_type::rascsi_board_type_e::BOARD_TYPE_FULLSPEC) override;
// Initialization
void Reset() override;
// Reset
void Cleanup() override;
// Cleanup
//---------------------------------------------------------------------------
//
@ -58,7 +55,9 @@ class GPIOBUS_Allwinner : public GPIOBUS
// Set Control Signal
void SetMode(board_type::pi_physical_pin_e pin, board_type::gpio_direction_e mode) override;
// Set SCSI I/O mode
bool GetSignal(board_type::pi_physical_pin_e pin) const override;
bool GetSignal(board_type::pi_physical_pin_e pin);
bool GetSignal(board_type::pi_physical_pin_e pin) const override {(void)pin;return true;}
// Get SCSI input signal value
void SetSignal(board_type::pi_physical_pin_e pin, board_type::gpio_high_low_e ast) override;
// Set SCSI output signal value
@ -81,7 +80,7 @@ class GPIOBUS_Allwinner : public GPIOBUS
// Set GPIO drive strength
// Map the physical pin number to the logical GPIO number
const static std::map<board_type::pi_physical_pin_e, int> phys_to_gpio_map;
shared_ptr<Banana_Pi_Gpio_Mapping> phys_to_gpio_map;
#if !defined(__x86_64__) && !defined(__X86__)
uint32_t baseaddr = 0; // Base address