mirror of
https://github.com/sipeed/Maixduino.git
synced 2026-03-03 09:04:00 +01:00
fix bug #15
This commit is contained in:
@@ -6,7 +6,7 @@ extern pwm_fpio_set_t pwm_pins[VARIANT_NUM_PWM];
|
||||
|
||||
void tone(uint8_t pin, unsigned int frequency, unsigned long duration)
|
||||
{
|
||||
int8_t _pin = k210FpioSet(pin);
|
||||
int8_t _pin = k210FpioSet(MD_PIN_MAP(pin));
|
||||
if(_pin >= 0){
|
||||
if (duration > 0) {
|
||||
pwm_set_frequency(pwm_pins[_pin].device, pwm_pins[_pin].channel,(double)frequency,0.5);
|
||||
@@ -24,7 +24,7 @@ void tone(uint8_t pin, unsigned int frequency, unsigned long duration)
|
||||
|
||||
void noTone(uint8_t pin)
|
||||
{
|
||||
int8_t _pin = k210FpioSet(pin);
|
||||
int8_t _pin = k210FpioSet(MD_PIN_MAP(pin));
|
||||
if(_pin >= 0){
|
||||
pwm_set_enable(pwm_pins[_pin].device, pwm_pins[_pin].channel,0);
|
||||
}
|
||||
|
||||
@@ -66,8 +66,8 @@ UARTClass::UARTClass(uart_device_number_t device_select)
|
||||
void
|
||||
UARTClass::begin(uint32_t dwBaudRate, uint8_t _rx, uint8_t _tx)
|
||||
{
|
||||
fpioa_set_function((int)_rx, this->_rxfunc);
|
||||
fpioa_set_function((int)_tx, this->_txfunc);
|
||||
fpioa_set_function((int)MD_PIN_MAP(_rx), this->_rxfunc);
|
||||
fpioa_set_function((int)MD_PIN_MAP(_tx), this->_txfunc);
|
||||
uart_init(this->_uart);
|
||||
uart_configure(this->_uart, dwBaudRate, UART_BITWIDTH_8BIT, UART_STOP_1, UART_PARITY_NONE);
|
||||
this->_buff = new RingBuffer();
|
||||
@@ -144,8 +144,8 @@ UARTHSClass::UARTHSClass()
|
||||
void
|
||||
UARTHSClass::begin(uint32_t dwBaudRate, uint8_t _rx, uint8_t _tx)
|
||||
{
|
||||
fpioa_set_function((int)_rx, FUNC_UARTHS_RX);
|
||||
fpioa_set_function((int)_tx, FUNC_UARTHS_TX);
|
||||
fpioa_set_function((int)MD_PIN_MAP(_rx), FUNC_UARTHS_RX);
|
||||
fpioa_set_function((int)MD_PIN_MAP(_tx), FUNC_UARTHS_TX);
|
||||
uarths_init();
|
||||
uarths_config(dwBaudRate, UARTHS_STOP_1);
|
||||
this->_buff = new RingBuffer();
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
|
||||
void attachInterrupt(uint8_t intnum, voidFuncPtr user_callback, uint8_t mode)
|
||||
{
|
||||
int gpionum = getGpio(intnum);
|
||||
int gpionum = get_gpio(MD_PIN_MAP(intnum));
|
||||
if(gpionum >= 0){
|
||||
fpioa_function_t function = FUNC_GPIOHS0 + gpionum;
|
||||
fpioa_set_function(intnum, function);
|
||||
@@ -34,7 +34,7 @@ void attachInterrupt(uint8_t intnum, voidFuncPtr user_callback, uint8_t mode)
|
||||
|
||||
void detachInterrupt(uint8_t intnum)
|
||||
{
|
||||
int gpionum = getGpio(intnum);
|
||||
int gpionum = get_gpio(MD_PIN_MAP(intnum));
|
||||
if(gpionum >= 0){
|
||||
gpiohs_irq_unregister((uint8_t)gpionum);
|
||||
}
|
||||
|
||||
@@ -52,7 +52,7 @@ void analogOutputInit(void)
|
||||
|
||||
void analogWrite(uint8_t ucPin, uint32_t ulValue )
|
||||
{
|
||||
int8_t _pin = k210FpioSet(ucPin);
|
||||
int8_t _pin = k210FpioSet(MD_PIN_MAP(ucPin));
|
||||
double _duty;
|
||||
if(_pin >= 0){
|
||||
_duty = dValueToDuty(ulValue);
|
||||
|
||||
@@ -13,55 +13,43 @@
|
||||
extern "C"{
|
||||
#endif // __cplusplus
|
||||
|
||||
static int8_t _fpio_to_gpio_table[48]={-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1};
|
||||
|
||||
void pinMode(uint8_t dwPin, uint8_t dwMode){
|
||||
int gpionum = getGpio(dwPin);
|
||||
int gpionum = get_gpio(MD_PIN_MAP(dwPin));
|
||||
if(gpionum >= 0){
|
||||
fpioa_function_t function = FUNC_GPIOHS0 + gpionum;
|
||||
fpioa_set_function(dwPin, function);
|
||||
fpioa_set_function(MD_PIN_MAP(dwPin), function);
|
||||
gpiohs_set_drive_mode((uint8_t)gpionum, (gpio_drive_mode_t)dwMode);
|
||||
}
|
||||
return ;
|
||||
}
|
||||
|
||||
void digitalWrite(uint8_t dwPin, uint8_t dwVal){
|
||||
int gpionum = getGpio_s(dwPin);
|
||||
if(gpionum >= 0){
|
||||
gpiohs_set_pin((uint8_t)gpionum, (gpio_pin_value_t)dwVal);
|
||||
if(_fpio_to_gpio_table[MD_PIN_MAP(dwPin)] >= 0){
|
||||
gpiohs_set_pin((uint8_t)_fpio_to_gpio_table[MD_PIN_MAP(dwPin)], (gpio_pin_value_t)dwVal);
|
||||
}
|
||||
return ;
|
||||
}
|
||||
|
||||
int digitalRead(uint8_t dwPin){
|
||||
int gpionum = getGpio_s(dwPin);
|
||||
if(gpionum >= 0){
|
||||
return (int)gpiohs_get_pin((uint8_t)gpionum);
|
||||
if(_fpio_to_gpio_table[MD_PIN_MAP(dwPin)] >= 0){
|
||||
return (int)gpiohs_get_pin((uint8_t)_fpio_to_gpio_table[MD_PIN_MAP(dwPin)]);
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
|
||||
int getGpio(uint8_t fpioPin) //分配一个gpio给fpio 输入 fpio 返回 gpiohs号
|
||||
int get_gpio(uint8_t fpio_pin)
|
||||
{
|
||||
fpioa_function_t function = fpioa_get_function_buy_io(fpioPin);
|
||||
if(function <= FUNC_GPIOHS31 && function >= FUNC_GPIOHS0 )
|
||||
{
|
||||
return (int)(function - FUNC_GPIOHS0);
|
||||
if(_fpio_to_gpio_table[MD_PIN_MAP(fpio_pin)] > -1){
|
||||
return _fpio_to_gpio_table[MD_PIN_MAP(fpio_pin)];
|
||||
}else{
|
||||
return find_unused_gpiohs_io();
|
||||
_fpio_to_gpio_table[MD_PIN_MAP(fpio_pin)] = find_unused_gpiohs_io();
|
||||
return _fpio_to_gpio_table[MD_PIN_MAP(fpio_pin)];
|
||||
}
|
||||
}
|
||||
|
||||
int getGpio_s(uint8_t fpioPin)
|
||||
{
|
||||
fpioa_function_t function = fpioa_get_function_buy_io(fpioPin);
|
||||
if(function <= FUNC_GPIOHS31 && function >= FUNC_GPIOHS0 )
|
||||
{
|
||||
return (int)(function - FUNC_GPIOHS0);
|
||||
}else{
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
fpioa_function_t fpioa_get_function_buy_io(uint8_t fpioPin)
|
||||
fpioa_function_t fpioa_get_function_by_io(uint8_t fpioPin)
|
||||
{
|
||||
return (fpioa_function_t)fpioa->io[fpioPin].ch_sel ;
|
||||
}
|
||||
|
||||
@@ -53,9 +53,8 @@ extern void digitalWrite( uint8_t dwPin, uint8_t dwVal ) ;
|
||||
*/
|
||||
extern int digitalRead( uint8_t dwPin ) ;
|
||||
|
||||
int getGpio(uint8_t fpioPin) ;
|
||||
int getGpio_s(uint8_t fpioPin) ;
|
||||
fpioa_function_t fpioa_get_function_buy_io(uint8_t fpioPin) ;
|
||||
int get_gpio(uint8_t fpio_pin) ;
|
||||
fpioa_function_t fpioa_get_function_by_io(uint8_t fpioPin) ;
|
||||
int find_unused_gpiohs_io(void) ;
|
||||
|
||||
#ifdef __cplusplus
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
#ifndef _VARIANT_SIPEED_M1_DOCK
|
||||
#define _VARIANT_SIPEED_M1_DOCK
|
||||
#ifndef _VARIANT_SIPEED_MAIX_BIT
|
||||
#define _VARIANT_SIPEED_MAIX_BIT
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
@@ -58,6 +58,8 @@ extern class UARTClass Serial3;
|
||||
#define SDA 31
|
||||
#define SCL 30
|
||||
|
||||
#define MD_PIN_MAP(fpio) (fpio)
|
||||
|
||||
static const uint8_t SS = SPI0_CS0 ;
|
||||
static const uint8_t MOSI = SPI0_MOSI;
|
||||
static const uint8_t MISO = SPI0_MISO;
|
||||
|
||||
@@ -65,6 +65,8 @@ extern class UARTClass Serial3;
|
||||
#define SDA 31
|
||||
#define SCL 30
|
||||
|
||||
#define MD_PIN_MAP(fpio) (fpio)
|
||||
|
||||
static const uint8_t SS = SPI0_CS0 ;
|
||||
static const uint8_t MOSI = SPI0_MOSI;
|
||||
static const uint8_t MISO = SPI0_MISO;
|
||||
|
||||
@@ -65,6 +65,8 @@ extern class UARTClass Serial3;
|
||||
#define SDA 31
|
||||
#define SCL 30
|
||||
|
||||
#define MD_PIN_MAP(fpio) (fpio)
|
||||
|
||||
static const uint8_t SS = SPI0_CS0 ;
|
||||
static const uint8_t MOSI = SPI0_MOSI;
|
||||
static const uint8_t MISO = SPI0_MISO;
|
||||
|
||||
@@ -1,5 +1,5 @@
|
||||
#ifndef _VARIANT_SIPEED_M1_DOCK
|
||||
#define _VARIANT_SIPEED_M1_DOCK
|
||||
#ifndef _VARIANT_SIPEED_MAIXDUINO
|
||||
#define _VARIANT_SIPEED_MAIXDUINO
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
@@ -56,8 +56,8 @@ extern class UARTClass Serial3;
|
||||
#define LCD_DC 38
|
||||
#define LCD_WR 39
|
||||
|
||||
#define RX0 4
|
||||
#define TX0 5
|
||||
#define RX0 0
|
||||
#define TX0 1
|
||||
|
||||
#define RX1 6
|
||||
#define TX1 7
|
||||
@@ -76,9 +76,13 @@ typedef struct _pwm_fpio_set_t{
|
||||
uint8_t inuse;
|
||||
}pwm_fpio_set_t;
|
||||
|
||||
static uint8_t maixduino_pin_map[14] = {4, 5, 21, 22, 23, 24, 32, 15, 14, 13, 12, 11, 10, 3};
|
||||
#define MD_PIN_MAP(fpio) _maixduino_pin_map[(fpio)]
|
||||
|
||||
uint8_t _maixduino_pin_map[14] = {4, 5, 21, 22, 23, 24, 32, 15, 14, 13, 12, 11, 10, 3};
|
||||
|
||||
|
||||
uint8_t pinToFpio(uint8_t pin){ return MD_PIN_MAP(pin); }
|
||||
|
||||
uint8_t pinToFpio(uint8_t pin){ return maixduino_pin_map[pin]; }
|
||||
|
||||
typedef enum _analog_output_pin_t{
|
||||
A0,
|
||||
|
||||
Reference in New Issue
Block a user