Add support for spi sdcard with card detection logic

This commit is contained in:
Michał Łyszczek 2016-08-15 17:34:43 +02:00
parent 8c396a2986
commit 83fca7ded7
7 changed files with 468 additions and 50 deletions

View File

@ -49,7 +49,7 @@
#include "stm32_rcc.h"
/*******************************************************************************
* Pre-processor Definitions
* Pre-processor Definitions
******************************************************************************/
/* Clocking *******************************************************************/
@ -100,7 +100,7 @@
#define STM32_APB1_TIM5_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM6_CLKIN (2*STM32_PCLK1_FREQUENCY)
#define STM32_APB1_TIM7_CLKIN (2*STM32_PCLK1_FREQUENCY)
/* LED definitions ************************************************************/
/* There are four LEDs on stm32butterfly2 board that can be controlled by
* software. All pulled high and van be illuminated by driving the output low.
@ -154,6 +154,12 @@
# error "CONFIG_STM32_ADC2 is not supported"
#endif
/* SPI configuration. Only SPI1 is supported */
#ifdef CONFIG_STM32_SPI2
# error "CONFIG_STM32_SPI2 is not supported"
#endif
/*******************************************************************************
* Public Data
******************************************************************************/
@ -178,7 +184,7 @@ extern "C" {
* Description:
* Initializes board specific LEDS
******************************************************************************/
void stm32_led_initialize(void);
void stm32_led_initialize(void);
/*******************************************************************************
* Name: stm32_boardinitialize

View File

@ -43,38 +43,7 @@ CONFIG_RAW_BINARY=y
# Debug Options
#
CONFIG_DEBUG_ALERT=y
CONFIG_DEBUG_FEATURES=y
#
# Debug SYSLOG Output Controls
#
CONFIG_DEBUG_ERROR=y
CONFIG_DEBUG_WARN=y
CONFIG_DEBUG_INFO=y
# CONFIG_DEBUG_ASSERTIONS is not set
#
# Subsystem Debug Options
#
# CONFIG_DEBUG_BINFMT is not set
# CONFIG_DEBUG_FS is not set
# CONFIG_DEBUG_GRAPHICS is not set
# CONFIG_DEBUG_LIB is not set
# CONFIG_DEBUG_MM is not set
# CONFIG_DEBUG_NET is not set
# CONFIG_DEBUG_SCHED is not set
#
# OS Function Debug Options
#
# CONFIG_DEBUG_IRQ is not set
#
# Driver Debug Options
#
# CONFIG_DEBUG_LEDS is not set
# CONFIG_DEBUG_ANALOG is not set
# CONFIG_DEBUG_GPIO is not set
# CONFIG_DEBUG_FEATURES is not set
CONFIG_ARCH_HAVE_STACKCHECK=y
# CONFIG_STACK_COLORATION is not set
CONFIG_ARCH_HAVE_HEAPCHECK=y
@ -161,7 +130,6 @@ CONFIG_ARCH_HAVE_CMNVECTOR=y
# CONFIG_ARCH_HAVE_TRUSTZONE is not set
CONFIG_ARM_HAVE_MPU_UNIFIED=y
# CONFIG_ARM_MPU is not set
# CONFIG_DEBUG_HARDFAULT is not set
#
# ARMV7M Configuration Options
@ -411,7 +379,7 @@ CONFIG_STM32_ETHMAC=y
# CONFIG_STM32_I2C1 is not set
# CONFIG_STM32_OTGFS is not set
CONFIG_STM32_PWR=y
# CONFIG_STM32_SPI1 is not set
CONFIG_STM32_SPI1=y
# CONFIG_STM32_SPI2 is not set
# CONFIG_STM32_SPI3 is not set
# CONFIG_STM32_TIM1 is not set
@ -429,12 +397,14 @@ CONFIG_STM32_USART2=y
# CONFIG_STM32_IWDG is not set
# CONFIG_STM32_WWDG is not set
CONFIG_STM32_ADC=y
CONFIG_STM32_SPI=y
# CONFIG_STM32_NOEXT_VECTORS is not set
#
# Alternate Pin Mapping
#
CONFIG_STM32_ETH_REMAP=y
# CONFIG_STM32_SPI1_REMAP is not set
CONFIG_STM32_USART2_REMAP=y
# CONFIG_STM32_JTAG_DISABLE is not set
CONFIG_STM32_JTAG_FULL_ENABLE=y
@ -479,6 +449,12 @@ CONFIG_STM32_USART2_SERIALDRIVER=y
# CONFIG_STM32_FLOWCONTROL_BROKEN is not set
# CONFIG_STM32_USART_BREAKS is not set
# CONFIG_STM32_USART_SINGLEWIRE is not set
#
# SPI Configuration
#
# CONFIG_STM32_SPI_INTERRUPTS is not set
# CONFIG_STM32_SPI_DMA is not set
CONFIG_STM32_HAVE_RTC_COUNTER=y
# CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set
@ -613,7 +589,7 @@ CONFIG_ARCH_HAVE_TICKLESS=y
# CONFIG_SCHED_TICKLESS is not set
CONFIG_USEC_PER_TICK=10000
# CONFIG_SYSTEM_TIME64 is not set
# CONFIG_CLOCK_MONOTONIC is not set
CONFIG_CLOCK_MONOTONIC=y
# CONFIG_JULIAN_TIME is not set
CONFIG_START_YEAR=1970
CONFIG_START_MONTH=0
@ -728,7 +704,16 @@ CONFIG_RAMDISK=y
# CONFIG_PWM is not set
CONFIG_ARCH_HAVE_I2CRESET=y
# CONFIG_I2C is not set
# CONFIG_SPI is not set
CONFIG_SPI=y
# CONFIG_SPI_SLAVE is not set
CONFIG_SPI_EXCHANGE=y
# CONFIG_SPI_CMDDATA is not set
CONFIG_SPI_CALLBACK=y
# CONFIG_SPI_BITBANG is not set
CONFIG_SPI_HWFEATURES=y
# CONFIG_SPI_CRCGENERATION is not set
CONFIG_SPI_CS_CONTROL=y
# CONFIG_SPI_CS_DELAY_CONTROL is not set
# CONFIG_I2S is not set
#
@ -769,7 +754,17 @@ CONFIG_ADC_FIFOSIZE=8
# CONFIG_RGBLED is not set
# CONFIG_PCA9635PW is not set
# CONFIG_NCP5623C is not set
# CONFIG_MMCSD is not set
CONFIG_MMCSD=y
CONFIG_MMCSD_NSLOTS=1
# CONFIG_MMCSD_READONLY is not set
# CONFIG_MMCSD_MULTIBLOCK_DISABLE is not set
# CONFIG_MMCSD_MMCSUPPORT is not set
CONFIG_MMCSD_HAVECARDDETECT=y
CONFIG_MMCSD_SPI=y
CONFIG_MMCSD_SPICLOCK=20000000
CONFIG_MMCSD_SPIMODE=0
# CONFIG_ARCH_HAVE_SDIO is not set
# CONFIG_ARCH_HAVE_SDIOWAIT_WRCOMPLETE is not set
# CONFIG_MODEM is not set
# CONFIG_MTD is not set
# CONFIG_EEPROM is not set
@ -783,7 +778,6 @@ CONFIG_NETDEVICES=y
# CONFIG_NETDEV_MULTINIC is not set
# CONFIG_ARCH_HAVE_NETDEV_STATISTICS is not set
# CONFIG_NETDEV_LATEINIT is not set
# CONFIG_NET_DUMPPACKET is not set
#
# External Ethernet MAC Device Support
@ -814,7 +808,6 @@ CONFIG_ETH0_PHY_DP83848C=y
# CONFIG_ETH0_PHY_LAN8740A is not set
# CONFIG_ETH0_PHY_LAN8742A is not set
# CONFIG_ETH0_PHY_DM9161 is not set
# CONFIG_NETDEV_PHY_DEBUG is not set
# CONFIG_PIPES is not set
# CONFIG_PM is not set
# CONFIG_POWER is not set
@ -853,7 +846,6 @@ CONFIG_SERIAL_NPOLLWAITERS=2
# CONFIG_SERIAL_IFLOWCONTROL is not set
# CONFIG_SERIAL_OFLOWCONTROL is not set
# CONFIG_SERIAL_DMA is not set
# CONFIG_SERIAL_TIOCSERGSTRUCT is not set
CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y
CONFIG_USART2_SERIAL_CONSOLE=y
# CONFIG_OTHER_SERIAL_CONSOLE is not set
@ -992,7 +984,6 @@ CONFIG_NET_IOB=y
CONFIG_IOB_NBUFFERS=24
CONFIG_IOB_BUFSIZE=196
CONFIG_IOB_NCHAINS=8
# CONFIG_IOB_DEBUG is not set
# CONFIG_NET_ARCH_INCR32 is not set
# CONFIG_NET_ARCH_CHKSUM is not set
# CONFIG_NET_STATISTICS is not set
@ -1023,7 +1014,14 @@ CONFIG_FS_WRITABLE=y
# CONFIG_FS_NAMED_SEMAPHORES is not set
CONFIG_FS_MQUEUE_MPATH="/var/mqueue"
# CONFIG_FS_RAMMAP is not set
# CONFIG_FS_FAT is not set
CONFIG_FS_FAT=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_MAXFNAME=32
# CONFIG_FS_FATTIME is not set
# CONFIG_FAT_FORCE_INDIRECT is not set
# CONFIG_FAT_DMAMEMORY is not set
# CONFIG_FAT_DIRECT_RETRY is not set
# CONFIG_FS_NXFFS is not set
# CONFIG_FS_ROMFS is not set
# CONFIG_FS_TMPFS is not set
@ -1168,7 +1166,11 @@ CONFIG_EXAMPLES_ADC_SWTRIG=y
# CONFIG_EXAMPLES_MEDIA is not set
# CONFIG_EXAMPLES_MM is not set
# CONFIG_EXAMPLES_MODBUS is not set
# CONFIG_EXAMPLES_MOUNT is not set
CONFIG_EXAMPLES_MOUNT=y
# CONFIG_EXAMPLES_MOUNT_BLOCKDEVICE is not set
CONFIG_EXAMPLES_MOUNT_NSECTORS=2048
CONFIG_EXAMPLES_MOUNT_SECTORSIZE=512
CONFIG_EXAMPLES_MOUNT_RAMDEVNO=0
# CONFIG_EXAMPLES_NETTEST is not set
# CONFIG_EXAMPLES_NRF24L01TERM is not set
CONFIG_EXAMPLES_NSH=y
@ -1302,6 +1304,7 @@ CONFIG_NSH_BUILTIN_APPS=y
# CONFIG_NSH_DISABLE_LS is not set
# CONFIG_NSH_DISABLE_MB is not set
# CONFIG_NSH_DISABLE_MKDIR is not set
# CONFIG_NSH_DISABLE_MKFATFS is not set
# CONFIG_NSH_DISABLE_MKRD is not set
# CONFIG_NSH_DISABLE_MH is not set
# CONFIG_NSH_DISABLE_MOUNT is not set
@ -1325,6 +1328,8 @@ CONFIG_NSH_BUILTIN_APPS=y
# CONFIG_NSH_DISABLE_WGET is not set
# CONFIG_NSH_DISABLE_XD is not set
CONFIG_NSH_MMCSDMINOR=0
CONFIG_NSH_MMCSDSLOTNO=0
CONFIG_NSH_MMCSDSPIPORTNO=0
#
# Configure Command Options
@ -1348,7 +1353,7 @@ CONFIG_NSH_STRERROR=y
#
CONFIG_NSH_CONSOLE=y
# CONFIG_NSH_ALTCONDEV is not set
# CONFIG_NSH_ARCHINIT is not set
CONFIG_NSH_ARCHINIT=y
#
# Networking Configuration
@ -1357,7 +1362,6 @@ CONFIG_NSH_NETINIT=y
CONFIG_NSH_NETINIT_THREAD=y
CONFIG_NSH_NETINIT_THREAD_STACKSIZE=1568
CONFIG_NSH_NETINIT_THREAD_PRIORITY=80
# CONFIG_NSH_NETINIT_DEBUG is not set
#
# IP Address Configuration
@ -1391,7 +1395,7 @@ CONFIG_NSH_MAX_ROUNDTRIP=20
# CONFIG_SYSTEM_HEXED is not set
# CONFIG_SYSTEM_INSTALL is not set
# CONFIG_SYSTEM_NETDB is not set
# CONFIG_SYSTEM_RAMTEST is not set
CONFIG_SYSTEM_RAMTEST=y
CONFIG_READLINE_HAVE_EXTMATCH=y
CONFIG_SYSTEM_READLINE=y
CONFIG_READLINE_ECHO=y

View File

@ -42,4 +42,12 @@ ifeq ($(CONFIG_STM32_ADC),y)
CSRCS += stm32_adc.c
endif
ifeq ($(CONFIG_STM32_SPI1),y)
CSRCS += stm32_spi.c
endif
ifeq ($(CONFIG_MMCSD),y)
CSRCS += stm32_mmcsd.c
endif
include $(TOPDIR)/configs/Board.mk

View File

@ -39,6 +39,10 @@
#include <nuttx/config.h>
#include <arch/board/board.h>
#include <syslog.h>
#include "stm32_gpio.h"
#include "stm32_butterfly2.h"
/*******************************************************************************
* Public Functions
@ -47,9 +51,17 @@
void stm32_boardinitialize(void)
{
stm32_led_initialize();
stm32_spidev_initialize();
}
int board_app_initialize(uintptr_t arg)
{
return 0;
int rv;
if ((rv = stm32_sdinitialize(CONFIG_NSH_MMCSDMINOR)) < 0)
{
syslog(LOG_ERR, "Failed to initialize SD slot %d: %d\n");
return rv;
}
return 0;
}

View File

@ -0,0 +1,77 @@
/*****************************************************************************
* configs/stm32butterfly2/src/stm32_butterfly2.h
*
* Copyright (C) 2016 Michał Łyszczek. All rights reserved.
* Author: Michał Łyszczek <michal.lyszczek@gmail.com>
*
* 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 NuttX 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 "stm32_gpio.h"
/*****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define GPIO_SD_CS (GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz |\
GPIO_OUTPUT_SET | GPIO_PORTA | GPIO_PIN4)
#define GPIO_SD_CD (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_EXTI |\
GPIO_PORTB | GPIO_PIN9)
/*****************************************************************************
* Public Functions
****************************************************************************/
/*****************************************************************************
* Name: stm32_spidev_initialize
*
* Description:
* Called to configure SPI chip select GPIO pins.
*
* Note:
* Here only CS pins are configured as SPI pins are configured by driver
* itself.
****************************************************************************/
void stm32_spidev_initialize(void);
/*****************************************************************************
* Name: stm32_sdinitialize
*
* Description:
* Initializes SPI-based SD card
*
****************************************************************************/
int stm32_sdinitialize(int minor);

View File

@ -0,0 +1,209 @@
/*****************************************************************************
* configs/stm32butterfly2/src/stm32_mmcsd.c
*
* Copyright (C) 2016 Michał Łyszczek. All rights reserved.
* Author: Michał Łyszczek <michal.lyszczek@gmail.com>
*
* 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 NuttX 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 <debug.h>
#include <fcntl.h>
#include <nuttx/config.h>
#include <nuttx/mmcsd.h>
#include <nuttx/spi/spi.h>
#include <pthread.h>
#include <semaphore.h>
#include <time.h>
#include <unistd.h>
#include "stm32.h"
#include "stm32_butterfly2.h"
#include "stm32_spi.h"
/*****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#ifndef CONFIG_STM32_SPI1
# error "SD driver requires CONFIG_STM32_SPI1 to be enabled"
#endif
#ifdef CONFIG_DISABLE_MOUNTPOINT
# error "SD driver requires CONFIG_DISABLE_MOUNTPOINT to be disabled"
#endif
/*****************************************************************************
* Private Definitions
****************************************************************************/
static const int SD_SPI_PORT = 1; /* SD is connected to SPI1 port */
static const int SD_SLOT_NO = 0; /* There is only one SD slot */
/* Media changed callback */
static spi_mediachange_t mediachangeclbk;
/* Argument for media changed callback */
static void *mediachangearg;
/* Semafor to inform stm32_cd_thread that card was inserted or pulled out */
static sem_t cdsem;
/*****************************************************************************
* Private Functions
****************************************************************************/
/*****************************************************************************
* Name: stm32_cd_thread
*
* Description:
* Working thread to call mediachanged function when card is inserted or
* pulled out.
****************************************************************************/
static void *stm32_cd_thread(void *arg)
{
(void)arg;
while (1)
{
sem_wait(&cdsem);
if (mediachangeclbk)
{
/* Card doesn't seem to initialize properly without letting it to
* rest for a millsecond or so.
*/
usleep(1 * 1000);
mediachangeclbk(mediachangearg);
}
}
return NULL;
}
/*****************************************************************************
* Name: stm32_cd
*
* Description:
* Card detect interrupt handler.
****************************************************************************/
static int stm32_cd(int irq, FAR void *context)
{
static const int debounce_time = 100; /* [ms] */
static uint32_t now = 0;
static uint32_t prev = 0;
struct timespec tp;
clock_gettime(CLOCK_MONOTONIC, &tp);
now = tp.tv_sec * 1000 + tp.tv_nsec / 1000000;
/* When inserting card, card detect plate might bounce causing this
* interrupt to be called many time on single card insert/deinsert. Thus we
* are allowing only one interrupt every 100ms.
*/
if (now - debounce_time > prev)
{
prev = now;
sem_post(&cdsem);
}
return OK;
}
/*****************************************************************************
* Public Functions
****************************************************************************/
/*****************************************************************************
* Name: stm32_spi1register
*
* Description:
* Registers media change callback
****************************************************************************/
int stm32_spi1register(FAR struct spi_dev_s *dev, spi_mediachange_t callback,
FAR void *arg)
{
mediachangeclbk = callback;
mediachangearg = arg;
return OK;
}
/*****************************************************************************
* Name: stm32_sdinitialize
*
* Description:
* Initialize SPI-based SD card and card detect thread.
****************************************************************************/
int stm32_sdinitialize(int minor)
{
FAR struct spi_dev_s *spi;
int rv;
spi = stm32_spibus_initialize(SD_SPI_PORT);
if (!spi)
{
ferr("failed to initialize SPI port %d\n", SD_SPI_PORT);
return -ENODEV;
}
if ((rv = mmcsd_spislotinitialize(minor, SD_SLOT_NO, spi)) < 0)
{
ferr("failed to bind SPI port %d to SD slot %d\n", SD_SPI_PORT,
SD_SLOT_NO);
return rv;
}
stm32_gpiosetevent(GPIO_SD_CD, true, true, true, stm32_cd);
sem_init(&cdsem, 0, 0);
pthread_attr_t pattr;
pthread_attr_init(&pattr);
#ifdef CONFIG_DEBUG_FS
pthread_attr_setstacksize(&pattr, 1024);
#else
pthread_attr_setstacksize(&pattr, 256);
#endif
pthread_create(NULL, &pattr, stm32_cd_thread, NULL);
return OK;
}

View File

@ -0,0 +1,102 @@
/*****************************************************************************
* configs/stm32butterfly2/src/stm32_spi.c
*
* Copyright (C) 2016 Michał Łyszczek. All rights reserved.
* Author: Michał Łyszczek <michal.lyszczek@gmail.com>
*
* 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 NuttX 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 <debug.h>
#include <nuttx/config.h>
#include <nuttx/spi/spi.h>
#include "stm32_butterfly2.h"
#include "stm32_gpio.h"
#include "stm32_spi.h"
/*****************************************************************************
* Public Functions
****************************************************************************/
/*****************************************************************************
* Name: stm32_spidev_initialize
*
* Description:
* Called to configure SPI chip select GPIO pins.
*
* Note:
* Here only CS pins are configured as SPI pins are configured by driver
* itself.
****************************************************************************/
void stm32_spidev_initialize(void)
{
stm32_configgpio(GPIO_SD_CS);
stm32_configgpio(GPIO_SD_CD);
}
/*****************************************************************************
* Name: stm32_spi1select
*
* Description:
* Function asserts given devid based on select
****************************************************************************/
void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid,
bool select)
{
if (devid == SPIDEV_MMCSD)
{
stm32_gpiowrite(GPIO_SD_CS, !select);
}
}
/*****************************************************************************
* Name: stm32_spi1status
*
* Description:
* Return status of devid
****************************************************************************/
uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
if (devid == SPIDEV_MMCSD)
{
if (stm32_gpioread(GPIO_SD_CD) == 0)
{
return SPI_STATUS_PRESENT;
}
}
return 0;
}