Merge pull request #1939 from bthebaudeau/re-mote-sd-fat

Add global SD/MMC and FAT support, with RE-Mote as an example
This commit is contained in:
Antonio Lignan 2016-12-10 18:32:39 +01:00 committed by GitHub
commit bd3f8fa3c5
44 changed files with 39692 additions and 98 deletions

View File

@ -100,6 +100,20 @@ typedef void (* gpio_callback_t)(uint8_t port, uint8_t pin);
#define GPIO_SET_OUTPUT(PORT_BASE, PIN_MASK) \
do { REG((PORT_BASE) + GPIO_DIR) |= (PIN_MASK); } while(0)
/** \brief Return whether pins with PIN_MASK of port with PORT_BASE are set to
* output.
* \param PORT_BASE GPIO Port register offset
* \param PIN_MASK Pin number mask. Pin 0: 0x01, Pin 1: 0x02 ... Pin 7: 0x80
* \return The direction of the pins specified by PIN_MASK
*
* This macro will \e not return 0 or 1. Instead, it will return the directions
* of the pins specified by PIN_MASK ORed together. Thus, if 0xC3
* (0x80 | 0x40 | 0x02 | 0x01) is passed as the PIN_MASK and pins 7 and 0 are
* set to output, the macro will return 0x81.
*/
#define GPIO_IS_OUTPUT(PORT_BASE, PIN_MASK) \
(REG((PORT_BASE) + GPIO_DIR) & (PIN_MASK))
/** \brief Set pins with PIN_MASK of port with PORT_BASE high.
* \param PORT_BASE GPIO Port register offset
* \param PIN_MASK Pin number mask. Pin 0: 0x01, Pin 1: 0x02 ... Pin 7: 0x80

View File

@ -40,6 +40,7 @@
#include "contiki.h"
#include "reg.h"
#include "spi-arch.h"
#include "sys/cc.h"
#include "dev/ioc.h"
#include "dev/sys-ctrl.h"
#include "dev/spi.h"
@ -155,7 +156,12 @@
#if (SPI1_CPRS_CPSDVSR & 1) == 1 || SPI1_CPRS_CPSDVSR < 2 || SPI1_CPRS_CPSDVSR > 254
#error SPI1_CPRS_CPSDVSR must be an even number between 2 and 254
#endif
/*---------------------------------------------------------------------------*/
/*
* Clock source from which the baud clock is determined for the SSI, according
* to SSI_CC.CS.
*/
#define SSI_SYS_CLOCK SYS_CTRL_SYS_CLOCK
/*---------------------------------------------------------------------------*/
typedef struct {
int8_t port;
@ -314,6 +320,37 @@ spix_set_mode(uint8_t spi,
}
/*---------------------------------------------------------------------------*/
void
spix_set_clock_freq(uint8_t spi, uint32_t freq)
{
const spi_regs_t *regs;
uint64_t div;
uint32_t scr;
if(spi >= SSI_INSTANCE_COUNT) {
return;
}
regs = &spi_regs[spi];
/* Disable the SSI peripheral to configure it */
REG(regs->base + SSI_CR1) = 0;
/* Configure the SSI serial clock rate */
if(!freq) {
scr = 255;
} else {
div = (uint64_t)regs->ssi_cprs_cpsdvsr * freq;
scr = (SSI_SYS_CLOCK + div - 1) / div;
scr = MIN(MAX(scr, 1), 256) - 1;
}
REG(regs->base + SSI_CR0) = (REG(regs->base + SSI_CR0) & ~SSI_CR0_SCR_M) |
scr << SSI_CR0_SCR_S;
/* Re-enable the SSI */
REG(regs->base + SSI_CR1) |= SSI_CR1_SSE;
}
/*---------------------------------------------------------------------------*/
void
spix_cs_init(uint8_t port, uint8_t pin)
{
GPIO_SOFTWARE_CONTROL(GPIO_PORT_TO_BASE(port),

View File

@ -57,6 +57,8 @@
*/
#define SSI0_BASE 0x40008000 /**< Base address for SSI0 */
#define SSI1_BASE 0x40009000 /**< Base address for SSI1 */
/** Base address of the \c dev instance of the SSI */
#define SSI_BASE(dev) (SSI0_BASE + (dev) * (SSI1_BASE - SSI0_BASE))
/** @} */
/*---------------------------------------------------------------------------*/
/** \name SSI register offsets

View File

@ -109,17 +109,17 @@
/*---------------------------------------------------------------------------*/
/* New API macros */
#define SPIX_WAITFORTxREADY(spi) do { \
while(!(REG(CC_CONCAT3(SSI, spi, _BASE) + SSI_SR) & SSI_SR_TNF)) ; \
while(!(REG(SSI_BASE(spi) + SSI_SR) & SSI_SR_TNF)) ; \
} while(0)
#define SPIX_BUF(spi) REG(CC_CONCAT3(SSI, spi, _BASE) + SSI_DR)
#define SPIX_BUF(spi) REG(SSI_BASE(spi) + SSI_DR)
#define SPIX_WAITFOREOTx(spi) do { \
while(REG(CC_CONCAT3(SSI, spi, _BASE) + SSI_SR) & SSI_SR_BSY) ; \
while(REG(SSI_BASE(spi) + SSI_SR) & SSI_SR_BSY) ; \
} while(0)
#define SPIX_WAITFOREORx(spi) do { \
while(!(REG(CC_CONCAT3(SSI, spi, _BASE) + SSI_SR) & SSI_SR_RNE)) ; \
while(!(REG(SSI_BASE(spi) + SSI_SR) & SSI_SR_RNE)) ; \
} while(0)
#define SPIX_FLUSH(spi) do { \
while(REG(CC_CONCAT3(SSI, spi, _BASE) + SSI_SR) & SSI_SR_RNE) { \
while(REG(SSI_BASE(spi) + SSI_SR) & SSI_SR_RNE) { \
SPIX_BUF(spi); \
} \
} while(0)
@ -197,6 +197,14 @@ void spix_set_mode(uint8_t spi, uint32_t frame_format,
uint32_t clock_polarity, uint32_t clock_phase,
uint32_t data_size);
/**
* \brief Sets the SPI clock frequency of the given SSI instance.
*
* \param spi SSI instance
* \param freq Frequency (Hz)
*/
void spix_set_clock_freq(uint8_t spi, uint32_t freq);
/**
* \brief Configure a GPIO to be the chip select pin.
*

98
dev/disk/disk.h Normal file
View File

@ -0,0 +1,98 @@
/*
* Copyright (c) 2016, Benoît Thébaudeau <benoit@wsystem.com>
* All rights reserved.
*
* 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 the copyright holder 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 HOLDER 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.
*/
/**
* \addtogroup dev
* @{
*
* \defgroup disk Disk device drivers
*
* Documentation for all the disk device drivers.
* @{
*
* \file
* Header file defining the disk device driver API.
*/
#ifndef DISK_H_
#define DISK_H_
#include <stdint.h>
/** Disk status flags. */
typedef enum {
DISK_STATUS_INIT = 0x01, /**< Device initialized and ready to work */
DISK_STATUS_DISK = 0x02, /**< Medium present in the drive */
DISK_STATUS_WRITABLE = 0x04 /**< Writable medium */
} disk_status_t;
/** Generic disk I/O control commands. */
typedef enum {
DISK_IOCTL_CTRL_SYNC, /**< Synchronize the cached writes to persistent storage */
DISK_IOCTL_GET_SECTOR_COUNT, /**< Get the sector count through the \c uint32_t pointed to by \c buff */
DISK_IOCTL_GET_SECTOR_SIZE, /**< Get the sector size through the \c uint16_t pointed to by \c buff */
DISK_IOCTL_GET_BLOCK_SIZE, /**< Get the erase block size (in sectors) through the \c uint32_t pointed to by \c buff */
DISK_IOCTL_CTRL_TRIM /**< Trim the sector range within the \c uint32_t boundaries pointed to by \c buff */
} disk_ioctl_t;
/** Disk access result codes. */
typedef enum {
DISK_RESULT_OK, /**< Success */
DISK_RESULT_IO_ERROR, /**< Unrecoverable I/O error */
DISK_RESULT_WR_PROTECTED, /**< Write-protected medium */
DISK_RESULT_NO_INIT, /**< Device not initialized */
DISK_RESULT_INVALID_ARG /**< Invalid argument */
} disk_result_t;
/** Disk driver API structure. */
struct disk_driver {
/** Get device status. */
disk_status_t (*status)(uint8_t dev);
/** Initialize device. */
disk_status_t (*initialize)(uint8_t dev);
/** Read sector(s). */
disk_result_t (*read)(uint8_t dev, void *buff, uint32_t sector,
uint32_t count);
/** Write sector(s). */
disk_result_t (*write)(uint8_t dev, const void *buff, uint32_t sector,
uint32_t count);
/** Control device-specific features. */
disk_result_t (*ioctl)(uint8_t dev, uint8_t cmd, void *buff);
};
#endif /* DISK_H_ */
/**
* @}
* @}
*/

98
dev/disk/mmc/mmc-arch.h Normal file
View File

@ -0,0 +1,98 @@
/*
* Copyright (c) 2016, Benoît Thébaudeau <benoit@wsystem.com>
* All rights reserved.
*
* 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 the copyright holder 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 HOLDER 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.
*/
/**
* \addtogroup mmc
* @{
*
* \defgroup mmc-arch SD/MMC architecture-specific definitions
*
* SD/MMC device driver architecture-specific definitions.
* @{
*
* \file
* Header file for the SD/MMC device driver architecture-specific definitions.
*/
#ifndef MMC_ARCH_H_
#define MMC_ARCH_H_
#include <stddef.h>
#include <stdbool.h>
#include <stdint.h>
/** \brief Callback of the SD/MMC driver to call when the card-detection signal
* changes.
* \param dev Device
* \param cd Whether a card is detected
* \note Using this function is not mandatory. This only allows to detect a card
* replacement between two successive calls to the SD/MMC driver API.
*/
void mmc_arch_cd_changed_callback(uint8_t dev, bool cd);
/** \brief Gets the state of the card-detection signal.
* \param dev Device
* \return Whether a card is detected
*/
bool mmc_arch_get_cd(uint8_t dev);
/** \brief Gets the state of the write-protection signal.
* \param dev Device
* \return Whether the card is write-protected
*/
bool mmc_arch_get_wp(uint8_t dev);
/** \brief Sets the SPI /CS signal as indicated.
* \param dev Device
* \param sel Whether to assert /CS
*/
void mmc_arch_spi_select(uint8_t dev, bool sel);
/** \brief Sets the SPI clock frequency.
* \param dev Device
* \param freq Frequency (Hz)
*/
void mmc_arch_spi_set_clock_freq(uint8_t dev, uint32_t freq);
/** \brief Performs an SPI transfer.
* \param dev Device
* \param tx_buf Pointer to the transmission buffer, or \c NULL
* \param tx_cnt Number of bytes to transmit, or \c 0
* \param rx_buf Pointer to the reception buffer, or \c NULL
* \param rx_cnt Number of bytes to receive, or \c 0
*/
void mmc_arch_spi_xfer(uint8_t dev, const void *tx_buf, size_t tx_cnt,
void *rx_buf, size_t rx_cnt);
#endif /* MMC_ARCH_H_ */
/**
* @}
* @}
*/

608
dev/disk/mmc/mmc.c Normal file
View File

@ -0,0 +1,608 @@
/*
* Copyright (c) 2016, Benoît Thébaudeau <benoit@wsystem.com>
* All rights reserved.
*
* Based on the FatFs Module STM32 Sample Project,
* Copyright (c) 2014, ChaN
* All rights reserved.
*
* 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 the copyright holder 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 HOLDER 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.
*/
/**
* \addtogroup mmc
* @{
*
* \file
* Implementation of the SD/MMC device driver.
*/
#include <stddef.h>
#include <stdint.h>
#include "contiki.h"
#include "sys/clock.h"
#include "sys/rtimer.h"
#include "dev/watchdog.h"
#include "mmc-arch.h"
#include "mmc.h"
/* Data read/write block length */
#define BLOCK_LEN 512
/*
* Logical sector size exposed to the disk API, not to be confused with the SDSC
* sector size, which is the size of an erasable sector
*/
#define SECTOR_SIZE BLOCK_LEN
/* Clock frequency in card identification mode: fOD <= 400 kHz */
#define CLOCK_FREQ_CARD_ID_MODE 400000
/*
* Clock frequency in data transfer mode: fPP <= 20 MHz, limited by the
* backward-compatible MMC interface timings
*/
#define CLOCK_FREQ_DATA_XFER_MODE 20000000
/* SPI-mode command list */
#define CMD0 0 /* GO_IDLE_STATE */
#define CMD1 1 /* SEND_OP_COND */
#define CMD8 8 /* SEND_IF_COND */
#define CMD8_VHS_2_7_3_6 0x1
#define CMD8_ARG(vhs, check_pattern) ((vhs) << 8 | (check_pattern))
#define CMD8_ECHO_MASK 0x00000fff
#define CMD9 9 /* SEND_CSD */
#define CMD10 10 /* SEND_CID */
#define CMD12 12 /* STOP_TRANSMISSION */
#define CMD13 13 /* SEND_STATUS */
#define CMD16 16 /* SET_BLOCKLEN */
#define CMD17 17 /* READ_SINGLE_BLOCK */
#define CMD18 18 /* READ_MULTIPLE_BLOCK */
#define CMD23 23 /* SET_BLOCK_COUNT */
#define CMD24 24 /* WRITE_BLOCK */
#define CMD25 25 /* WRITE_MULTIPLE_BLOCK */
#define CMD32 32 /* ERASE_WR_BLK_START */
#define CMD33 33 /* ERASE_WR_BLK_END */
#define CMD38 38 /* ERASE */
#define CMD55 55 /* APP_CMD */
#define CMD58 58 /* READ_OCR */
#define ACMD 0x80 /* Application-specific command */
#define ACMD13 (ACMD | 13) /* SD_STATUS */
#define ACMD23 (ACMD | 23) /* SET_WR_BLK_ERASE_COUNT */
#define ACMD41 (ACMD | 41) /* SD_APP_OP_COND */
#define ACMD41_HCS (1 << 30)
#define CMD_TX 0x40 /* Command transmission bit */
#define R1_MSB 0x00
#define R1_SUCCESS 0x00
#define R1_IDLE_STATE (1 << 0)
#define R1_ERASE_RESET (1 << 1)
#define R1_ILLEGAL_COMMAND (1 << 2)
#define R1_COM_CRC_ERROR (1 << 3)
#define R1_ERASE_SEQUENCE_ERROR (1 << 4)
#define R1_ADDRESS_ERROR (1 << 5)
#define R1_PARAMETER_ERROR (1 << 6)
#define TOK_DATA_RESP_MASK 0x1f
#define TOK_DATA_RESP_ACCEPTED 0x05
#define TOK_DATA_RESP_CRC_ERROR 0x0b
#define TOK_DATA_RESP_WR_ERROR 0x0d
#define TOK_RD_SINGLE_WR_START_BLOCK 0xfe
#define TOK_MULTI_WR_START_BLOCK 0xfc
#define TOK_MULTI_WR_STOP_TRAN 0xfd
/* The SD Status is one data block of 512 bits. */
#define SD_STATUS_SIZE (512 / 8)
#define SD_STATUS_AU_SIZE(sd_status) ((sd_status)[10] >> 4)
#define OCR_CCS (1 << 30)
#define CSD_SIZE 16
#define CSD_STRUCTURE(csd) ((csd)[0] >> 6)
#define CSD_STRUCTURE_SD_V1_0 0
#define CSD_STRUCTURE_SD_V2_0 1
#define CSD_SD_V1_0_READ_BL_LEN(csd) ((csd)[5] & 0x0f)
#define CSD_SD_V1_0_BLOCK_LEN(csd) (1ull << CSD_SD_V1_0_READ_BL_LEN(csd))
#define CSD_SD_V1_0_C_SIZE(csd) \
(((csd)[6] & 0x03) << 10 | (csd)[7] << 2 | (csd)[8] >> 6)
#define CSD_SD_V1_0_C_SIZE_MULT(csd) \
(((csd)[9] & 0x03) << 1 | (csd)[10] >> 7)
#define CSD_SD_V1_0_MULT(csd) \
(1 << (CSD_SD_V1_0_C_SIZE_MULT(csd) + 2))
#define CSD_SD_V1_0_BLOCKNR(csd) \
(((uint32_t)CSD_SD_V1_0_C_SIZE(csd) + 1) * CSD_SD_V1_0_MULT(csd))
#define CSD_SD_V1_0_CAPACITY(csd) \
(CSD_SD_V1_0_BLOCKNR(csd) * CSD_SD_V1_0_BLOCK_LEN(csd))
#define CSD_SD_V1_0_SECTOR_SIZE(csd) \
(((csd)[10] & 0x3f) << 1 | (csd)[11] >> 7)
#define CSD_SD_V1_0_WRITE_BL_LEN(csd) \
(((csd)[12] & 0x03) << 2 | (csd)[13] >> 6)
#define CSD_SD_V2_0_C_SIZE(csd) \
(((csd)[7] & 0x3f) << 16 | (csd)[8] << 8 | (csd)[9])
#define CSD_SD_V2_0_CAPACITY(csd) \
(((uint64_t)CSD_SD_V2_0_C_SIZE(csd) + 1) << 19)
#define CSD_MMC_ERASE_GRP_SIZE(csd) (((csd)[10] & 0x7c) >> 2)
#define CSD_MMC_ERASE_GRP_MULT(csd) \
(((csd)[10] & 0x03) << 3 | (csd)[11] >> 5)
#define CSD_MMC_WRITE_BL_LEN(csd) \
(((csd)[12] & 0x03) << 2 | (csd)[13] >> 6)
typedef enum {
CARD_TYPE_MMC = 0x01, /* MMC v3 */
CARD_TYPE_SD1 = 0x02, /* SD v1 */
CARD_TYPE_SD2 = 0x04, /* SD v2 */
CARD_TYPE_SD = CARD_TYPE_SD1 | CARD_TYPE_SD2, /* SD */
CARD_TYPE_BLOCK = 0x08 /* Block addressing */
} card_type_t;
static struct mmc_priv {
uint8_t status;
uint8_t card_type;
} mmc_priv[MMC_CONF_DEV_COUNT];
/*----------------------------------------------------------------------------*/
static uint8_t
mmc_spi_xchg(uint8_t dev, uint8_t tx_byte)
{
uint8_t rx_byte;
mmc_arch_spi_xfer(dev, &tx_byte, 1, &rx_byte, 1);
return rx_byte;
}
/*----------------------------------------------------------------------------*/
static void
mmc_spi_tx(uint8_t dev, const void *buf, size_t cnt)
{
mmc_arch_spi_xfer(dev, buf, cnt, NULL, 0);
}
/*----------------------------------------------------------------------------*/
static void
mmc_spi_rx(uint8_t dev, void *buf, size_t cnt)
{
mmc_arch_spi_xfer(dev, NULL, 0, buf, cnt);
}
/*----------------------------------------------------------------------------*/
static bool
mmc_wait_ready(uint8_t dev, uint16_t timeout_ms)
{
rtimer_clock_t timeout_end =
RTIMER_NOW() + ((uint32_t)timeout_ms * RTIMER_SECOND + 999) / 1000;
uint8_t rx_byte;
do {
rx_byte = mmc_spi_xchg(dev, 0xff);
watchdog_periodic();
} while(rx_byte != 0xff && RTIMER_CLOCK_LT(RTIMER_NOW(), timeout_end));
return rx_byte == 0xff;
}
/*----------------------------------------------------------------------------*/
static bool
mmc_select(uint8_t dev, bool sel)
{
mmc_arch_spi_select(dev, sel);
mmc_spi_xchg(dev, 0xff); /* Dummy clock (force D0) */
if(sel && !mmc_wait_ready(dev, 500)) {
mmc_select(dev, false);
return false;
}
return true;
}
/*----------------------------------------------------------------------------*/
static uint8_t
mmc_send_cmd(uint8_t dev, uint8_t cmd, uint32_t arg)
{
uint8_t resp, n;
/* Send a CMD55 prior to a ACMD<n>. */
if(cmd & ACMD) {
cmd &= ~ACMD;
resp = mmc_send_cmd(dev, CMD55, 0);
if(resp != R1_SUCCESS && resp != R1_IDLE_STATE) {
return resp;
}
}
/*
* Select the card and wait for ready, except to stop a multiple-block read.
*/
if(cmd != CMD12) {
mmc_select(dev, false);
if(!mmc_select(dev, true)) {
return 0xff;
}
}
/* Send the command packet. */
mmc_spi_xchg(dev, CMD_TX | cmd); /* Start & tx bits, cmd index */
mmc_spi_xchg(dev, arg >> 24); /* Argument[31..24] */
mmc_spi_xchg(dev, arg >> 16); /* Argument[23..16] */
mmc_spi_xchg(dev, arg >> 8); /* Argument[15..8] */
mmc_spi_xchg(dev, arg); /* Argument[7..0] */
switch(cmd) {
case CMD0:
n = 0x95; /* CMD0(0) CRC7, end bit */
break;
case CMD8:
n = 0x87; /* CMD8(0x1aa) CRC7, end bit */
break;
default:
n = 0x01; /* Dummy CRC7, end bit */
break;
}
mmc_spi_xchg(dev, n);
/* Receive the command response. */
if(cmd == CMD12) {
mmc_spi_xchg(dev, 0xff); /* Discard following byte if CMD12. */
}
/* Wait for the response (max. 10 bytes). */
n = 10;
do {
resp = mmc_spi_xchg(dev, 0xff);
} while((resp & 0x80) != R1_MSB && --n);
return resp;
}
/*----------------------------------------------------------------------------*/
static bool
mmc_tx_block(uint8_t dev, const void *buf, uint8_t token)
{
uint8_t resp;
if(!mmc_wait_ready(dev, 500)) {
return false;
}
mmc_spi_xchg(dev, token);
if(token != TOK_MULTI_WR_STOP_TRAN) {
mmc_spi_tx(dev, buf, BLOCK_LEN);
mmc_spi_xchg(dev, 0xff); /* Dummy CRC */
mmc_spi_xchg(dev, 0xff);
resp = mmc_spi_xchg(dev, 0xff);
if((resp & TOK_DATA_RESP_MASK) != TOK_DATA_RESP_ACCEPTED) {
return false;
}
}
return true;
}
/*----------------------------------------------------------------------------*/
static bool
mmc_rx(uint8_t dev, void *buf, size_t cnt)
{
rtimer_clock_t timeout_end =
RTIMER_NOW() + (200ul * RTIMER_SECOND + 999) / 1000;
uint8_t token;
do {
token = mmc_spi_xchg(dev, 0xff);
watchdog_periodic();
} while(token == 0xff && RTIMER_CLOCK_LT(RTIMER_NOW(), timeout_end));
if(token != TOK_RD_SINGLE_WR_START_BLOCK) {
return false;
}
mmc_spi_rx(dev, buf, cnt);
mmc_spi_xchg(dev, 0xff); /* Discard CRC. */
mmc_spi_xchg(dev, 0xff);
return true;
}
/*----------------------------------------------------------------------------*/
void
mmc_arch_cd_changed_callback(uint8_t dev, bool cd)
{
uint8_t status;
if(dev >= MMC_CONF_DEV_COUNT) {
return;
}
if(cd) {
status = DISK_STATUS_DISK;
if(!mmc_arch_get_wp(dev)) {
status |= DISK_STATUS_WRITABLE;
}
} else {
status = 0;
}
mmc_priv[dev].status = status;
}
/*----------------------------------------------------------------------------*/
static disk_status_t
mmc_status(uint8_t dev)
{
bool cd;
struct mmc_priv *priv;
if(dev >= MMC_CONF_DEV_COUNT) {
return DISK_RESULT_INVALID_ARG;
}
cd = mmc_arch_get_cd(dev);
priv = &mmc_priv[dev];
if(cd == !(priv->status & DISK_STATUS_DISK)) {
mmc_arch_cd_changed_callback(dev, cd);
}
return priv->status;
}
/*----------------------------------------------------------------------------*/
static disk_status_t
mmc_initialize(uint8_t dev)
{
disk_status_t status;
uint8_t n, cmd;
card_type_t card_type;
rtimer_clock_t timeout_end;
uint32_t arg, resp, ocr;
struct mmc_priv *priv;
if(dev >= MMC_CONF_DEV_COUNT) {
return DISK_RESULT_INVALID_ARG;
}
status = mmc_status(dev);
if(!(status & DISK_STATUS_DISK)) {
return status;
}
mmc_arch_spi_select(dev, false);
clock_delay_usec(10000);
mmc_arch_spi_set_clock_freq(dev, CLOCK_FREQ_CARD_ID_MODE);
for(n = 10; n; n--) {
mmc_spi_xchg(dev, 0xff); /* Generate 80 dummy clock cycles. */
}
card_type = 0;
if(mmc_send_cmd(dev, CMD0, 0) == R1_IDLE_STATE) {
timeout_end = RTIMER_NOW() + RTIMER_SECOND;
arg = CMD8_ARG(CMD8_VHS_2_7_3_6, 0xaa); /* Arbitrary check pattern */
if(mmc_send_cmd(dev, CMD8, arg) == R1_IDLE_STATE) { /* SD v2? */
resp = 0;
for(n = 4; n; n--) {
resp = resp << 8 | mmc_spi_xchg(dev, 0xff);
}
/* Does the card support 2.7 V - 3.6 V? */
if((arg & CMD8_ECHO_MASK) == (resp & CMD8_ECHO_MASK)) {
/* Wait for end of initialization. */
while(RTIMER_CLOCK_LT(RTIMER_NOW(), timeout_end) &&
mmc_send_cmd(dev, ACMD41, ACMD41_HCS) != R1_SUCCESS) {
watchdog_periodic();
}
if(RTIMER_CLOCK_LT(RTIMER_NOW(), timeout_end) &&
mmc_send_cmd(dev, CMD58, 0) == R1_SUCCESS) { /* Read OCR. */
ocr = 0;
for(n = 4; n; n--) {
ocr = ocr << 8 | mmc_spi_xchg(dev, 0xff);
}
card_type = CARD_TYPE_SD2;
if(ocr & OCR_CCS) {
card_type |= CARD_TYPE_BLOCK;
}
}
}
} else { /* Not SD v2 */
resp = mmc_send_cmd(dev, ACMD41, 0);
if(resp == R1_SUCCESS || resp == R1_IDLE_STATE) { /* SD v1 or MMC? */
card_type = CARD_TYPE_SD1;
cmd = ACMD41;
} else {
card_type = CARD_TYPE_MMC;
cmd = CMD1;
}
/* Wait for end of initialization. */
while(RTIMER_CLOCK_LT(RTIMER_NOW(), timeout_end) &&
mmc_send_cmd(dev, cmd, 0) != R1_SUCCESS) {
watchdog_periodic();
}
/* Set block length. */
if(!RTIMER_CLOCK_LT(RTIMER_NOW(), timeout_end) ||
mmc_send_cmd(dev, CMD16, BLOCK_LEN) != R1_SUCCESS) {
card_type = 0;
}
}
}
priv = &mmc_priv[dev];
priv->card_type = card_type;
mmc_select(dev, false);
status = priv->status;
if(status & DISK_STATUS_DISK && card_type) { /* OK */
mmc_arch_spi_set_clock_freq(dev, CLOCK_FREQ_DATA_XFER_MODE);
status |= DISK_STATUS_INIT;
} else { /* Failed */
status &= ~DISK_STATUS_INIT;
}
priv->status = status;
return status;
}
/*----------------------------------------------------------------------------*/
static disk_result_t
mmc_read(uint8_t dev, void *buff, uint32_t sector, uint32_t count)
{
if(dev >= MMC_CONF_DEV_COUNT || !count) {
return DISK_RESULT_INVALID_ARG;
}
if(!(mmc_status(dev) & DISK_STATUS_INIT)) {
return DISK_RESULT_NO_INIT;
}
if(!(mmc_priv[dev].card_type & CARD_TYPE_BLOCK)) {
sector *= SECTOR_SIZE;
}
if(count == 1) {
if(mmc_send_cmd(dev, CMD17, sector) == R1_SUCCESS &&
mmc_rx(dev, buff, SECTOR_SIZE)) {
count = 0;
}
} else if(mmc_send_cmd(dev, CMD18, sector) == R1_SUCCESS) {
do {
if(!mmc_rx(dev, buff, SECTOR_SIZE)) {
break;
}
buff = (uint8_t *)buff + SECTOR_SIZE;
watchdog_periodic();
} while(--count);
mmc_send_cmd(dev, CMD12, 0); /* Stop transmission. */
}
mmc_select(dev, false);
return count ? DISK_RESULT_IO_ERROR : DISK_RESULT_OK;
}
/*----------------------------------------------------------------------------*/
static disk_result_t
mmc_write(uint8_t dev, const void *buff, uint32_t sector, uint32_t count)
{
disk_status_t status;
card_type_t card_type;
if(dev >= MMC_CONF_DEV_COUNT || !count) {
return DISK_RESULT_INVALID_ARG;
}
status = mmc_status(dev);
if(!(status & DISK_STATUS_INIT)) {
return DISK_RESULT_NO_INIT;
}
if(!(status & DISK_STATUS_WRITABLE)) {
return DISK_RESULT_WR_PROTECTED;
}
card_type = mmc_priv[dev].card_type;
if(!(card_type & CARD_TYPE_BLOCK)) {
sector *= SECTOR_SIZE;
}
if(count == 1) {
if(mmc_send_cmd(dev, CMD24, sector) == R1_SUCCESS &&
mmc_tx_block(dev, buff, TOK_RD_SINGLE_WR_START_BLOCK)) {
count = 0;
}
} else {
if(card_type & CARD_TYPE_SD) {
mmc_send_cmd(dev, ACMD23, count);
}
if(mmc_send_cmd(dev, CMD25, sector) == R1_SUCCESS) {
do {
if(!mmc_tx_block(dev, buff, TOK_MULTI_WR_START_BLOCK)) {
break;
}
buff = (uint8_t *)buff + BLOCK_LEN;
watchdog_periodic();
} while(--count);
if(!mmc_tx_block(dev, NULL, TOK_MULTI_WR_STOP_TRAN)) {
count = 1;
}
}
}
mmc_select(dev, false);
return count ? DISK_RESULT_IO_ERROR : DISK_RESULT_OK;
}
/*----------------------------------------------------------------------------*/
static disk_result_t
mmc_ioctl(uint8_t dev, uint8_t cmd, void *buff)
{
card_type_t card_type;
disk_result_t res;
uint8_t csd[CSD_SIZE], sd_status[SD_STATUS_SIZE], au_size;
uint64_t capacity;
uint32_t block_size;
static const uint8_t AU_TO_BLOCK_SIZE[] = {12, 16, 24, 32, 64};
if(dev >= MMC_CONF_DEV_COUNT) {
return DISK_RESULT_INVALID_ARG;
}
if(!(mmc_status(dev) & DISK_STATUS_INIT)) {
return DISK_RESULT_NO_INIT;
}
card_type = mmc_priv[dev].card_type;
res = DISK_RESULT_IO_ERROR;
switch(cmd) {
case DISK_IOCTL_CTRL_SYNC:
if(mmc_select(dev, true)) {
res = DISK_RESULT_OK;
}
break;
case DISK_IOCTL_GET_SECTOR_COUNT:
if(mmc_send_cmd(dev, CMD9, 0) == R1_SUCCESS && mmc_rx(dev, csd, CSD_SIZE)) {
capacity = CSD_STRUCTURE(csd) == CSD_STRUCTURE_SD_V2_0 ?
CSD_SD_V2_0_CAPACITY(csd) : CSD_SD_V1_0_CAPACITY(csd);
*(uint32_t *)buff = capacity / SECTOR_SIZE;
res = DISK_RESULT_OK;
}
break;
case DISK_IOCTL_GET_SECTOR_SIZE:
*(uint16_t *)buff = SECTOR_SIZE;
res = DISK_RESULT_OK;
break;
case DISK_IOCTL_GET_BLOCK_SIZE:
if(card_type & CARD_TYPE_SD2) {
if(mmc_send_cmd(dev, ACMD13, 0) == R1_SUCCESS) { /* Read SD status. */
mmc_spi_xchg(dev, 0xff);
if(mmc_rx(dev, sd_status, SD_STATUS_SIZE)) {
au_size = SD_STATUS_AU_SIZE(sd_status);
if(au_size) {
block_size = au_size <= 0xa ? 8192ull << au_size :
(uint32_t)AU_TO_BLOCK_SIZE[au_size - 0xb] << 20;
*(uint32_t *)buff = block_size / SECTOR_SIZE;
res = DISK_RESULT_OK;
}
}
}
} else if(mmc_send_cmd(dev, CMD9, 0) == R1_SUCCESS &&
mmc_rx(dev, csd, CSD_SIZE)) {
if(card_type & CARD_TYPE_SD1) {
block_size = (uint32_t)(CSD_SD_V1_0_SECTOR_SIZE(csd) + 1) <<
CSD_SD_V1_0_WRITE_BL_LEN(csd);
} else { /* MMC */
block_size = (uint32_t)(CSD_MMC_ERASE_GRP_SIZE(csd) + 1) *
(CSD_MMC_ERASE_GRP_MULT(csd) + 1) <<
CSD_MMC_WRITE_BL_LEN(csd);
}
*(uint32_t *)buff = block_size / SECTOR_SIZE;
res = DISK_RESULT_OK;
}
break;
default:
res = DISK_RESULT_INVALID_ARG;
break;
}
mmc_select(dev, false);
return res;
}
/*----------------------------------------------------------------------------*/
const struct disk_driver mmc_driver = {
.status = mmc_status,
.initialize = mmc_initialize,
.read = mmc_read,
.write = mmc_write,
.ioctl = mmc_ioctl
};
/*----------------------------------------------------------------------------*/
/** @} */

61
dev/disk/mmc/mmc.h Normal file
View File

@ -0,0 +1,61 @@
/*
* Copyright (c) 2016, Benoît Thébaudeau <benoit@wsystem.com>
* All rights reserved.
*
* 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 the copyright holder 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 HOLDER 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.
*/
/**
* \addtogroup disk
* @{
*
* \defgroup mmc SD/MMC
*
* SD/MMC device driver.
* @{
*
* \file
* Header file for the SD/MMC device driver.
*/
#ifndef MMC_H_
#define MMC_H_
#include "contiki-conf.h"
#include "../disk.h"
#ifndef MMC_CONF_DEV_COUNT
/** Number of SD/MMC devices. */
#define MMC_CONF_DEV_COUNT 1
#endif
extern const struct disk_driver mmc_driver;
#endif /* MMC_H_ */
/**
* @}
* @}
*/

12
examples/fat/Makefile Normal file
View File

@ -0,0 +1,12 @@
DEFINES+=PROJECT_CONF_H=\"project-conf.h\"
CONTIKI = ../..
all: example-fat
CONTIKI_WITH_RIME = 1
ifeq ($(TARGET), zoul)
BOARD ?= remote-revb
endif
include $(CONTIKI)/Makefile.include

View File

@ -0,0 +1,2 @@
TARGET = zoul
BOARD ?= remote-revb

6
examples/fat/README.md Normal file
View File

@ -0,0 +1,6 @@
FAT File System Example
=======================
Supported Hardware (tested or known to work)
--------------------------------------------
* Zoul: RE-Mote revision B

View File

@ -0,0 +1,96 @@
/*
* Copyright (c) 2016, Benoît Thébaudeau <benoit@wsystem.com>
* All rights reserved.
*
* 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 the copyright holder 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 HOLDER 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.
*/
/*---------------------------------------------------------------------------*/
/**
* \file
* Example demonstrating how to use the FAT file system.
*/
/*---------------------------------------------------------------------------*/
#include <stdio.h>
#include "contiki.h"
#include "ff.h"
/*---------------------------------------------------------------------------*/
PROCESS(example_fat_process, "FAT example");
AUTOSTART_PROCESSES(&example_fat_process);
/*---------------------------------------------------------------------------*/
#define TEST_FILENAME "test.txt"
#define TEST_LINE "Hello world!"
/*---------------------------------------------------------------------------*/
PROCESS_THREAD(example_fat_process, ev, data)
{
static FATFS FatFs; /* Work area (file system object) for logical drive */
FIL fil; /* File object */
char line[82]; /* Line buffer */
FRESULT fr; /* FatFs return code */
PROCESS_BEGIN();
printf("FAT example\n");
/* Register work area to the default drive */
f_mount(&FatFs, "", 0);
printf("Writing \"%s\" to \"%s\"\n", TEST_LINE, TEST_FILENAME);
/* Create the test file */
fr = f_open(&fil, TEST_FILENAME, FA_WRITE | FA_CREATE_ALWAYS);
if(fr) {
printf("f_open() error: %d\n", fr);
PROCESS_EXIT();
}
/* Write the test line */
f_printf(&fil, "%s\n", TEST_LINE);
/* Close the file */
f_close(&fil);
printf("Reading back \"%s\":\n\n", TEST_FILENAME);
/* Open the test file */
fr = f_open(&fil, TEST_FILENAME, FA_READ);
if(fr) {
printf("f_open() error: %d\n", fr);
PROCESS_EXIT();
}
/* Read all the lines and display them */
while(f_gets(line, sizeof(line), &fil)) {
printf(line);
}
/* Close the file */
f_close(&fil);
printf("\nDone\n");
PROCESS_END();
}

View File

@ -0,0 +1,41 @@
/*
* Copyright (c) 2016, Benoît Thébaudeau <benoit.thebaudeau.dev@gmail.com>
* All rights reserved.
*
* 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 the copyright holder 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 HOLDER 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 PROJECT_CONF_H_
#define PROJECT_CONF_H_
/*---------------------------------------------------------------------------*/
#if CONTIKI_TARGET_ZOUL
#define RTC_CONF_INIT 1
#define RTC_CONF_SET_FROM_SYS 1
#endif
#endif /* PROJECT_CONF_H_ */
/*---------------------------------------------------------------------------*/

View File

@ -4,9 +4,6 @@ CONTIKI_PROJECT = test-power-mgmt
BOARD ?= remote-revb
# Works in Linux and probably on OSX too (RTCC example)
CFLAGS = -DDATE="\"`date +"%02u %02d %02m %02y %02H %02M %02S"`\""
all: $(CONTIKI_PROJECT)
CONTIKI = ../../../..

View File

@ -46,6 +46,9 @@
#define BROADCAST_CHANNEL 129
#define NETSTACK_CONF_RDC nullrdc_driver
#define RTC_CONF_INIT 1
#define RTC_CONF_SET_FROM_SYS 1
#endif /* PROJECT_CONF_H_ */
/**

View File

@ -59,10 +59,6 @@ static struct etimer et;
/* RE-Mote revision B, low-power PIC version */
#define PM_EXPECTED_VERSION 0x20
/*---------------------------------------------------------------------------*/
#ifndef DATE
#define DATE "Unknown"
#endif
/*---------------------------------------------------------------------------*/
#define TEST_LEDS_FAIL leds_off(LEDS_ALL); \
leds_on(LEDS_RED); \
PROCESS_EXIT();
@ -80,7 +76,6 @@ PROCESS_THREAD(test_remote_pm, ev, data)
static uint8_t aux;
static uint16_t voltage;
static uint32_t cycles;
static char *next;
PROCESS_BEGIN();
@ -162,38 +157,13 @@ PROCESS_THREAD(test_remote_pm, ev, data)
/* Configure the RTCC to schedule a "hard" restart of the shutdown mode,
* waking up from a RTCC interrupt to the low-power PIC
*/
printf("PM: System date: %s\n", DATE);
if(strcmp("Unknown", DATE) == 0) {
printf("PM: could not retrieve date from system\n");
printf("PM\n");
if(rtcc_get_time_date(simple_td) == AB08_ERROR) {
printf("PM: Couldn't read time and date\n");
TEST_LEDS_FAIL;
}
/* Configure RTC and return structure with all parameters */
rtcc_init();
/* Configure the RTC with the current values */
simple_td->weekdays = (uint8_t)strtol(DATE, &next, 10);
simple_td->day = (uint8_t)strtol(next, &next, 10);
simple_td->months = (uint8_t)strtol(next, &next, 10);
simple_td->years = (uint8_t)strtol(next, &next, 10);
simple_td->hours = (uint8_t)strtol(next, &next, 10);
simple_td->minutes = (uint8_t)strtol(next, &next, 10);
simple_td->seconds = (uint8_t)strtol(next, NULL, 10);
simple_td->miliseconds = 0;
simple_td->mode = RTCC_24H_MODE;
simple_td->century = RTCC_CENTURY_20XX;
if(rtcc_set_time_date(simple_td) == AB08_ERROR) {
printf("PM: Time and date configuration failed\n");
TEST_LEDS_FAIL;
} else {
if(rtcc_get_time_date(simple_td) == AB08_ERROR) {
printf("PM: Couldn't read time and date\n");
TEST_LEDS_FAIL;
}
}
printf("PM: Configured time: ");
rtcc_print(RTCC_PRINT_DATE_DEC);

View File

@ -3,9 +3,6 @@ CONTIKI_PROJECT = test-rtcc
TARGET = zoul
# Works in Linux and probably on OSX too (RTCC example)
CFLAGS = -DDATE="\"`date +"%02u %02d %02m %02y %02H %02M %02S"`\""
all: $(CONTIKI_PROJECT)
CONTIKI = ../../../..

View File

@ -47,6 +47,9 @@
#define NETSTACK_CONF_RDC nullrdc_driver
#define RTC_CONF_INIT 1
#define RTC_CONF_SET_FROM_SYS 1
#endif /* PROJECT_CONF_H_ */
/*---------------------------------------------------------------------------*/
/**

View File

@ -55,10 +55,6 @@
#include <stdio.h>
#include <stdlib.h>
/*---------------------------------------------------------------------------*/
#ifndef DATE
#define DATE "Unknown"
#endif
/*---------------------------------------------------------------------------*/
#define LOOP_PERIOD 60L
#define LOOP_INTERVAL (CLOCK_SECOND * LOOP_PERIOD)
#define TEST_ALARM_SECOND 15
@ -109,58 +105,13 @@ rtcc_interrupt_callback(uint8_t value)
/*---------------------------------------------------------------------------*/
PROCESS_THREAD(test_remote_rtcc_process, ev, data)
{
static char *next;
PROCESS_BEGIN();
/* Alternatively for test only, undefine DATE and define on your own as
* #define DATE "07 06 12 15 16 00 00"
* Also note that if you restart the node at a given time, it will use the
* already defined DATE, so if you want to update the device date/time you
* need to reflash the node
*/
/* Get the system date in the following format: wd dd mm yy hh mm ss */
printf("RE-Mote RTC test, system date: %s\n", DATE);
/* Sanity check */
if(strcmp("Unknown", DATE) == 0) {
printf("Fail: could not retrieve date from system\n");
PROCESS_EXIT();
}
/* Configure RTC and return structure with all parameters */
rtcc_init();
printf("RE-Mote RTC test\n");
/* Map interrupt callback handler */
RTCC_REGISTER_INT1(rtcc_interrupt_callback);
/* Configure the RTC with the current values */
simple_td->weekdays = (uint8_t)strtol(DATE, &next, 10);
simple_td->day = (uint8_t)strtol(next, &next, 10);
simple_td->months = (uint8_t)strtol(next, &next, 10);
simple_td->years = (uint8_t)strtol(next, &next, 10);
simple_td->hours = (uint8_t)strtol(next, &next, 10);
simple_td->minutes = (uint8_t)strtol(next, &next, 10);
simple_td->seconds = (uint8_t)strtol(next, NULL, 10);
/* Don't care about the milliseconds... */
simple_td->miliseconds = 0;
/* This example relies on 24h mode */
simple_td->mode = RTCC_24H_MODE;
/* And to simplify the configuration, it relies it will be executed in the
* present century
*/
simple_td->century = RTCC_CENTURY_20XX;
/* Set the time and date */
if(rtcc_set_time_date(simple_td) == AB08_ERROR) {
printf("Fail: Time and date not configured\n");
PROCESS_EXIT();
}
/* Wait a bit */
etimer_set(&et, (CLOCK_SECOND * 2));
PROCESS_WAIT_EVENT_UNTIL(etimer_expired(&et));

279
lib/fs/fat/00history.txt Normal file
View File

@ -0,0 +1,279 @@
----------------------------------------------------------------------------
Revision history of FatFs module
----------------------------------------------------------------------------
R0.00 (February 26, 2006)
Prototype.
R0.01 (April 29, 2006)
The first release.
R0.02 (June 01, 2006)
Added FAT12 support.
Removed unbuffered mode.
Fixed a problem on small (<32M) partition.
R0.02a (June 10, 2006)