Merged in alinjerpelea/nuttx (pull request #914)
configs: spresense: add I2CTOOL support and extend GPIO for future use * arch: arm: cxd56xx: add delay support add delay support for cxd56xx chip Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com> * configs: spresense: register I2C busses for development is usefull to register I2C busses when the I2CTOOL is built Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com> * configs:spresense: enable GPIO interface enable GPIO interface on spresense board Signed-off-by: Alin Jerpelea <alin.jerpelea@sony.com> Approved-by: Gregory Nutt <gnutt@nuttx.org>
This commit is contained in:
parent
df664a8334
commit
c62d90fdb7
@ -92,6 +92,7 @@ CHIP_CSRCS += cxd56_start.c
|
||||
CHIP_CSRCS += cxd56_timerisr.c
|
||||
CHIP_CSRCS += cxd56_pinconfig.c
|
||||
CHIP_CSRCS += cxd56_clock.c
|
||||
CHIP_CSRCS += cxd56_delay.c
|
||||
CHIP_CSRCS += cxd56_gpio.c
|
||||
CHIP_CSRCS += cxd56_pmic.c
|
||||
CHIP_CSRCS += cxd56_cpufifo.c
|
||||
|
119
arch/arm/src/cxd56xx/cxd56_delay.c
Normal file
119
arch/arm/src/cxd56xx/cxd56_delay.c
Normal file
@ -0,0 +1,119 @@
|
||||
/****************************************************************************
|
||||
* arch/arm/src/cxd56xx/cxd56_delay.c
|
||||
*
|
||||
* Copyright 2018 Sony Semiconductor Solutions Corporation
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name of Sony Semiconductor Solutions Corporation nor
|
||||
* the names of its contributors may be used to endorse or promote
|
||||
* products derived from this software without specific prior written
|
||||
* permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
#include <sys/types.h>
|
||||
#include <nuttx/arch.h>
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "cxd56_clock.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
#define CXD56XX_LOOPSPERMSEC_156MHZ 7428ull
|
||||
#define CXD56XX_LOOPSPERMSEC_BY_CLOCK(clock) \
|
||||
(uint32_t)(CXD56XX_LOOPSPERMSEC_156MHZ * (clock) / 156000000ull)
|
||||
|
||||
/* Adjust manually to be up_udelay(1000) is neary equal with up_udelay(999) */
|
||||
|
||||
#define CXD56XX_LOOPSPERUSEC_ADJUST 810ul;
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_mdelay
|
||||
*
|
||||
* Description:
|
||||
* Delay inline for the requested number of milliseconds.
|
||||
* *** NOT multi-tasking friendly ***
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void up_mdelay(unsigned int milliseconds)
|
||||
{
|
||||
volatile unsigned int i;
|
||||
volatile unsigned int j;
|
||||
uint32_t clock = cxd56_get_cpu_baseclk();
|
||||
uint32_t loops = CXD56XX_LOOPSPERMSEC_BY_CLOCK(clock);
|
||||
|
||||
for (i = 0; i < milliseconds; i++)
|
||||
{
|
||||
for (j = 0; j < loops; j++)
|
||||
{
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: up_udelay
|
||||
*
|
||||
* Description:
|
||||
* Delay inline for the requested number of microseconds. NOTE: Because
|
||||
* of all of the setup, several microseconds will be lost before the actual
|
||||
* timing looop begins. Thus, the delay will always be a few microseconds
|
||||
* longer than requested.
|
||||
*
|
||||
* *** NOT multi-tasking friendly ***
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
void up_udelay(useconds_t microseconds)
|
||||
{
|
||||
volatile unsigned int i;
|
||||
volatile unsigned int j;
|
||||
uint32_t clock = cxd56_get_cpu_baseclk();
|
||||
uint32_t loops = CXD56XX_LOOPSPERMSEC_BY_CLOCK(clock);
|
||||
uint32_t milliseconds = microseconds / 1000;
|
||||
|
||||
for (i = 0; i < milliseconds; i++)
|
||||
{
|
||||
for (j = 0; j < loops; j++)
|
||||
{
|
||||
}
|
||||
}
|
||||
loops = loops * (microseconds % 1000) / CXD56XX_LOOPSPERUSEC_ADJUST;
|
||||
for (i = 0; i < loops; i++)
|
||||
{
|
||||
}
|
||||
}
|
@ -49,9 +49,11 @@
|
||||
#include "cxd56_power.h"
|
||||
#include "cxd56_flash.h"
|
||||
#include "cxd56_gs2200m.h"
|
||||
#include "cxd56_i2cdev.h"
|
||||
#include "cxd56_bmi160.h"
|
||||
#include "cxd56_sdcard.h"
|
||||
#include "cxd56_wdt.h"
|
||||
#include "cxd56_gpioif.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
|
202
configs/spresense/include/cxd56_gpioif.h
Normal file
202
configs/spresense/include/cxd56_gpioif.h
Normal file
@ -0,0 +1,202 @@
|
||||
/****************************************************************************
|
||||
* configs/spresense/include/cxd56_gpioif.h
|
||||
*
|
||||
* Copyright 2018 Sony Semiconductor Solutions Corporation
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name of Sony Semiconductor Solutions Corporation nor
|
||||
* the names of its contributors may be used to endorse or promote
|
||||
* products derived from this software without specific prior written
|
||||
* permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef __BOARD_COMMON_INCLUDE_CXD56_GPIOIF_H
|
||||
#define __BOARD_COMMON_INCLUDE_CXD56_GPIOIF_H
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <stdint.h>
|
||||
#include <stdbool.h>
|
||||
|
||||
#include <nuttx/irq.h>
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
#define EXTERN extern "C"
|
||||
extern "C"
|
||||
{
|
||||
#else
|
||||
#define EXTERN extern
|
||||
#endif
|
||||
|
||||
/* gpioif GPIO Interface driver */
|
||||
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
|
||||
/* Pin Pull Setting
|
||||
* Pin floating, pull up, pull down definitions
|
||||
*/
|
||||
|
||||
#define PIN_FLOAT (0) /**< Floating */
|
||||
#define PIN_PULLUP (1) /**< Internal Weak Pull Up */
|
||||
#define PIN_PULLDOWN (2) /**< Internal Weak Pull Down */
|
||||
#define PIN_BUSKEEPER (3) /**< Internal Bus-Keeper */
|
||||
|
||||
/*
|
||||
* GPIO Interrupt Setting
|
||||
* GPIO interrupt level and edge trigger types
|
||||
*/
|
||||
|
||||
#define INT_HIGH_LEVEL (2) /**< High Level */
|
||||
#define INT_LOW_LEVEL (3) /**< Low Level */
|
||||
#define INT_RISING_EDGE (4) /**< Rising Edge */
|
||||
#define INT_FALLING_EDGE (5) /**< Falling Edge */
|
||||
#define INT_BOTH_EDGE (7) /**< Both Edge */
|
||||
|
||||
#ifndef __ASSEMBLY__
|
||||
|
||||
/****************************************************************************
|
||||
* Public Function Prototypes
|
||||
****************************************************************************/
|
||||
|
||||
/*
|
||||
* GPIO Configure
|
||||
*
|
||||
* [in] pin: Pin number
|
||||
* [in] mode: Function mode 0=GPIO
|
||||
* [in] input: Input Enable true=enable, false=disable
|
||||
* [in] drive: Drive Strength true=High Drive(4mA), false=Normal(2mA)
|
||||
* [in] pull: 0=float, 1=pullup, 2=pulldown, 3=buskeeper
|
||||
* - PIN_FLOAT
|
||||
* - PIN_PULLUP
|
||||
* - PIN_PULLDOWN
|
||||
* - PIN_BUSKEEPER
|
||||
*
|
||||
* return: OK(0) is success. negative value is failure.
|
||||
*/
|
||||
|
||||
int board_gpio_config(uint32_t pin, int mode, bool input, bool drive,
|
||||
int pull);
|
||||
|
||||
/*
|
||||
* GPIO Status
|
||||
*
|
||||
* [in] pin: Pin number
|
||||
* [out] input: Input Enable true=enable, false=disable
|
||||
* [out] output: Output Enable true=enable, false=disable
|
||||
* [out] drive: Drive Strength true=HighDrive(4mA), false=Normal(2mA)
|
||||
* [out] pull: 0=float, 1=pullup, 2=pulldown, 3=buskeeper
|
||||
* - PIN_FLOAT
|
||||
* - PIN_PULLUP
|
||||
* - PIN_PULLDOWN
|
||||
* - PIN_BUSKEEPER
|
||||
*
|
||||
* return: Pin function mode. negative value is failure.
|
||||
*/
|
||||
|
||||
int board_gpio_status(uint32_t pin, bool *input, bool *output, bool *drive,
|
||||
int *pull);
|
||||
|
||||
/*
|
||||
* GPIO Write
|
||||
*
|
||||
* [in] pin: Pin number
|
||||
* [in] value: Write Value 0<high, 0=low, 0>hiz
|
||||
*/
|
||||
|
||||
void board_gpio_write(uint32_t pin, int value);
|
||||
|
||||
/*
|
||||
* GPIO Read
|
||||
*
|
||||
* param: [in] pin: Pin number
|
||||
*
|
||||
* return: read value 1=high, 0=low
|
||||
*/
|
||||
|
||||
int board_gpio_read(uint32_t pin);
|
||||
|
||||
/*
|
||||
* GPIO Interrupt Configure
|
||||
*
|
||||
* [in] pin: Pin number
|
||||
* [in] mode: Interrupt polarity
|
||||
* - #INT_HIGH_LEVEL
|
||||
* - #INT_LOW_LEVEL
|
||||
* - #INT_RISING_EDGE
|
||||
* - #INT_FALLING_EDGE
|
||||
* - #INT_BOTH_EDGE
|
||||
* [in] filter: Noise Filter true=enable, false=disable
|
||||
* [in] isr: Interrupt Service Routine
|
||||
*
|
||||
* IRQ number. negative value is failure.
|
||||
*/
|
||||
|
||||
int board_gpio_intconfig(uint32_t pin, int mode, bool filter, xcpt_t isr);
|
||||
|
||||
/*
|
||||
* GPIO Interrupt Configure
|
||||
*
|
||||
* [in] pin: Pin number
|
||||
* [out] mode: Interrupt polarity
|
||||
* - #INT_HIGH_LEVEL
|
||||
* - #INT_LOW_LEVEL
|
||||
* - #INT_RISING_EDGE
|
||||
* - #INT_FALLING_EDGE
|
||||
* - #INT_BOTH_EDGE
|
||||
* [out] filter: Noise Filter true=enable, false=disable
|
||||
* [out] enabled: Interrupt true=enable, false=disable
|
||||
*
|
||||
* IRQ number. negative value is failure.
|
||||
*/
|
||||
|
||||
int board_gpio_intstatus(uint32_t pin, int *mode,
|
||||
bool *filter, bool *enabled);
|
||||
|
||||
/*
|
||||
* GPIO Interrupt Enable/Disable
|
||||
*
|
||||
* [in] pin: Pin number
|
||||
* [in] enable: Interrupt true=enable, false=disable
|
||||
*
|
||||
* IRQ number. negative value is failure.
|
||||
*/
|
||||
|
||||
int board_gpio_int(uint32_t pin, bool enable);
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif /* __ASSEMBLY__ */
|
||||
#endif /* __BOARD_COMMON_INCLUDE_CXD56_GPIOIF_H */
|
@ -64,6 +64,10 @@ CSRCS += cxd56_userleds.c
|
||||
endif
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_CXD56_GPIO_IRQ),y)
|
||||
CSRCS += cxd56_gpioif.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_CXD56_PWM),y)
|
||||
CSRCS += cxd56_pwm.c
|
||||
endif
|
||||
@ -96,4 +100,8 @@ ifeq ($(CONFIG_SENSORS_BMI160_I2C),y)
|
||||
CSRCS += cxd56_bmi160_i2c.c
|
||||
endif
|
||||
|
||||
ifeq ($(CONFIG_SYSTEM_I2CTOOL),y)
|
||||
CSRCS += cxd56_i2cdev.c
|
||||
endif
|
||||
|
||||
include $(TOPDIR)/configs/Board.mk
|
||||
|
@ -229,6 +229,32 @@ int cxd56_bringup(void)
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_SYSTEM_I2CTOOL
|
||||
#ifdef CONFIG_CXD56_I2C0
|
||||
ret = board_i2cdev_initialize(0);
|
||||
if (ret < 0)
|
||||
{
|
||||
_err("ERROR: Failed to initialize I2C0.\n");
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_CXD56_I2C1
|
||||
ret = board_i2cdev_initialize(1);
|
||||
if (ret < 0)
|
||||
{
|
||||
_err("ERROR: Failed to initialize I2C1.\n");
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef CONFIG_CXD56_I2C2
|
||||
ret = board_i2cdev_initialize(2);
|
||||
if (ret < 0)
|
||||
{
|
||||
_err("ERROR: Failed to initialize I2C2.\n");
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
cxd56_uart_initialize();
|
||||
cxd56_timerisr_initialize();
|
||||
|
||||
|
285
configs/spresense/src/cxd56_gpioif.c
Normal file
285
configs/spresense/src/cxd56_gpioif.c
Normal file
@ -0,0 +1,285 @@
|
||||
/****************************************************************************
|
||||
* configs/spresense/src/cxd56_gpioif.c
|
||||
*
|
||||
* Copyright 2018 Sony Semiconductor Solutions Corporation
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name of Sony Semiconductor Solutions Corporation nor
|
||||
* the names of its contributors may be used to endorse or promote
|
||||
* products derived from this software without specific prior written
|
||||
* permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Included Files
|
||||
****************************************************************************/
|
||||
|
||||
#include <nuttx/config.h>
|
||||
|
||||
#include <stdio.h>
|
||||
#include <debug.h>
|
||||
#include <errno.h>
|
||||
|
||||
#include <nuttx/board.h>
|
||||
#include <arch/board/board.h>
|
||||
|
||||
#include "cxd56_pinconfig.h"
|
||||
#include "cxd56_gpio.h"
|
||||
#include "cxd56_gpioint.h"
|
||||
|
||||
/****************************************************************************
|
||||
* Public Functions
|
||||
****************************************************************************/
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_gpio_config
|
||||
****************************************************************************/
|
||||
|
||||
int board_gpio_config(uint32_t pin, int mode, bool input, bool drive,
|
||||
int pull)
|
||||
{
|
||||
uint32_t pinconf;
|
||||
|
||||
pinconf = PINCONF_SET_PIN(pin);
|
||||
pinconf |= (input) ? PINCONF_INPUT_ENABLE : PINCONF_INPUT_DISABLE;
|
||||
pinconf |= (drive) ? PINCONF_DRIVE_HIGH : PINCONF_DRIVE_NORMAL;
|
||||
|
||||
switch (pull)
|
||||
{
|
||||
case PIN_PULLUP:
|
||||
pinconf |= PINCONF_PULLUP;
|
||||
break;
|
||||
case PIN_PULLDOWN:
|
||||
pinconf |= PINCONF_PULLDOWN;
|
||||
break;
|
||||
case PIN_BUSKEEPER:
|
||||
pinconf |= PINCONF_BUSKEEPER;
|
||||
break;
|
||||
default:
|
||||
case PIN_FLOAT:
|
||||
pinconf |= PINCONF_FLOAT;
|
||||
break;
|
||||
}
|
||||
|
||||
pinconf |= PINCONF_SET_MODE(mode);
|
||||
|
||||
return cxd56_pin_config(pinconf);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_gpio_status
|
||||
****************************************************************************/
|
||||
|
||||
int board_gpio_status(uint32_t pin, bool *input, bool *output, bool *drive,
|
||||
int *pull)
|
||||
{
|
||||
int ret;
|
||||
cxd56_pin_status_t pstat;
|
||||
cxd56_gpio_status_t gstat;
|
||||
|
||||
DEBUGASSERT(input);
|
||||
DEBUGASSERT(output);
|
||||
DEBUGASSERT(drive);
|
||||
DEBUGASSERT(pull);
|
||||
|
||||
ret = cxd56_pin_status(pin, &pstat);
|
||||
if (ret < 0)
|
||||
{
|
||||
return ret;
|
||||
}
|
||||
*input = PINCONF_INPUT_ENABLED(pstat.input_en);
|
||||
*drive = PINCONF_IS_DRIVE_HIGH(pstat.drive);
|
||||
if (PINCONF_IS_FLOAT(pstat.pull))
|
||||
{
|
||||
*pull = PIN_FLOAT;
|
||||
}
|
||||
else if (PINCONF_IS_PULLUP(pstat.pull))
|
||||
{
|
||||
*pull = PIN_PULLUP;
|
||||
}
|
||||
else if (PINCONF_IS_PULLDOWN(pstat.pull))
|
||||
{
|
||||
*pull = PIN_PULLDOWN;
|
||||
}
|
||||
else
|
||||
{
|
||||
*pull = PIN_BUSKEEPER;
|
||||
}
|
||||
|
||||
cxd56_gpio_status(pin, &gstat);
|
||||
*output = gstat.output_en;
|
||||
|
||||
return pstat.mode;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_gpio_write
|
||||
****************************************************************************/
|
||||
|
||||
void board_gpio_write(uint32_t pin, int value)
|
||||
{
|
||||
if (value < 0)
|
||||
{
|
||||
cxd56_gpio_write_hiz(pin);
|
||||
}
|
||||
else
|
||||
{
|
||||
cxd56_gpio_write(pin, (value > 0));
|
||||
}
|
||||
return;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_gpio_read
|
||||
****************************************************************************/
|
||||
|
||||
int board_gpio_read(uint32_t pin)
|
||||
{
|
||||
return (int)cxd56_gpio_read(pin);
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_gpio_intconfig
|
||||
****************************************************************************/
|
||||
|
||||
int board_gpio_intconfig(uint32_t pin, int mode, bool filter, xcpt_t isr)
|
||||
{
|
||||
#ifdef CONFIG_CXD56_GPIO_IRQ
|
||||
int ret = OK;
|
||||
uint32_t gpiocfg = 0;
|
||||
|
||||
switch (mode)
|
||||
{
|
||||
case INT_HIGH_LEVEL:
|
||||
gpiocfg = GPIOINT_LEVEL_HIGH;
|
||||
break;
|
||||
case INT_LOW_LEVEL:
|
||||
gpiocfg = GPIOINT_LEVEL_LOW;
|
||||
break;
|
||||
case INT_RISING_EDGE:
|
||||
gpiocfg = GPIOINT_PSEUDO_EDGE_RISE;
|
||||
break;
|
||||
case INT_FALLING_EDGE:
|
||||
gpiocfg = GPIOINT_PSEUDO_EDGE_FALL;
|
||||
break;
|
||||
case INT_BOTH_EDGE:
|
||||
gpiocfg = GPIOINT_PSEUDO_EDGE_BOTH;
|
||||
break;
|
||||
default:
|
||||
if (isr)
|
||||
{
|
||||
return -EINVAL;
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
if (filter)
|
||||
{
|
||||
gpiocfg |= GPIOINT_NOISE_FILTER_ENABLE;
|
||||
}
|
||||
|
||||
ret = cxd56_gpioint_config(pin, gpiocfg, isr, NULL);
|
||||
return ret;
|
||||
#else
|
||||
return -ENOTSUP;
|
||||
#endif
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_gpio_intstatus
|
||||
****************************************************************************/
|
||||
|
||||
int board_gpio_intstatus(uint32_t pin, int *mode, bool *filter, bool *enabled)
|
||||
{
|
||||
#ifdef CONFIG_CXD56_GPIO_IRQ
|
||||
int ret;
|
||||
cxd56_gpioint_status_t stat;
|
||||
|
||||
DEBUGASSERT(mode);
|
||||
DEBUGASSERT(filter);
|
||||
DEBUGASSERT(enabled);
|
||||
|
||||
ret = cxd56_gpioint_status(pin, &stat);
|
||||
if (ret < 0)
|
||||
{
|
||||
return ret;
|
||||
}
|
||||
|
||||
switch (stat.polarity)
|
||||
{
|
||||
case GPIOINT_LEVEL_HIGH:
|
||||
*mode = INT_HIGH_LEVEL;
|
||||
break;
|
||||
case GPIOINT_LEVEL_LOW:
|
||||
*mode = INT_LOW_LEVEL;
|
||||
break;
|
||||
case GPIOINT_EDGE_RISE:
|
||||
*mode = INT_RISING_EDGE;
|
||||
break;
|
||||
case GPIOINT_EDGE_FALL:
|
||||
*mode = INT_FALLING_EDGE;
|
||||
break;
|
||||
case GPIOINT_EDGE_BOTH:
|
||||
*mode = INT_BOTH_EDGE;
|
||||
break;
|
||||
default:
|
||||
*mode = 0;
|
||||
break;
|
||||
}
|
||||
*filter = stat.filter;
|
||||
*enabled = stat.enable;
|
||||
|
||||
return stat.irq;
|
||||
#else
|
||||
return -ENOTSUP;
|
||||
#endif
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
* Name: board_gpio_int
|
||||
****************************************************************************/
|
||||
|
||||
int board_gpio_int(uint32_t pin, bool enable)
|
||||
{
|
||||
#ifdef CONFIG_CXD56_GPIO_IRQ
|
||||
int irq = cxd56_gpioint_irq(pin);
|
||||
|
||||
if (irq > 0)
|
||||
{
|
||||
if (enable)
|
||||
{
|
||||
cxd56_gpioint_enable(pin);
|
||||
}
|
||||
else
|
||||
{
|
||||
cxd56_gpioint_disable(pin);
|
||||
}
|
||||
}
|
||||
return irq;
|
||||
#else
|
||||
return -ENOTSUP;
|
||||
#endif
|
||||
}
|
Loading…
Reference in New Issue
Block a user