Added some libraries that need implementation to achieve 115200 bitrates for sd card logging

This commit is contained in:
Mike C 2013-04-25 22:15:16 -04:00
parent f4f8367236
commit fc49b2e735
494 changed files with 90637 additions and 0 deletions

View file

@ -0,0 +1,171 @@
// A simple data logger for the Adafruit Data Logging shield on a mega
// You must edit SdFatConfig.h and set MEGA_SOFT_SPI nonzero
#include <SdFat.h>
#include <SdFatUtil.h> // define FreeRam()
#include <I2cMaster.h>
#include <SoftRTClib.h>
#define CHIP_SELECT 10 // SD chip select pin
#define LOG_INTERVAL 1000 // mills between entries
#define SENSOR_COUNT 3 // number of analog pins to log
#define ECHO_TO_SERIAL 1 // echo data to serial port if nonzero
#define WAIT_TO_START 1 // Wait for serial input in setup()
#define ADC_DELAY 10 // ADC delay for high impedence sensors
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
#if !MEGA_SOFT_SPI
#error set MEGA_SOFT_SPI nonzero in libraries/SdFat/SdFatConfig.h
#endif // MEGA_SOFT_SPI
// Is a Mega use analog pins 4, 5 for software I2C
const uint8_t RTC_SCL_PIN = 59;
const uint8_t RTC_SDA_PIN = 58;
SoftI2cMaster i2c(RTC_SDA_PIN, RTC_SCL_PIN);
#elif defined(__AVR_ATmega32U4__)
#if !LEONARDO_SOFT_SPI
#error set LEONARDO_SOFT_SPI nonzero in libraries/SdFat/SdFatConfig.h
#endif // LEONARDO_SOFT_SPI
// Is a Leonardo use analog pins 4, 5 for software I2C
const uint8_t RTC_SCL_PIN = 23;
const uint8_t RTC_SDA_PIN = 22;
SoftI2cMaster i2c(RTC_SDA_PIN, RTC_SCL_PIN);
#else // defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
// Not Mega use hardware I2C
// enable pull-ups on SDA/SCL
TwiMaster i2c(true);
#endif // defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
RTC_DS1307 RTC(&i2c); // define the Real Time Clock object
// file system object
SdFat sd;
// text file for logging
ofstream logfile;
// Serial print stream
ArduinoOutStream cout(Serial);
// buffer to format data - makes it eaiser to echo to Serial
char buf[80];
//------------------------------------------------------------------------------
#if SENSOR_COUNT > 6
#error SENSOR_COUNT too large
#endif // SENSOR_COUNT
//------------------------------------------------------------------------------
// store error strings in flash to save RAM
#define error(s) sd.errorHalt_P(PSTR(s))
//------------------------------------------------------------------------------
// call back for file timestamps
void dateTime(uint16_t* date, uint16_t* time) {
DateTime now = RTC.now();
// return date using FAT_DATE macro to format fields
*date = FAT_DATE(now.year(), now.month(), now.day());
// return time using FAT_TIME macro to format fields
*time = FAT_TIME(now.hour(), now.minute(), now.second());
}
//------------------------------------------------------------------------------
// format date/time
ostream& operator << (ostream& os, DateTime& dt) {
os << dt.year() << '/' << int(dt.month()) << '/' << int(dt.day()) << ',';
os << int(dt.hour()) << ':' << setfill('0') << setw(2) << int(dt.minute());
os << ':' << setw(2) << int(dt.second()) << setfill(' ');
return os;
}
//------------------------------------------------------------------------------
void setup() {
// For Leonardo
while (!Serial) {}
Serial.begin(9600);
// pstr stores strings in flash to save RAM
cout << endl << pstr("FreeRam: ") << FreeRam() << endl;
#if WAIT_TO_START
cout << pstr("Type any character to start\n");
while (Serial.read() < 0) {}
#endif // WAIT_TO_START
// connect to RTC
if (!RTC.begin()) error("RTC failed");
// set date time callback function
SdFile::dateTimeCallback(dateTime);
DateTime now = RTC.now();
cout << now << endl;
// initialize the SD card
if (!sd.begin(CHIP_SELECT)) sd.initErrorHalt();
// create a new file in root, the current working directory
char name[] = "LOGGER00.CSV";
for (uint8_t i = 0; i < 100; i++) {
name[6] = i/10 + '0';
name[7] = i%10 + '0';
if (sd.exists(name)) continue;
logfile.open(name);
break;
}
if (!logfile.is_open()) error("file.open");
cout << pstr("Logging to: ") << name << endl;
// format header in buffer
obufstream bout(buf, sizeof(buf));
bout << pstr("millis");
bout << pstr(",date,time");
for (uint8_t i = 0; i < SENSOR_COUNT; i++) {
bout << pstr(",sens") << int(i);
}
logfile << buf << endl;
#if ECHO_TO_SERIAL
cout << buf << endl;
#endif // ECHO_TO_SERIAL
}
//------------------------------------------------------------------------------
void loop() {
uint32_t m;
// wait for time to be a multiple of interval
do {
m = millis();
} while (m % LOG_INTERVAL);
// use buffer stream to format line
obufstream bout(buf, sizeof(buf));
// start with time in millis
bout << m;
DateTime now = RTC.now();
bout << ',' << now;
// read analog pins and format data
for (uint8_t ia = 0; ia < SENSOR_COUNT; ia++) {
#if ADC_DELAY
analogRead(ia);
delay(ADC_DELAY);
#endif // ADC_DELAY
bout << ',' << analogRead(ia);
}
bout << endl;
// log data and flush to SD
logfile << buf << flush;
// check for error
if (!logfile) error("write data failed");
#if ECHO_TO_SERIAL
cout << buf;
#endif // ECHO_TO_SERIAL
// don't log two points in the same millis
if (m == millis()) delay(1);
}

View file

@ -0,0 +1,234 @@
/* Arduino I2cMaster Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino I2cMaster Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino I2cMaster Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#include <I2cMaster.h>
//==============================================================================
// WARNING don't change SoftI2cMaster unless you verify the change with a scope
//------------------------------------------------------------------------------
/**
* Initialize SCL/SDA pins and set the bus high.
*
* \param[in] sdaPin The software SDA pin number.
*
* \param[in] sclPin The software SCL pin number.
*
* \param[in] enablePullup Enable pullup on DSA during read.
*/
SoftI2cMaster::SoftI2cMaster(uint8_t sdaPin, uint8_t sclPin,
bool enablePullup) {
sdaPin_ = sdaPin;
pinMode(sdaPin_, OUTPUT);
digitalWrite(sdaPin_, HIGH);
sclPin_ = sclPin;
pinMode(sclPin_, OUTPUT);
digitalWrite(sclPin_, HIGH);
}
//------------------------------------------------------------------------------
/** Read a byte and send Ack if more reads follow else Nak to terminate read.
*
* \param[in] last Set true to terminate the read else false.
*
* \return The byte read from the I2C bus.
*/
uint8_t SoftI2cMaster::read(uint8_t last) {
uint8_t b = 0;
pinMode(sdaPin_, INPUT);
// make sure pull-up enabled
digitalWrite(sdaPin_, HIGH);
// read byte
for (uint8_t i = 0; i < 8; i++) {
// don't change this loop unless you verify the change with a scope
b <<= 1;
delayMicroseconds(I2C_DELAY_USEC);
digitalWrite(sclPin_, HIGH);
if (digitalRead(sdaPin_)) b |= 1;
digitalWrite(sclPin_, LOW);
}
// send Ack or Nak
pinMode(sdaPin_, OUTPUT);
digitalWrite(sdaPin_, last);
digitalWrite(sclPin_, HIGH);
delayMicroseconds(I2C_DELAY_USEC);
digitalWrite(sclPin_, LOW);
digitalWrite(sdaPin_, LOW);
return b;
}
//------------------------------------------------------------------------------
/** Issue a restart condition.
*
* \param[in] addressRW I2C address with read/write bit.
*
* \return The value true, 1, for success or false, 0, for failure.
*/
bool SoftI2cMaster::restart(uint8_t addressRW) {
digitalWrite(sdaPin_, HIGH);
digitalWrite(sclPin_, HIGH);
delayMicroseconds(I2C_DELAY_USEC);
return start(addressRW);
}
//------------------------------------------------------------------------------
/** Issue a start condition.
*
* \param[in] addressRW I2C address with read/write bit.
*
* \return The value true, 1, for success or false, 0, for failure.
*/
bool SoftI2cMaster::start(uint8_t addressRW) {
digitalWrite(sdaPin_, LOW);
delayMicroseconds(I2C_DELAY_USEC);
digitalWrite(sclPin_, LOW);
return write(addressRW);
}
//------------------------------------------------------------------------------
/** Issue a stop condition. */
void SoftI2cMaster::stop(void) {
digitalWrite(sdaPin_, LOW);
delayMicroseconds(I2C_DELAY_USEC);
digitalWrite(sclPin_, HIGH);
delayMicroseconds(I2C_DELAY_USEC);
digitalWrite(sdaPin_, HIGH);
delayMicroseconds(I2C_DELAY_USEC);
}
//------------------------------------------------------------------------------
/**
* Write a byte.
*
* \param[in] data The byte to send.
*
* \return The value true, 1, if the slave returned an Ack or false for Nak.
*/
bool SoftI2cMaster::write(uint8_t data) {
// write byte
for (uint8_t m = 0X80; m != 0; m >>= 1) {
// don't change this loop unless you verify the change with a scope
digitalWrite(sdaPin_, m & data);
digitalWrite(sclPin_, HIGH);
delayMicroseconds(I2C_DELAY_USEC);
digitalWrite(sclPin_, LOW);
}
// get Ack or Nak
pinMode(sdaPin_, INPUT);
// enable pullup
digitalWrite(sdaPin_, HIGH);
digitalWrite(sclPin_, HIGH);
uint8_t rtn = digitalRead(sdaPin_);
digitalWrite(sclPin_, LOW);
pinMode(sdaPin_, OUTPUT);
digitalWrite(sdaPin_, LOW);
return rtn == 0;
}
//==============================================================================
void TwiMaster::execCmd(uint8_t cmdReg) {
// send command
TWCR = cmdReg;
// wait for command to complete
while (!(TWCR & (1 << TWINT)));
// status bits.
status_ = TWSR & 0xF8;
}
//------------------------------------------------------------------------------
/**
* Initialize hardware TWI.
*
* \param[in] enablePullup Enable the AVR internal pull-ups. The internal
* pull-ups can, in some systems, eliminate the need for external pull-ups.
*/
TwiMaster::TwiMaster(bool enablePullup) {
// no prescaler
TWSR = 0;
// set bit rate factor
TWBR = (F_CPU/F_TWI - 16)/2;
// enable pull-ups if requested
if (enablePullup) {
digitalWrite(SDA, HIGH);
digitalWrite(SCL, HIGH);
}
}
//------------------------------------------------------------------------------
/** Read a byte and send Ack if more reads follow else Nak to terminate read.
*
* \param[in] last Set true to terminate the read else false.
*
* \return The byte read from the I2C bus.
*/
uint8_t TwiMaster::read(uint8_t last) {
execCmd((1 << TWINT) | (1 << TWEN) | (last ? 0 : (1 << TWEA)));
return TWDR;
}
//------------------------------------------------------------------------------
/** Issue a restart condition.
*
* \param[in] addressRW I2C address with read/write bit.
*
* \return The value true, 1, for success or false, 0, for failure.
*/
bool TwiMaster::restart(uint8_t addressRW) {
return start(addressRW);
}
//------------------------------------------------------------------------------
/** Set bus speed.
*
* \param[in] fast Set speed to 400 kHz if true else 100 kHz.
*/
void TwiMaster::speed(bool fast) {
TWBR = fast ? (F_CPU/400000 -16)/2 : (F_CPU/100000 -16)/2;
}
//------------------------------------------------------------------------------
/** Issue a start condition.
*
* \param[in] addressRW I2C address with read/write bit.
*
* \return The value true for success or false for failure.
*/
bool TwiMaster::start(uint8_t addressRW) {
// send START condition
execCmd((1<<TWINT) | (1<<TWSTA) | (1<<TWEN));
if (status() != TWSR_START && status() != TWSR_REP_START) return false;
// send device address and direction
TWDR = addressRW;
execCmd((1 << TWINT) | (1 << TWEN));
if (addressRW & I2C_READ) {
return status() == TWSR_MRX_ADR_ACK;
} else {
return status() == TWSR_MTX_ADR_ACK;
}
}
//------------------------------------------------------------------------------
/** Issue a stop condition. */
void TwiMaster::stop(void) {
TWCR = (1 << TWINT) | (1 << TWEN) | (1 << TWSTO);
// wait until stop condition is executed and bus released
while (TWCR & (1 << TWSTO));
}
//------------------------------------------------------------------------------
/**
* Write a byte.
*
* \param[in] data The byte to send.
*
* \return The value true, 1, if the slave returned an Ack or false for Nak.
*/
bool TwiMaster::write(uint8_t data) {
TWDR = data;
execCmd((1 << TWINT) | (1 << TWEN));
return status() == TWSR_MTX_DATA_ACK;
}

View file

@ -0,0 +1,256 @@
/* Arduino I2cMaster Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino I2cMaster Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino I2cMaster Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef I2C_MASTER_H
#define I2C_MASTER_H
/**
* \file
* \brief Software I2C and hardware TWI library
*/
#if ARDUINO < 100
#error Requires Arduino 1.0 or greater.
#else // ARDUINO
#include <Arduino.h>
#endif // ARDUINO
//------------------------------------------------------------------------------
/** I2cMaster version YYYYMMDD */
#define I2C_MASTER_VERSION 20120716
//------------------------------------------------------------------------------
/** Default hardware I2C clock in Hz */
uint32_t const F_TWI = 400000L;
/** Delay used for software I2C */
uint8_t const I2C_DELAY_USEC = 4;
/** Bit to or with address for read start and read restart */
uint8_t const I2C_READ = 1;
/** Bit to or with address for write start and write restart */
uint8_t const I2C_WRITE = 0;
//------------------------------------------------------------------------------
// Status codes in TWSR - names are from Atmel TWSR.h with TWSR_ added
/** start condition transmitted */
uint8_t const TWSR_START = 0x08;
/** repeated start condition transmitted */
uint8_t const TWSR_REP_START = 0x10;
/** slave address plus write bit transmitted, ACK received */
uint8_t const TWSR_MTX_ADR_ACK = 0x18;
/** data transmitted, ACK received */
uint8_t const TWSR_MTX_DATA_ACK = 0x28;
/** slave address plus read bit transmitted, ACK received */
uint8_t const TWSR_MRX_ADR_ACK = 0x40;
//==============================================================================
/**
* \class I2cMasterBase
* \brief Base class for FastI2cMaster, SoftI2cMaster, and TwiMaster
*/
class I2cMasterBase {
public:
/** Read a byte
* \param[in] last send Ack if last is false else Nak to terminate read
* \return byte read from I2C bus
*/
virtual uint8_t read(uint8_t last) = 0;
/** Send new address and read/write bit without sending a stop.
* \param[in] addressRW i2c address with read/write bit
* \return true for success false for failure
*/
virtual bool restart(uint8_t addressRW) = 0;
/** Issue a start condition
* \param[in] addressRW i2c address with read/write bit
* \return true for success false for failure
*/
virtual bool start(uint8_t addressRW) = 0;
/** Issue a stop condition. */
virtual void stop(void) = 0;
/** Write a byte
* \param[in] data byte to write
* \return true for Ack or false for Nak */
virtual bool write(uint8_t data) = 0;
};
//==============================================================================
/**
* \class SoftI2cMaster
* \brief Software I2C master class
*/
class SoftI2cMaster : public I2cMasterBase {
public:
SoftI2cMaster(uint8_t sdaPin, uint8_t sclPin, bool enablePullup = true);
uint8_t read(uint8_t last);
bool restart(uint8_t addressRW);
bool start(uint8_t addressRW);
void stop(void);
bool write(uint8_t b);
private:
SoftI2cMaster() {}
bool enablePullup_;
uint8_t sdaPin_;
uint8_t sclPin_;
};
//==============================================================================
/**
* \class TwiMaster
* \brief Hardware I2C master class
*
* Uses ATmega TWI hardware port
*/
class TwiMaster : public I2cMasterBase {
public:
explicit TwiMaster(bool enablePullup);
uint8_t read(uint8_t last);
bool restart(uint8_t addressRW);
void speed(bool fast);
bool start(uint8_t addressRW);
/** \return status from last TWI command - useful for library debug */
uint8_t status(void) {return status_;}
void stop(void);
bool write(uint8_t data);
private:
TwiMaster() {}
uint8_t status_;
void execCmd(uint8_t cmdReg);
};
//==============================================================================
// experimental template based fast software I2C
#ifndef USE_FAST_I2C_MASTER
/** disable experimental fast software I2C */
#define USE_FAST_I2C_MASTER 0
#endif // USE_FAST_I2C_MASTER
#if USE_FAST_I2C_MASTER || DOXYGEN
#include <util/delay_basic.h>
#include <DigitalPin.h>
//------------------------------------------------------------------------------
/**
* \class FastI2cMaster
* \brief Fast software I2C master class
*/
template<uint8_t sdaPin, uint8_t sclPin, bool enablePullups = true>
class FastI2cMaster : public I2cMasterBase {
public:
FastI2cMaster() {
fastPinMode(sdaPin, OUTPUT);
fastDigitalWrite(sdaPin, HIGH);
fastPinMode(sclPin, OUTPUT);
fastDigitalWrite(sclPin, HIGH);
}
//----------------------------------------------------------------------------
uint8_t read(uint8_t last) {
uint8_t data = 0;
// make sure pull-up enabled
fastPinMode(sdaPin, INPUT);
fastDigitalWrite(sdaPin, enablePullups);
readBit(7, &data);
readBit(6, &data);
readBit(5, &data);
readBit(4, &data);
readBit(3, &data);
readBit(2, &data);
readBit(1, &data);
readBit(0, &data);
// send Ack or Nak
fastPinMode(sdaPin, OUTPUT);
fastDigitalWrite(sdaPin, last);
fastDigitalWrite(sclPin, HIGH);
sclDelay(3);
fastDigitalWrite(sclPin, LOW);
fastDigitalWrite(sdaPin, LOW);
return data;
}
//----------------------------------------------------------------------------
bool restart(uint8_t addressRW) {
fastDigitalWrite(sdaPin, HIGH);
sclDelay(8);
fastDigitalWrite(sclPin, HIGH);
sclDelay(8);
return start(addressRW);
}
//----------------------------------------------------------------------------
bool start(uint8_t addressRW) {
fastDigitalWrite(sdaPin, LOW);
sclDelay(8);
fastDigitalWrite(sclPin, LOW);
sclDelay(8);
return write(addressRW);
}
//----------------------------------------------------------------------------
void stop(void) {
fastDigitalWrite(sdaPin, LOW);
sclDelay(8);
fastDigitalWrite(sclPin, HIGH);
sclDelay(8);
fastDigitalWrite(sdaPin, HIGH);
sclDelay(8);
}
//----------------------------------------------------------------------------
bool write(uint8_t data) {
// write byte
writeBit(7, data);
writeBit(6, data);
writeBit(5, data);
writeBit(4, data);
writeBit(3, data);
writeBit(2, data);
writeBit(1, data);
writeBit(0, data);
// get Ack or Nak
fastPinMode(sdaPin, INPUT);
// enable pullup
fastDigitalWrite(sdaPin, HIGH);
fastDigitalWrite(sclPin, HIGH);
sclDelay(3);
uint8_t rtn = fastDigitalRead(sdaPin);
fastDigitalWrite(sclPin, LOW);
fastPinMode(sdaPin, OUTPUT);
fastDigitalWrite(sdaPin, LOW);
return rtn == 0;
}
//----------------------------------------------------------------------------
private:
inline __attribute__((always_inline))
void readBit(uint8_t bit, uint8_t* data) {
fastDigitalWrite(sclPin, HIGH);
sclDelay(3);
if (fastDigitalRead(sdaPin)) *data |= 1 << bit;
fastDigitalWrite(sclPin, LOW);
sclDelay(7);
}
//----------------------------------------------------------------------------
void sclDelay(uint8_t n) {
_delay_loop_1(n);
}
//----------------------------------------------------------------------------
inline __attribute__((always_inline))
void writeBit(uint8_t bit, uint8_t data) {
fastDigitalWrite(sdaPin, data & (1 << bit));
fastDigitalWrite(sclPin, HIGH);
sclDelay(4);
fastDigitalWrite(sclPin, LOW);
sclDelay(6);
}
};
#endif // USE_FAST_I2C_MASTER
#endif // I2C_MASTER_H

View file

@ -0,0 +1,53 @@
// Warning only use this for hardware debug!
// See which addresses respond to a start condition.
#include <I2cMaster.h>
// select software or hardware i2c
#define USE_SOFT_I2C 0
#if USE_SOFT_I2C
// use analog pins 4 and 5 for this example
// this allows a 328 shield to be used on the Mega
// edit next two line to change pins
const uint8_t SDA_PIN = A4;
const uint8_t SCL_PIN = A5;
// An instance of class for software master
SoftI2cMaster i2c(SDA_PIN, SCL_PIN);
#else // USE_SOFT_I2C
// hardware master with pullups enabled
TwiMaster i2c(true);
#endif // USE_SOFT_I2C
//------------------------------------------------------------------------------
void setup(void) {
Serial.begin(9600);
uint8_t add = 0;
// try read
do {
if (i2c.start(add | I2C_READ)) {
Serial.print("Add read: 0X");
Serial.println(add, HEX);
i2c.read(true);
}
i2c.stop();
add += 2;
} while (add);
// try write
add = 0;
do {
if (i2c.start(add | I2C_WRITE)) {
Serial.print("Add write: 0X");
Serial.println(add, HEX);
}
i2c.stop();
add += 2;
} while (add);
Serial.println("Done");
}
void loop(void){}

View file

@ -0,0 +1,53 @@
// this sketch is for tweaking soft i2c signals
// Uncomment next two lines to test fast software I2C
// #include <DigitalPin.h>
// #define USE_FAST_I2C_MASTER 1
#include <I2cMaster.h>
const uint8_t sdaPin = 8;
const uint8_t sclPin = 7;
#if USE_FAST_I2C_MASTER
FastI2cMaster<sdaPin, sclPin, false> i2c;
#else // USE_FAST_I2C_MASTER
SoftI2cMaster i2c(sdaPin, sclPin);
#endif
// also test base class idea
I2cMasterBase *bus;
uint8_t mode;
//------------------------------------------------------------------------------
void setup(void) {
Serial.begin(9600);
// convert softI2cMaster to TwoWireBase to test base class idea
bus = &i2c;
Serial.println("enter 0 for write, 1 for read, 2 for start/stop");
while (!Serial.available());
mode = Serial.read();
if (mode == '0') {
Serial.println("Write Mode");
} else if (mode == '1') {
Serial.println("Read Mode");
} else if (mode == '2' ) {
Serial.println("Start/Stop");
} else {
Serial.println("Bad Option");
while(1);
}
}
//------------------------------------------------------------------------------
void loop(void) {
if (mode == '0') {
bus->write(0X55);
} else if (mode == '1') {
bus->read(0);
} else {
bus->start(0XAA);
bus->stop();
}
delay(1);
}

View file

@ -0,0 +1,321 @@
// Utility sketch to explore DS1307 and
// demonstrate SoftI2cMaster and TwiMaster
//
#include <avr/pgmspace.h>
#include <I2cMaster.h>
// select software or hardware i2c
#define USE_SOFT_I2C 1
#if USE_SOFT_I2C
// use analog pins 4 and 5 for this example
// this allows a 328 shield to be used on the Mega
// edit next two line to change pins
const uint8_t SDA_PIN = A4;
const uint8_t SCL_PIN = A5;
// An instance of class for software master
SoftI2cMaster rtc(SDA_PIN, SCL_PIN);
#else // USE_SOFT_I2C
// Pins for DS1307 with hardware i2c
// connect SCL to Arduino 168/328 analog pin 5
// connect SDA to Arduino 168/328 analog pin 4
// Instance of class for hardware master with pullups enabled
TwiMaster rtc(true);
#endif // USE_SOFT_I2C
// i2c 8-bit address for DS1307. low bit is read/write
#define DS1307ADDR 0XD0
//------------------------------------------------------------------------------
/*
* Read 'count' bytes from the DS1307 starting at 'address'
*/
uint8_t readDS1307(uint8_t address, uint8_t *buf, uint8_t count) {
// issue a start condition, send device address and write direction bit
if (!rtc.start(DS1307ADDR | I2C_WRITE)) return false;
// send the DS1307 address
if (!rtc.write(address)) return false;
// issue a repeated start condition, send device address and read direction bit
if (!rtc.restart(DS1307ADDR | I2C_READ))return false;
// read data from the DS1307
for (uint8_t i = 0; i < count; i++) {
// send Ack until last byte then send Ack
buf[i] = rtc.read(i == (count-1));
}
// issue a stop condition
rtc.stop();
return true;
}
//------------------------------------------------------------------------------
/*
* write 'count' bytes to DS1307 starting at 'address'
*/
uint8_t writeDS1307(uint8_t address, uint8_t *buf, uint8_t count) {
// issue a start condition, send device address and write direction bit
if (!rtc.start(DS1307ADDR | I2C_WRITE)) return false;
// send the DS1307 address
if (!rtc.write(address)) return false;
// send data to the DS1307
for (uint8_t i = 0; i < count; i++) {
if (!rtc.write(buf[i])) return false;
}
// issue a stop condition
rtc.stop();
return true;
}
//------------------------------------------------------------------------------
void setup(void) {
Serial.begin(9600);
}
//------------------------------------------------------------------------------
/** Store and print a string in flash memory.*/
#define PgmPrint(x) Serial.print(F(x))
/** Store and print a string in flash memory followed by a CR/LF.*/
#define PgmPrintln(x) Serial.println(F(x))
//-------------------------------------------------------------------------------
// day of week U.S. convention
char *Ddd[] = {"Bad", "Sun", "Mon", "Tue", "Wed", "Thu", "Fri", "Sat"};
//------------------------------------------------------------------------------
void hexPrint(uint8_t v) {
Serial.print(v >> 4, HEX);
Serial.print(v & 0XF, HEX);
}
//------------------------------------------------------------------------------
void hexPrintln(uint8_t v) {
hexPrint(v);
Serial.println();
}
//------------------------------------------------------------------------------
// read hex input
uint8_t hexRead(uint16_t* v) {
uint16_t n = 0;
while (!Serial.available());
while (Serial.available()) {
uint8_t c = Serial.read();
// exit if end-of-line
if (c == '\n' || c == '\r') break;
n <<= 4;
if ('a' <= c && c <= 'f') {
n += c - ('a' - 10);
}
else if ('A' <= c && c <= 'F') {
n += c - ('A' - 10);
}
else if ('0' <= c && c <= '9') {
n += c - '0';
}
else {
PgmPrintln("Invalid entry");
return false;
}
delay(10);
}
*v = n;
return true;
}
//------------------------------------------------------------------------------
uint8_t bcdRead(uint8_t min, uint8_t max, uint8_t* n) {
uint16_t v;
if (!hexRead(&v)) return false;
uint8_t d = 10 * (v >> 4) + (v & 0XF);
if ((v >> 4) > 9 || (v & 0XF) > 9 || d < min || d > max) {
PgmPrintln("Invalid");
return false;
}
*n = v;
return true;
}
//------------------------------------------------------------------------------
void displayTime(void) {
uint8_t r[8];
if (!readDS1307(0, r, 8)) {
PgmPrintln("Read Failed for display time");
return;
}
PgmPrint("The current time is 20");
// year
hexPrint(r[6]);
Serial.write('-');
// month
hexPrint(r[5]);
Serial.write('-');
// day
hexPrint(r[4]);
Serial.write(' ');
Serial.print(Ddd[r[3] < 8 ? r[3] : 0]);
Serial.write(' ');
// hour
hexPrint(r[2]);
Serial.write(':');
// minute
hexPrint(r[1]);
Serial.write(':');
// second
hexPrintln(r[0]);
PgmPrint("Control: ");
hexPrintln(r[7]);
}
//------------------------------------------------------------------------------
// dump registers and 56 bytes of RAM
void dumpAll(void) {
uint8_t buf[8];
for (uint8_t a = 0; a < 64; a += 8) {
hexPrint(a);
Serial.write(' ');
if (!readDS1307(a, buf, 8)) {
PgmPrint("read failed for dumpAll");
return;
}
for (uint8_t i = 0; i < 8; i++) {
Serial.write(' ');
hexPrint(buf[i]);
}
Serial.println();
}
}
//------------------------------------------------------------------------------
// set control register
/*
The DS1307 control register is used to control the operation of the SQW/OUT pin.
+-----------------------------------------------+
|BIT 7|BIT 6|BIT 5|BIT 4|BIT 3|BIT 2|BIT 1|BIT 0|
+-----------------------------------------------+
|OUT | 0 | 0 |SQWE | 0 | 0 | RS1 | RS0 |
+-----------------------------------------------+
OUT (Output control): This bit controls the output level of the SQW/OUT pin
when the square wave output is disabled. If SQWE = 0, the logic level on the
SQW/OUT pin is 1 if OUT = 1 and is 0 if OUT = 0.
SQWE (Square Wave Enable): This bit, when set to a logic 1, will enable the
oscillator output. The frequency of the square wave output depends upon the
value of the RS0 and RS1 bits. With the square wave output set to 1Hz, the
clock registers update on the falling edge of the square wave.
Square wave Output Frequency for SQWE = 1.
RS1 RS0 FREQUENCY
0 0 1Hz
0 1 4.096kHz
1 0 8.192kHz
1 1 32.768kHz
*/
void setControl(void) {
PgmPrintln("SQW/OUT pin: ");
PgmPrintln("(00) Low");
PgmPrintln("(10) 1Hz");
PgmPrintln("(11) 4.096kHz");
PgmPrintln("(12) 8.192kHz");
PgmPrintln("(13) 32.768kHz");
PgmPrintln("(80) High");
PgmPrint("Enter control: ");
uint16_t r;
if (!hexRead(&r)) return;
hexPrintln(r);
if (!writeDS1307(7, (uint8_t *)&r, 1)) {
PgmPrint("Write Failed for setControl");
}
}
//------------------------------------------------------------------------------
void setDate(void) {
uint8_t r[4];
PgmPrint("Enter year (00-99): ");
if (!bcdRead(0, 99, &r[3])) return;
hexPrintln(r[3]);
PgmPrint("Enter month (01-12): ");
if (!bcdRead(1, 12, &r[2])) return;
hexPrintln(r[2]);
PgmPrint("Enter day (01-31): ");
if (!bcdRead(1, 31, &r[1])) return;
hexPrintln(r[1]);
PgmPrint("Enter day of week (01-07): ");
if (!bcdRead(1, 7, &r[0])) return;
hexPrintln(r[0]);
if (!writeDS1307(3, r, 4)) {
PgmPrintln("Write failed for setDate");
}
}
//------------------------------------------------------------------------------
void setNvRam(void) {
uint8_t buf[8];
PgmPrint("Enter HEX value for all NV RAM locations (00-FF): ");
uint16_t v;
if (!hexRead(&v)) return;
hexPrint(v);
for (uint8_t a = 8; a < 64; a ++) {
if (!writeDS1307(a, (uint8_t *)&v, 1)) {
PgmPrintln("write failed for setNvRam");
}
}
}
//------------------------------------------------------------------------------
void setTime(void) {
uint8_t r[3];
PgmPrint("Enter hours (00-23): ");
if (!bcdRead(0, 23, &r[2])) return;
hexPrintln(r[2]);
PgmPrint("Enter minutes (00-59): ");
if (!bcdRead(0, 59, &r[1])) return;
hexPrintln(r[1]);
PgmPrint("Enter seconds (00-59): ");
if (!bcdRead(0, 59, &r[0])) return;
hexPrintln(r[0]);
if (!writeDS1307(0, r, 3)) {
PgmPrintln("write failed in setTime");
return;
}
}
//------------------------------------------------------------------------------
void loop(void) {
Serial.println();
displayTime();
while (Serial.read() >= 0) {}
PgmPrintln("\nOptions are:");
PgmPrintln("(0) Display date and time");
PgmPrintln("(1) Set time");
PgmPrintln("(2) Set date");
PgmPrintln("(3) Set Control");
PgmPrintln("(4) Dump all");
PgmPrintln("(5) Set NV RAM");
PgmPrint("Enter option: ");
uint16_t n;
if (!hexRead(&n)) return;
Serial.println(n, DEC);
if (n == 0) return;
Serial.println();
if (n == 1) {
setTime();
}
else if (n == 2) {
setDate();
}
else if (n == 3) {
setControl();
}
else if (n == 4) {
dumpAll();
}
else if (n == 5) {
setNvRam();
}
else {
PgmPrintln("Invalid option");
}
}

View file

@ -0,0 +1,119 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef ArduinoStream_h
#define ArduinoStream_h
/**
* \file
* \brief ArduinoInStream and ArduinoOutStream classes
*/
#include <bufstream.h>
//==============================================================================
/**
* \class ArduinoInStream
* \brief Input stream for Arduino Stream objects
*/
class ArduinoInStream : public ibufstream {
public:
/**
* Constructor
* \param[in] hws hardware stream
* \param[in] buf buffer for input line
* \param[in] size size of input buffer
*/
ArduinoInStream(Stream &hws, char* buf, size_t size) {
hw_ = &hws;
line_ = buf;
size_ = size;
}
/** read a line. */
void readline() {
size_t i = 0;
uint32_t t;
line_[0] = '\0';
while (!hw_->available());
while (1) {
t = millis();
while (!hw_->available()) {
if ((millis() - t) > 10) goto done;
}
if (i >= (size_ - 1)) {
setstate(failbit);
return;
}
line_[i++] = hw_->read();
line_[i] = '\0';
}
done:
init(line_);
}
protected:
/** Internal - do not use.
* \param[in] off
* \param[in] way
* \return true/false.
*/
bool seekoff(off_type off, seekdir way) {return false;}
/** Internal - do not use.
* \param[in] pos
* \return true/false.
*/
bool seekpos(pos_type pos) {return false;}
private:
char *line_;
size_t size_;
Stream* hw_;
};
//==============================================================================
/**
* \class ArduinoOutStream
* \brief Output stream for Arduino Print objects
*/
class ArduinoOutStream : public ostream {
public:
/** constructor
*
* \param[in] pr Print object for this ArduinoOutStream.
*/
explicit ArduinoOutStream(Print& pr) : pr_(&pr) {}
protected:
/// @cond SHOW_PROTECTED
/**
* Internal do not use
* \param[in] c
*/
void putch(char c) {
if (c == '\n') pr_->write('\r');
pr_->write(c);
}
void putstr(const char* str) {pr_->write(str);}
bool seekoff(off_type off, seekdir way) {return false;}
bool seekpos(pos_type pos) {return false;}
bool sync() {return true;}
pos_type tellpos() {return 0;}
/// @endcond
private:
ArduinoOutStream() {}
Print* pr_;
};
#endif // ArduinoStream_h

View file

@ -0,0 +1,71 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#include <Arduino.h>
#if defined(UDR0) || defined(DOXYGEN)
#include <MinimumSerial.h>
//------------------------------------------------------------------------------
/**
* Set baud rate for serial port zero and enable in non interrupt mode.
* Do not call this function if you use another serial library.
* \param[in] baud rate
*/
void MinimumSerial::begin(unsigned long baud) {
uint16_t baud_setting;
// don't worry, the compiler will squeeze out F_CPU != 16000000UL
if (F_CPU != 16000000UL || baud != 57600) {
// Double the USART Transmission Speed
UCSR0A = 1 << U2X0;
baud_setting = (F_CPU / 4 / baud - 1) / 2;
} else {
// hardcoded exception for compatibility with the bootloader shipped
// with the Duemilanove and previous boards and the firmware on the 8U2
// on the Uno and Mega 2560.
UCSR0A = 0;
baud_setting = (F_CPU / 8 / baud - 1) / 2;
}
// assign the baud_setting
UBRR0H = baud_setting >> 8;
UBRR0L = baud_setting;
// enable transmit and receive
UCSR0B |= (1 << TXEN0) | (1 << RXEN0) ;
}
//------------------------------------------------------------------------------
/**
* Unbuffered read
* \return -1 if no character is available or an available character.
*/
int MinimumSerial::read() {
if (UCSR0A & (1 << RXC0)) return UDR0;
return -1;
}
//------------------------------------------------------------------------------
/**
* Unbuffered write
*
* \param[in] b byte to write.
* \return 1
*/
size_t MinimumSerial::write(uint8_t b) {
while (((1 << UDRIE0) & UCSR0B) || !(UCSR0A & (1 << UDRE0))) {}
UDR0 = b;
return 1;
}
MinimumSerial MiniSerial;
#endif // defined(UDR0) || defined(DOXYGEN)

View file

@ -0,0 +1,36 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef MinimumSerial_h
#define MinimumSerial_h
/**
* \class MinimumSerial
* \brief mini serial class for the %SdFat library.
*/
class MinimumSerial : public Print {
public:
void begin(unsigned long);
int read();
size_t write(uint8_t b);
using Print::write;
};
#ifdef UDR0
extern MinimumSerial MiniSerial;
#endif // UDR0
#endif // MinimumSerial_h

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,233 @@
/* Arduino Sd2Card Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino Sd2Card Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino Sd2Card Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef Sd2Card_h
#define Sd2Card_h
/**
* \file
* \brief Sd2Card class for V2 SD/SDHC cards
*/
#include <Arduino.h>
#include <SdFatConfig.h>
#include <SdInfo.h>
//------------------------------------------------------------------------------
// SPI speed is F_CPU/2^(1 + index), 0 <= index <= 6
/** Set SCK to max rate of F_CPU/2. See Sd2Card::setSckRate(). */
uint8_t const SPI_FULL_SPEED = 0;
/** Set SCK rate to F_CPU/3 for Due */
uint8_t const SPI_DIV3_SPEED = 1;
/** Set SCK rate to F_CPU/4. See Sd2Card::setSckRate(). */
uint8_t const SPI_HALF_SPEED = 2;
/** Set SCK rate to F_CPU/6 for Due */
uint8_t const SPI_DIV6_SPEED = 3;
/** Set SCK rate to F_CPU/8. See Sd2Card::setSckRate(). */
uint8_t const SPI_QUARTER_SPEED = 4;
/** Set SCK rate to F_CPU/16. See Sd2Card::setSckRate(). */
uint8_t const SPI_EIGHTH_SPEED = 6;
/** Set SCK rate to F_CPU/32. See Sd2Card::setSckRate(). */
uint8_t const SPI_SIXTEENTH_SPEED = 8;
/** MAX rate test - see spiInit for a given chip for details */
const uint8_t MAX_SCK_RATE_ID = 14;
//------------------------------------------------------------------------------
/** init timeout ms */
uint16_t const SD_INIT_TIMEOUT = 2000;
/** erase timeout ms */
uint16_t const SD_ERASE_TIMEOUT = 10000;
/** read timeout ms */
uint16_t const SD_READ_TIMEOUT = 300;
/** write time out ms */
uint16_t const SD_WRITE_TIMEOUT = 600;
//------------------------------------------------------------------------------
// SD card errors
/** timeout error for command CMD0 (initialize card in SPI mode) */
uint8_t const SD_CARD_ERROR_CMD0 = 0X1;
/** CMD8 was not accepted - not a valid SD card*/
uint8_t const SD_CARD_ERROR_CMD8 = 0X2;
/** card returned an error response for CMD12 (write stop) */
uint8_t const SD_CARD_ERROR_CMD12 = 0X3;
/** card returned an error response for CMD17 (read block) */
uint8_t const SD_CARD_ERROR_CMD17 = 0X4;
/** card returned an error response for CMD18 (read multiple block) */
uint8_t const SD_CARD_ERROR_CMD18 = 0X5;
/** card returned an error response for CMD24 (write block) */
uint8_t const SD_CARD_ERROR_CMD24 = 0X6;
/** WRITE_MULTIPLE_BLOCKS command failed */
uint8_t const SD_CARD_ERROR_CMD25 = 0X7;
/** card returned an error response for CMD58 (read OCR) */
uint8_t const SD_CARD_ERROR_CMD58 = 0X8;
/** SET_WR_BLK_ERASE_COUNT failed */
uint8_t const SD_CARD_ERROR_ACMD23 = 0X9;
/** ACMD41 initialization process timeout */
uint8_t const SD_CARD_ERROR_ACMD41 = 0XA;
/** card returned a bad CSR version field */
uint8_t const SD_CARD_ERROR_BAD_CSD = 0XB;
/** erase block group command failed */
uint8_t const SD_CARD_ERROR_ERASE = 0XC;
/** card not capable of single block erase */
uint8_t const SD_CARD_ERROR_ERASE_SINGLE_BLOCK = 0XD;
/** Erase sequence timed out */
uint8_t const SD_CARD_ERROR_ERASE_TIMEOUT = 0XE;
/** card returned an error token instead of read data */
uint8_t const SD_CARD_ERROR_READ = 0XF;
/** read CID or CSD failed */
uint8_t const SD_CARD_ERROR_READ_REG = 0X10;
/** timeout while waiting for start of read data */
uint8_t const SD_CARD_ERROR_READ_TIMEOUT = 0X11;
/** card did not accept STOP_TRAN_TOKEN */
uint8_t const SD_CARD_ERROR_STOP_TRAN = 0X12;
/** card returned an error token as a response to a write operation */
uint8_t const SD_CARD_ERROR_WRITE = 0X13;
/** attempt to write protected block zero */
uint8_t const SD_CARD_ERROR_WRITE_BLOCK_ZERO = 0X14; // REMOVE - not used
/** card did not go ready for a multiple block write */
uint8_t const SD_CARD_ERROR_WRITE_MULTIPLE = 0X15;
/** card returned an error to a CMD13 status check after a write */
uint8_t const SD_CARD_ERROR_WRITE_PROGRAMMING = 0X16;
/** timeout occurred during write programming */
uint8_t const SD_CARD_ERROR_WRITE_TIMEOUT = 0X17;
/** incorrect rate selected */
uint8_t const SD_CARD_ERROR_SCK_RATE = 0X18;
/** init() not called */
uint8_t const SD_CARD_ERROR_INIT_NOT_CALLED = 0X19;
/** card returned an error for CMD59 (CRC_ON_OFF) */
uint8_t const SD_CARD_ERROR_CMD59 = 0X1A;
/** invalid read CRC */
uint8_t const SD_CARD_ERROR_READ_CRC = 0X1B;
/** SPI DMA error */
uint8_t const SD_CARD_ERROR_SPI_DMA = 0X1C;
//------------------------------------------------------------------------------
// card types
/** Standard capacity V1 SD card */
uint8_t const SD_CARD_TYPE_SD1 = 1;
/** Standard capacity V2 SD card */
uint8_t const SD_CARD_TYPE_SD2 = 2;
/** High Capacity SD card */
uint8_t const SD_CARD_TYPE_SDHC = 3;
/**
* define SOFTWARE_SPI to use bit-bang SPI
*/
//------------------------------------------------------------------------------
#if LEONARDO_SOFT_SPI && defined(__AVR_ATmega32U4__) && !defined(CORE_TEENSY)
#define SOFTWARE_SPI
#elif MEGA_SOFT_SPI&&(defined(__AVR_ATmega1280__)||defined(__AVR_ATmega2560__))
#define SOFTWARE_SPI
#elif USE_SOFTWARE_SPI
#define SOFTWARE_SPI
#endif // LEONARDO_SOFT_SPI
//------------------------------------------------------------------------------
// define default chip select pin
//
#ifndef SOFTWARE_SPI
// hardware pin defs
/** The default chip select pin for the SD card is SS. */
uint8_t const SD_CHIP_SELECT_PIN = SS;
#else // SOFTWARE_SPI
/** SPI chip select pin */
uint8_t const SD_CHIP_SELECT_PIN = SOFT_SPI_CS_PIN;
#endif // SOFTWARE_SPI
//------------------------------------------------------------------------------
/**
* \class Sd2Card
* \brief Raw access to SD and SDHC flash memory cards.
*/
class Sd2Card {
public:
/** Construct an instance of Sd2Card. */
Sd2Card() : errorCode_(SD_CARD_ERROR_INIT_NOT_CALLED), type_(0) {}
uint32_t cardSize();
bool erase(uint32_t firstBlock, uint32_t lastBlock);
bool eraseSingleBlockEnable();
/**
* Set SD error code.
* \param[in] code value for error code.
*/
void error(uint8_t code) {errorCode_ = code;}
/**
* \return error code for last error. See Sd2Card.h for a list of error codes.
*/
int errorCode() const {return errorCode_;}
/** \return error data for last error. */
int errorData() const {return status_;}
/**
* Initialize an SD flash memory card with default clock rate and chip
* select pin. See sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin).
*
* \return true for success or false for failure.
*/
bool init(uint8_t sckRateID = SPI_FULL_SPEED,
uint8_t chipSelectPin = SD_CHIP_SELECT_PIN);
bool readBlock(uint32_t block, uint8_t* dst);
/**
* Read a card's CID register. The CID contains card identification
* information such as Manufacturer ID, Product name, Product serial
* number and Manufacturing date.
*
* \param[out] cid pointer to area for returned data.
*
* \return true for success or false for failure.
*/
bool readCID(cid_t* cid) {
return readRegister(CMD10, cid);
}
/**
* Read a card's CSD register. The CSD contains Card-Specific Data that
* provides information regarding access to the card's contents.
*
* \param[out] csd pointer to area for returned data.
*
* \return true for success or false for failure.
*/
bool readCSD(csd_t* csd) {
return readRegister(CMD9, csd);
}
bool readData(uint8_t *dst);
bool readStart(uint32_t blockNumber);
bool readStop();
bool setSckRate(uint8_t sckRateID);
/** Return the card type: SD V1, SD V2 or SDHC
* \return 0 - SD V1, 1 - SD V2, or 3 - SDHC.
*/
int type() const {return type_;}
bool writeBlock(uint32_t blockNumber, const uint8_t* src);
bool writeData(const uint8_t* src);
bool writeStart(uint32_t blockNumber, uint32_t eraseCount);
bool writeStop();
private:
//----------------------------------------------------------------------------
uint8_t chipSelectPin_;
uint8_t errorCode_;
uint8_t spiRate_;
uint8_t status_;
uint8_t type_;
// private functions
uint8_t cardAcmd(uint8_t cmd, uint32_t arg) {
cardCommand(CMD55, 0);
return cardCommand(cmd, arg);
}
uint8_t cardCommand(uint8_t cmd, uint32_t arg);
bool readData(uint8_t* dst, size_t count);
bool readRegister(uint8_t cmd, void* buf);
void chipSelectHigh();
void chipSelectLow();
void type(uint8_t value) {type_ = value;}
bool waitNotBusy(uint16_t timeoutMillis);
bool writeData(uint8_t token, const uint8_t* src);
};
#endif // Sd2Card_h

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,560 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef SdBaseFile_h
#define SdBaseFile_h
/**
* \file
* \brief SdBaseFile class
*/
#ifdef __AVR__
#include <avr/pgmspace.h>
#else // __AVR__
#ifndef PGM_P
/** pointer to flash for ARM */
#define PGM_P const char*
#endif // PGM_P
#ifndef PSTR
/** store literal string in flash for ARM */
#define PSTR(x) (x)
#endif // PSTR
#ifndef pgm_read_byte
/** read 8-bits from flash for ARM */
#define pgm_read_byte(addr) (*(const unsigned char*)(addr))
#endif // pgm_read_byte
#ifndef pgm_read_word
/** read 16-bits from flash for ARM */
#define pgm_read_word(addr) (*(const uint16_t*)(addr))
#endif // pgm_read_word
#ifndef PROGMEM
/** store in flash for ARM */
#define PROGMEM const
#endif // PROGMEM
#endif // __AVR__
#include <Arduino.h>
#include <SdFatConfig.h>
#include <SdVolume.h>
//------------------------------------------------------------------------------
/**
* \struct FatPos_t
* \brief internal type for istream
* do not use in user apps
*/
struct FatPos_t {
/** stream position */
uint32_t position;
/** cluster for position */
uint32_t cluster;
FatPos_t() : position(0), cluster(0) {}
};
// use the gnu style oflag in open()
/** open() oflag for reading */
uint8_t const O_READ = 0X01;
/** open() oflag - same as O_IN */
uint8_t const O_RDONLY = O_READ;
/** open() oflag for write */
uint8_t const O_WRITE = 0X02;
/** open() oflag - same as O_WRITE */
uint8_t const O_WRONLY = O_WRITE;
/** open() oflag for reading and writing */
uint8_t const O_RDWR = (O_READ | O_WRITE);
/** open() oflag mask for access modes */
uint8_t const O_ACCMODE = (O_READ | O_WRITE);
/** The file offset shall be set to the end of the file prior to each write. */
uint8_t const O_APPEND = 0X04;
/** synchronous writes - call sync() after each write */
uint8_t const O_SYNC = 0X08;
/** truncate the file to zero length */
uint8_t const O_TRUNC = 0X10;
/** set the initial position at the end of the file */
uint8_t const O_AT_END = 0X20;
/** create the file if nonexistent */
uint8_t const O_CREAT = 0X40;
/** If O_CREAT and O_EXCL are set, open() shall fail if the file exists */
uint8_t const O_EXCL = 0X80;
// SdBaseFile class static and const definitions
// flags for ls()
/** ls() flag to print modify date */
uint8_t const LS_DATE = 1;
/** ls() flag to print file size */
uint8_t const LS_SIZE = 2;
/** ls() flag for recursive list of subdirectories */
uint8_t const LS_R = 4;
// flags for timestamp
/** set the file's last access date */
uint8_t const T_ACCESS = 1;
/** set the file's creation date and time */
uint8_t const T_CREATE = 2;
/** Set the file's write date and time */
uint8_t const T_WRITE = 4;
// values for type_
/** This file has not been opened. */
uint8_t const FAT_FILE_TYPE_CLOSED = 0;
/** A normal file */
uint8_t const FAT_FILE_TYPE_NORMAL = 1;
/** A FAT12 or FAT16 root directory */
uint8_t const FAT_FILE_TYPE_ROOT_FIXED = 2;
/** A FAT32 root directory */
uint8_t const FAT_FILE_TYPE_ROOT32 = 3;
/** A subdirectory file*/
uint8_t const FAT_FILE_TYPE_SUBDIR = 4;
/** Test value for directory type */
uint8_t const FAT_FILE_TYPE_MIN_DIR = FAT_FILE_TYPE_ROOT_FIXED;
/** date field for FAT directory entry
* \param[in] year [1980,2107]
* \param[in] month [1,12]
* \param[in] day [1,31]
*
* \return Packed date for dir_t entry.
*/
static inline uint16_t FAT_DATE(uint16_t year, uint8_t month, uint8_t day) {
return (year - 1980) << 9 | month << 5 | day;
}
/** year part of FAT directory date field
* \param[in] fatDate Date in packed dir format.
*
* \return Extracted year [1980,2107]
*/
static inline uint16_t FAT_YEAR(uint16_t fatDate) {
return 1980 + (fatDate >> 9);
}
/** month part of FAT directory date field
* \param[in] fatDate Date in packed dir format.
*
* \return Extracted month [1,12]
*/
static inline uint8_t FAT_MONTH(uint16_t fatDate) {
return (fatDate >> 5) & 0XF;
}
/** day part of FAT directory date field
* \param[in] fatDate Date in packed dir format.
*
* \return Extracted day [1,31]
*/
static inline uint8_t FAT_DAY(uint16_t fatDate) {
return fatDate & 0X1F;
}
/** time field for FAT directory entry
* \param[in] hour [0,23]
* \param[in] minute [0,59]
* \param[in] second [0,59]
*
* \return Packed time for dir_t entry.
*/
static inline uint16_t FAT_TIME(uint8_t hour, uint8_t minute, uint8_t second) {
return hour << 11 | minute << 5 | second >> 1;
}
/** hour part of FAT directory time field
* \param[in] fatTime Time in packed dir format.
*
* \return Extracted hour [0,23]
*/
static inline uint8_t FAT_HOUR(uint16_t fatTime) {
return fatTime >> 11;
}
/** minute part of FAT directory time field
* \param[in] fatTime Time in packed dir format.
*
* \return Extracted minute [0,59]
*/
static inline uint8_t FAT_MINUTE(uint16_t fatTime) {
return(fatTime >> 5) & 0X3F;
}
/** second part of FAT directory time field
* Note second/2 is stored in packed time.
*
* \param[in] fatTime Time in packed dir format.
*
* \return Extracted second [0,58]
*/
static inline uint8_t FAT_SECOND(uint16_t fatTime) {
return 2*(fatTime & 0X1F);
}
/** Default date for file timestamps is 1 Jan 2000 */
uint16_t const FAT_DEFAULT_DATE = ((2000 - 1980) << 9) | (1 << 5) | 1;
/** Default time for file timestamp is 1 am */
uint16_t const FAT_DEFAULT_TIME = (1 << 11);
//------------------------------------------------------------------------------
/**
* \class SdBaseFile
* \brief Base class for SdFile with Print and C++ streams.
*/
class SdBaseFile {
public:
/** Create an instance. */
SdBaseFile() : writeError(false), type_(FAT_FILE_TYPE_CLOSED) {}
SdBaseFile(const char* path, uint8_t oflag);
#if DESTRUCTOR_CLOSES_FILE
~SdBaseFile() {if(isOpen()) close();}
#endif // DESTRUCTOR_CLOSES_FILE
/**
* writeError is set to true if an error occurs during a write().
* Set writeError to false before calling print() and/or write() and check
* for true after calls to print() and/or write().
*/
bool writeError;
/** \return value of writeError */
bool getWriteError() {return writeError;}
/** Set writeError to zero */
void clearWriteError() {writeError = 0;}
//----------------------------------------------------------------------------
// helpers for stream classes
/** get position for streams
* \param[out] pos struct to receive position
*/
void getpos(FatPos_t* pos);
/** set position for streams
* \param[out] pos struct with value for new position
*/
void setpos(FatPos_t* pos);
//----------------------------------------------------------------------------
/** \return number of bytes available from yhe current position to EOF */
uint32_t available() {return fileSize() - curPosition();}
bool close();
bool contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock);
bool createContiguous(SdBaseFile* dirFile,
const char* path, uint32_t size);
/** \return The current cluster number for a file or directory. */
uint32_t curCluster() const {return curCluster_;}
/** \return The current position for a file or directory. */
uint32_t curPosition() const {return curPosition_;}
/** \return Current working directory */
static SdBaseFile* cwd() {return cwd_;}
/** Set the date/time callback function
*
* \param[in] dateTime The user's call back function. The callback
* function is of the form:
*
* \code
* void dateTime(uint16_t* date, uint16_t* time) {
* uint16_t year;
* uint8_t month, day, hour, minute, second;
*
* // User gets date and time from GPS or real-time clock here
*
* // return date using FAT_DATE macro to format fields
* *date = FAT_DATE(year, month, day);
*
* // return time using FAT_TIME macro to format fields
* *time = FAT_TIME(hour, minute, second);
* }
* \endcode
*
* Sets the function that is called when a file is created or when
* a file's directory entry is modified by sync(). All timestamps,
* access, creation, and modify, are set when a file is created.
* sync() maintains the last access date and last modify date/time.
*
* See the timestamp() function.
*/
static void dateTimeCallback(
void (*dateTime)(uint16_t* date, uint16_t* time)) {
dateTime_ = dateTime;
}
/** Cancel the date/time callback function. */
static void dateTimeCallbackCancel() {dateTime_ = 0;}
bool dirEntry(dir_t* dir);
static void dirName(const dir_t& dir, char* name);
bool exists(const char* name);
int16_t fgets(char* str, int16_t num, char* delim = 0);
/** \return The total number of bytes in a file or directory. */
uint32_t fileSize() const {return fileSize_;}
/** \return The first cluster number for a file or directory. */
uint32_t firstCluster() const {return firstCluster_;}
bool getFilename(char* name);
/** \return True if this is a directory else false. */
bool isDir() const {return type_ >= FAT_FILE_TYPE_MIN_DIR;}
/** \return True if this is a normal file else false. */
bool isFile() const {return type_ == FAT_FILE_TYPE_NORMAL;}
/** \return True if this is an open file/directory else false. */
bool isOpen() const {return type_ != FAT_FILE_TYPE_CLOSED;}
/** \return True if this is a subdirectory else false. */
bool isSubDir() const {return type_ == FAT_FILE_TYPE_SUBDIR;}
/** \return True if this is the root directory. */
bool isRoot() const {
return type_ == FAT_FILE_TYPE_ROOT_FIXED || type_ == FAT_FILE_TYPE_ROOT32;
}
void ls(Print* pr, uint8_t flags = 0, uint8_t indent = 0);
void ls(uint8_t flags = 0);
bool mkdir(SdBaseFile* dir, const char* path, bool pFlag = true);
// alias for backward compactability
bool makeDir(SdBaseFile* dir, const char* path) {
return mkdir(dir, path, false);
}
bool open(SdBaseFile* dirFile, uint16_t index, uint8_t oflag);
bool open(SdBaseFile* dirFile, const char* path, uint8_t oflag);
bool open(const char* path, uint8_t oflag = O_READ);
bool openNext(SdBaseFile* dirFile, uint8_t oflag);
bool openRoot(SdVolume* vol);
int peek();
bool printCreateDateTime(Print* pr);
static void printFatDate(uint16_t fatDate);
static void printFatDate(Print* pr, uint16_t fatDate);
static void printFatTime(uint16_t fatTime);
static void printFatTime(Print* pr, uint16_t fatTime);
bool printModifyDateTime(Print* pr);
bool printName();
bool printName(Print* pr);
int16_t read();
int read(void* buf, size_t nbyte);
int8_t readDir(dir_t* dir);
static bool remove(SdBaseFile* dirFile, const char* path);
bool remove();
/** Set the file's current position to zero. */
void rewind() {seekSet(0);}
bool rename(SdBaseFile* dirFile, const char* newPath);
bool rmdir();
// for backward compatibility
bool rmDir() {return rmdir();}
bool rmRfStar();
/** Set the files position to current position + \a pos. See seekSet().
* \param[in] offset The new position in bytes from the current position.
* \return true for success or false for failure.
*/
bool seekCur(int32_t offset) {
return seekSet(curPosition_ + offset);
}
/** Set the files position to end-of-file + \a offset. See seekSet().
* \param[in] offset The new position in bytes from end-of-file.
* \return true for success or false for failure.
*/
bool seekEnd(int32_t offset = 0) {return seekSet(fileSize_ + offset);}
bool seekSet(uint32_t pos);
bool sync();
bool timestamp(SdBaseFile* file);
bool timestamp(uint8_t flag, uint16_t year, uint8_t month, uint8_t day,
uint8_t hour, uint8_t minute, uint8_t second);
/** Type of file. You should use isFile() or isDir() instead of type()
* if possible.
*
* \return The file or directory type.
*/
uint8_t type() const {return type_;}
bool truncate(uint32_t size);
/** \return SdVolume that contains this file. */
SdVolume* volume() const {return vol_;}
int write(const void* buf, size_t nbyte);
//------------------------------------------------------------------------------
private:
// allow SdFat to set cwd_
friend class SdFat;
// global pointer to cwd dir
static SdBaseFile* cwd_;
// data time callback function
static void (*dateTime_)(uint16_t* date, uint16_t* time);
// bits defined in flags_
// should be 0X0F
static uint8_t const F_OFLAG = (O_ACCMODE | O_APPEND | O_SYNC);
// sync of directory entry required
static uint8_t const F_FILE_DIR_DIRTY = 0X80;
// private data
uint8_t flags_; // See above for definition of flags_ bits
uint8_t fstate_; // error and eof indicator
uint8_t type_; // type of file see above for values
uint8_t dirIndex_; // index of directory entry in dirBlock
SdVolume* vol_; // volume where file is located
uint32_t curCluster_; // cluster for current file position
uint32_t curPosition_; // current file position in bytes from beginning
uint32_t dirBlock_; // block for this files directory entry
uint32_t fileSize_; // file size in bytes
uint32_t firstCluster_; // first cluster of file
/** experimental don't use */
bool openParent(SdBaseFile* dir);
// private functions
bool addCluster();
cache_t* addDirCluster();
dir_t* cacheDirEntry(uint8_t action);
int8_t lsPrintNext(Print *pr, uint8_t flags, uint8_t indent);
static bool make83Name(const char* str, uint8_t* name, const char** ptr);
bool mkdir(SdBaseFile* parent, const uint8_t dname[11]);
bool open(SdBaseFile* dirFile, const uint8_t dname[11], uint8_t oflag);
bool openCachedEntry(uint8_t cacheIndex, uint8_t oflags);
dir_t* readDirCache();
bool setDirSize();
//------------------------------------------------------------------------------
// to be deleted
static void printDirName(const dir_t& dir,
uint8_t width, bool printSlash);
static void printDirName(Print* pr, const dir_t& dir,
uint8_t width, bool printSlash);
//------------------------------------------------------------------------------
// Deprecated functions - suppress cpplint warnings with NOLINT comment
#if ALLOW_DEPRECATED_FUNCTIONS && !defined(DOXYGEN)
public:
/** \deprecated Use:
* bool contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock);
* \param[out] bgnBlock the first block address for the file.
* \param[out] endBlock the last block address for the file.
* \return true for success or false for failure.
*/
bool contiguousRange(uint32_t& bgnBlock, uint32_t& endBlock) { // NOLINT
return contiguousRange(&bgnBlock, &endBlock);
}
/** \deprecated Use:
* bool createContiguous(SdBaseFile* dirFile,
* const char* path, uint32_t size)
* \param[in] dirFile The directory where the file will be created.
* \param[in] path A path with a valid DOS 8.3 file name.
* \param[in] size The desired file size.
* \return true for success or false for failure.
*/
bool createContiguous(SdBaseFile& dirFile, // NOLINT
const char* path, uint32_t size) {
return createContiguous(&dirFile, path, size);
}
/** \deprecated Use:
* static void dateTimeCallback(
* void (*dateTime)(uint16_t* date, uint16_t* time));
* \param[in] dateTime The user's call back function.
*/
static void dateTimeCallback(
void (*dateTime)(uint16_t& date, uint16_t& time)) { // NOLINT
oldDateTime_ = dateTime;
dateTime_ = dateTime ? oldToNew : 0;
}
/** \deprecated Use: bool dirEntry(dir_t* dir);
* \param[out] dir Location for return of the file's directory entry.
* \return true for success or false for failure.
*/
bool dirEntry(dir_t& dir) {return dirEntry(&dir);} // NOLINT
/** \deprecated Use:
* bool mkdir(SdBaseFile* dir, const char* path);
* \param[in] dir An open SdFat instance for the directory that will contain
* the new directory.
* \param[in] path A path with a valid 8.3 DOS name for the new directory.
* \return true for success or false for failure.
*/
bool mkdir(SdBaseFile& dir, const char* path) { // NOLINT
return mkdir(&dir, path);
}
/** \deprecated Use:
* bool open(SdBaseFile* dirFile, const char* path, uint8_t oflag);
* \param[in] dirFile An open SdFat instance for the directory containing the
* file to be opened.
* \param[in] path A path with a valid 8.3 DOS name for the file.
* \param[in] oflag Values for \a oflag are constructed by a bitwise-inclusive
* OR of flags O_READ, O_WRITE, O_TRUNC, and O_SYNC.
* \return true for success or false for failure.
*/
bool open(SdBaseFile& dirFile, // NOLINT
const char* path, uint8_t oflag) {
return open(&dirFile, path, oflag);
}
/** \deprecated Do not use in new apps
* \param[in] dirFile An open SdFat instance for the directory containing the
* file to be opened.
* \param[in] path A path with a valid 8.3 DOS name for a file to be opened.
* \return true for success or false for failure.
*/
bool open(SdBaseFile& dirFile, const char* path) { // NOLINT
return open(dirFile, path, O_RDWR);
}
/** \deprecated Use:
* bool open(SdBaseFile* dirFile, uint16_t index, uint8_t oflag);
* \param[in] dirFile An open SdFat instance for the directory.
* \param[in] index The \a index of the directory entry for the file to be
* opened. The value for \a index is (directory file position)/32.
* \param[in] oflag Values for \a oflag are constructed by a bitwise-inclusive
* OR of flags O_READ, O_WRITE, O_TRUNC, and O_SYNC.
* \return true for success or false for failure.
*/
bool open(SdBaseFile& dirFile, uint16_t index, uint8_t oflag) { // NOLINT
return open(&dirFile, index, oflag);
}
/** \deprecated Use: bool openRoot(SdVolume* vol);
* \param[in] vol The FAT volume containing the root directory to be opened.
* \return true for success or false for failure.
*/
bool openRoot(SdVolume& vol) {return openRoot(&vol);} // NOLINT
/** \deprecated Use: int8_t readDir(dir_t* dir);
* \param[out] dir The dir_t struct that will receive the data.
* \return bytes read for success zero for eof or -1 for failure.
*/
int8_t readDir(dir_t& dir) {return readDir(&dir);} // NOLINT
/** \deprecated Use:
* static uint8_t remove(SdBaseFile* dirFile, const char* path);
* \param[in] dirFile The directory that contains the file.
* \param[in] path The name of the file to be removed.
* \return true for success or false for failure.
*/
static bool remove(SdBaseFile& dirFile, const char* path) { // NOLINT
return remove(&dirFile, path);
}
//------------------------------------------------------------------------------
// rest are private
private:
static void (*oldDateTime_)(uint16_t& date, uint16_t& time); // NOLINT
static void oldToNew(uint16_t* date, uint16_t* time) {
uint16_t d;
uint16_t t;
oldDateTime_(d, t);
*date = d;
*time = t;
}
#elif !defined(DOXYGEN) // ALLOW_DEPRECATED_FUNCTIONS
public:
bool contiguousRange(uint32_t& bgnBlock, uint32_t& endBlock) // NOLINT
__attribute__((error("use contiguousRange(&bgnBlock, &endBlock)")));
bool createContiguous(SdBaseFile& dirFile, // NOLINT
const char* path, uint32_t size)
__attribute__((error("use createContiguous(&bgnBlock, &endBlock)")));
static void dateTimeCallback( // NOLINT
void (*dateTime)(uint16_t& date, uint16_t& time)) // NOLINT
__attribute__((error("use void dateTimeCallback("
"void (*dateTime)(uint16_t* date, uint16_t* time))")));
bool dirEntry(dir_t& dir) // NOLINT
__attribute__((error("use dirEntry(&dir)")));
bool mkdir(SdBaseFile& dir, const char* path) // NOLINT
__attribute__((error("use mkdir(&dir, path)")));
bool open(SdBaseFile& dirFile, // NOLINT
const char* path, uint8_t oflag)
__attribute__((error("use open(&dirFile, path, oflag)")));
bool open(SdBaseFile& dirFile, const char* path) // NOLINT
__attribute__((error("use open(&dirFile, path, O_RDWR)")));
bool open(SdBaseFile& dirFile, uint16_t index, uint8_t oflag) // NOLINT
__attribute__((error("use open(&dirFile, index, oflag)")));
bool openRoot(SdVolume& vol) // NOLINT
__attribute__((error("use openRoot(&vol)")));
int8_t readDir(dir_t& dir) // NOLINT
__attribute__((error("use readDir(&dir)")));
static bool remove(SdBaseFile& dirFile, const char* path) // NOLINT
__attribute__((error("use remove(&dirFile, path)")));
#endif // ALLOW_DEPRECATED_FUNCTIONS
};
#endif // SdBaseFile_h

View file

@ -0,0 +1,350 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#include <SdFat.h>
#ifndef PSTR
#define PSTR(x) x
#define PGM_P const char*
#endif
//------------------------------------------------------------------------------
#if USE_SERIAL_FOR_STD_OUT || !defined(UDR0)
Print* SdFat::stdOut_ = &Serial;
#else // USE_SERIAL_FOR_STD_OUT
#include <MinimumSerial.h>
Print* SdFat::stdOut_ = &MiniSerial;
#endif // USE_SERIAL_FOR_STD_OUT
//------------------------------------------------------------------------------
static void pstrPrint(PGM_P str) {
for (uint8_t c; (c = pgm_read_byte(str)); str++) SdFat::stdOut()->write(c);
}
//------------------------------------------------------------------------------
static void pstrPrintln(PGM_P str) {
pstrPrint(str);
SdFat::stdOut()->println();
}
//------------------------------------------------------------------------------
/**
* Initialize an SdFat object.
*
* Initializes the SD card, SD volume, and root directory.
*
* \param[in] chipSelectPin SD chip select pin. See Sd2Card::init().
* \param[in] sckRateID value for SPI SCK rate. See Sd2Card::init().
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure.
*/
bool SdFat::begin(uint8_t chipSelectPin, uint8_t sckRateID) {
return card_.init(sckRateID, chipSelectPin) && vol_.init(&card_) && chdir(1);
}
//------------------------------------------------------------------------------
/** Change a volume's working directory to root
*
* Changes the volume's working directory to the SD's root directory.
* Optionally set the current working directory to the volume's
* working directory.
*
* \param[in] set_cwd Set the current working directory to this volume's
* working directory if true.
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure.
*/
bool SdFat::chdir(bool set_cwd) {
if (set_cwd) SdBaseFile::cwd_ = &vwd_;
if (vwd_.isOpen()) vwd_.close();
return vwd_.openRoot(&vol_);
}
//------------------------------------------------------------------------------
/** Change a volume's working directory
*
* Changes the volume working directory to the \a path subdirectory.
* Optionally set the current working directory to the volume's
* working directory.
*
* Example: If the volume's working directory is "/DIR", chdir("SUB")
* will change the volume's working directory from "/DIR" to "/DIR/SUB".
*
* If path is "/", the volume's working directory will be changed to the
* root directory
*
* \param[in] path The name of the subdirectory.
*
* \param[in] set_cwd Set the current working directory to this volume's
* working directory if true.
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure.
*/
bool SdFat::chdir(const char *path, bool set_cwd) {
SdBaseFile dir;
if (path[0] == '/' && path[1] == '\0') return chdir(set_cwd);
if (!dir.open(&vwd_, path, O_READ)) goto fail;
if (!dir.isDir()) goto fail;
vwd_ = dir;
if (set_cwd) SdBaseFile::cwd_ = &vwd_;
return true;
fail:
return false;
}
//------------------------------------------------------------------------------
/** Set the current working directory to a volume's working directory.
*
* This is useful with multiple SD cards.
*
* The current working directory is changed to this volume's working directory.
*
* This is like the Windows/DOS \<drive letter>: command.
*/
void SdFat::chvol() {
SdBaseFile::cwd_ = &vwd_;
}
//------------------------------------------------------------------------------
/** %Print any SD error code and halt. */
void SdFat::errorHalt() {
errorPrint();
while (1);
}
//------------------------------------------------------------------------------
/** %Print msg, any SD error code, and halt.
*
* \param[in] msg Message to print.
*/
void SdFat::errorHalt(char const* msg) {
errorPrint(msg);
while (1);
}
//------------------------------------------------------------------------------
/** %Print msg, any SD error code, and halt.
*
* \param[in] msg Message in program space (flash memory) to print.
*/
void SdFat::errorHalt_P(PGM_P msg) {
errorPrint_P(msg);
while (1);
}
//------------------------------------------------------------------------------
/** %Print any SD error code. */
void SdFat::errorPrint() {
if (!card_.errorCode()) return;
pstrPrint(PSTR("SD errorCode: 0X"));
stdOut_->print(card_.errorCode(), HEX);
pstrPrint(PSTR(",0X"));
stdOut_->println(card_.errorData(), HEX);
}
//------------------------------------------------------------------------------
/** %Print msg, any SD error code.
*
* \param[in] msg Message to print.
*/
void SdFat::errorPrint(char const* msg) {
pstrPrint(PSTR("error: "));
stdOut_->println(msg);
errorPrint();
}
//------------------------------------------------------------------------------
/** %Print msg, any SD error code.
*
* \param[in] msg Message in program space (flash memory) to print.
*/
void SdFat::errorPrint_P(PGM_P msg) {
pstrPrint(PSTR("error: "));
pstrPrintln(msg);
errorPrint();
}
//------------------------------------------------------------------------------
/**
* Test for the existence of a file.
*
* \param[in] name Name of the file to be tested for.
*
* \return true if the file exists else false.
*/
bool SdFat::exists(const char* name) {
return vwd_.exists(name);
}
//------------------------------------------------------------------------------
/** %Print error details and halt after SdFat::init() fails. */
void SdFat::initErrorHalt() {
initErrorPrint();
while (1);
}
//------------------------------------------------------------------------------
/**Print message, error details, and halt after SdFat::init() fails.
*
* \param[in] msg Message to print.
*/
void SdFat::initErrorHalt(char const *msg) {
stdOut_->println(msg);
initErrorHalt();
}
//------------------------------------------------------------------------------
/**Print message, error details, and halt after SdFat::init() fails.
*
* \param[in] msg Message in program space (flash memory) to print.
*/
void SdFat::initErrorHalt_P(PGM_P msg) {
pstrPrintln(msg);
initErrorHalt();
}
//------------------------------------------------------------------------------
/** Print error details after SdFat::init() fails. */
void SdFat::initErrorPrint() {
if (card_.errorCode()) {
pstrPrintln(PSTR("Can't access SD card. Do not reformat."));
if (card_.errorCode() == SD_CARD_ERROR_CMD0) {
pstrPrintln(PSTR("No card, wrong chip select pin, or SPI problem?"));
}
errorPrint();
} else if (vol_.fatType() == 0) {
pstrPrintln(PSTR("Invalid format, reformat SD."));
} else if (!vwd_.isOpen()) {
pstrPrintln(PSTR("Can't open root directory."));
} else {
pstrPrintln(PSTR("No error found."));
}
}
//------------------------------------------------------------------------------
/**Print message and error details and halt after SdFat::init() fails.
*
* \param[in] msg Message to print.
*/
void SdFat::initErrorPrint(char const *msg) {
stdOut_->println(msg);
initErrorPrint();
}
//------------------------------------------------------------------------------
/**Print message and error details after SdFat::init() fails.
*
* \param[in] msg Message in program space (flash memory) to print.
*/
void SdFat::initErrorPrint_P(PGM_P msg) {
pstrPrintln(msg);
initErrorHalt();
}
//------------------------------------------------------------------------------
/** List the directory contents of the volume working directory to stdOut.
*
* \param[in] flags The inclusive OR of
*
* LS_DATE - %Print file modification date
*
* LS_SIZE - %Print file size.
*
* LS_R - Recursive list of subdirectories.
*/
void SdFat::ls(uint8_t flags) {
vwd_.ls(stdOut_, flags);
}
//------------------------------------------------------------------------------
/** List the directory contents of the volume working directory.
*
* \param[in] pr Print stream for list.
*
* \param[in] flags The inclusive OR of
*
* LS_DATE - %Print file modification date
*
* LS_SIZE - %Print file size.
*
* LS_R - Recursive list of subdirectories.
*/
void SdFat::ls(Print* pr, uint8_t flags) {
vwd_.ls(pr, flags);
}
//------------------------------------------------------------------------------
/** Make a subdirectory in the volume working directory.
*
* \param[in] path A path with a valid 8.3 DOS name for the subdirectory.
*
* \param[in] pFlag Create missing parent directories if true.
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure.
*/
bool SdFat::mkdir(const char* path, bool pFlag) {
SdBaseFile sub;
return sub.mkdir(&vwd_, path, pFlag);
}
//------------------------------------------------------------------------------
/** Remove a file from the volume working directory.
*
* \param[in] path A path with a valid 8.3 DOS name for the file.
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure.
*/
bool SdFat::remove(const char* path) {
return SdBaseFile::remove(&vwd_, path);
}
//------------------------------------------------------------------------------
/** Rename a file or subdirectory.
*
* \param[in] oldPath Path name to the file or subdirectory to be renamed.
*
* \param[in] newPath New path name of the file or subdirectory.
*
* The \a newPath object must not exist before the rename call.
*
* The file to be renamed must not be open. The directory entry may be
* moved and file system corruption could occur if the file is accessed by
* a file object that was opened before the rename() call.
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure.
*/
bool SdFat::rename(const char *oldPath, const char *newPath) {
SdBaseFile file;
if (!file.open(oldPath, O_READ)) return false;
return file.rename(&vwd_, newPath);
}
//------------------------------------------------------------------------------
/** Remove a subdirectory from the volume's working directory.
*
* \param[in] path A path with a valid 8.3 DOS name for the subdirectory.
*
* The subdirectory file will be removed only if it is empty.
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure.
*/
bool SdFat::rmdir(const char* path) {
SdBaseFile sub;
if (!sub.open(path, O_READ)) return false;
return sub.rmdir();
}
//------------------------------------------------------------------------------
/** Truncate a file to a specified length. The current file position
* will be maintained if it is less than or equal to \a length otherwise
* it will be set to end of file.
*
* \param[in] path A path with a valid 8.3 DOS name for the file.
* \param[in] length The desired length for the file.
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure.
* Reasons for failure include file is read only, file is a directory,
* \a length is greater than the current file size or an I/O error occurs.
*/
bool SdFat::truncate(const char* path, uint32_t length) {
SdBaseFile file;
if (!file.open(path, O_WRITE)) return false;
return file.truncate(length);
}

View file

@ -0,0 +1,119 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef SdFat_h
#define SdFat_h
/**
* \file
* \brief SdFat class
*/
//------------------------------------------------------------------------------
/** SdFat version YYYYMMDD */
#define SD_FAT_VERSION 20121219
//------------------------------------------------------------------------------
/** error if old IDE */
#if !defined(ARDUINO) || ARDUINO < 100
#error Arduino IDE must be 1.0 or greater
#endif // ARDUINO < 100
//------------------------------------------------------------------------------
#include <SdFile.h>
#include <SdStream.h>
#include <ArduinoStream.h>
#include <MinimumSerial.h>
//------------------------------------------------------------------------------
/**
* \class SdFat
* \brief Integration class for the %SdFat library.
*/
class SdFat {
public:
SdFat() {}
#if ALLOW_DEPRECATED_FUNCTIONS && !defined(DOXYGEN)
/**
* Initialize an SdFat object.
*
* Initializes the SD card, SD volume, and root directory.
*
* \param[in] sckRateID value for SPI SCK rate. See Sd2Card::init().
* \param[in] chipSelectPin SD chip select pin. See Sd2Card::init().
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure.
*/
bool init(uint8_t sckRateID = SPI_FULL_SPEED,
uint8_t chipSelectPin = SD_CHIP_SELECT_PIN) {
return begin(chipSelectPin, sckRateID);
}
#elif !defined(DOXYGEN) // ALLOW_DEPRECATED_FUNCTIONS
bool init() __attribute__((error("use sd.begin()")));
bool init(uint8_t sckRateID)
__attribute__((error("use sd.begin(chipSelect, sckRate)")));
bool init(uint8_t sckRateID, uint8_t chipSelectPin)
__attribute__((error("use sd.begin(chipSelect, sckRate)")));
#endif // ALLOW_DEPRECATED_FUNCTIONS
/** \return a pointer to the Sd2Card object. */
Sd2Card* card() {return &card_;}
bool chdir(bool set_cwd = false);
bool chdir(const char* path, bool set_cwd = false);
void chvol();
void errorHalt();
void errorHalt(char const *msg);
void errorPrint();
void errorPrint(char const *msg);
bool exists(const char* name);
bool begin(uint8_t chipSelectPin = SD_CHIP_SELECT_PIN,
uint8_t sckRateID = SPI_FULL_SPEED);
void initErrorHalt();
void initErrorHalt(char const *msg);
void initErrorPrint();
void initErrorPrint(char const *msg);
void ls(uint8_t flags = 0);
void ls(Print* pr, uint8_t flags = 0);
bool mkdir(const char* path, bool pFlag = true);
bool remove(const char* path);
bool rename(const char *oldPath, const char *newPath);
bool rmdir(const char* path);
bool truncate(const char* path, uint32_t length);
/** \return a pointer to the SdVolume object. */
SdVolume* vol() {return &vol_;}
/** \return a pointer to the volume working directory. */
SdBaseFile* vwd() {return &vwd_;}
//----------------------------------------------------------------------------
void errorHalt_P(PGM_P msg);
void errorPrint_P(PGM_P msg);
void initErrorHalt_P(PGM_P msg);
void initErrorPrint_P(PGM_P msg);
//----------------------------------------------------------------------------
/**
* Set stdOut Print stream for messages.
* \param[in] stream The new Print stream.
*/
static void setStdOut(Print* stream) {stdOut_ = stream;}
/** \return Print stream for messages. */
static Print* stdOut() {return stdOut_;}
private:
Sd2Card card_;
SdVolume vol_;
SdBaseFile vwd_;
static Print* stdOut_;
};
#endif // SdFat_h

View file

@ -0,0 +1,183 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
/**
* \file
* \brief configuration definitions
*/
#ifndef SdFatConfig_h
#define SdFatConfig_h
#include <stdint.h>
//------------------------------------------------------------------------------
/**
* Set USE_SEPARATE_FAT_CACHE nonzero to use a second 512 byte cache
* for FAT table entries. Improves performance for large writes that
* are not a multiple of 512 bytes.
*/
#ifdef __arm__
#define USE_SEPARATE_FAT_CACHE 1
#else // __arm__
#define USE_SEPARATE_FAT_CACHE 0
#endif // __arm__
//------------------------------------------------------------------------------
/**
* Don't use mult-block read/write on small AVR boards
*/
#if defined(RAMEND) && RAMEND < 3000
#define USE_MULTI_BLOCK_SD_IO 0
#else
#define USE_MULTI_BLOCK_SD_IO 1
#endif
//------------------------------------------------------------------------------
/**
* Force use of Arduino Standard SPI library if USE_ARDUINO_SPI_LIBRARY
* is nonzero.
*/
#define USE_ARDUINO_SPI_LIBRARY 0
//------------------------------------------------------------------------------
/**
* Use native SPI on Teensy 3.0 if USE_NATIVE_MK20DX128-SPI is nonzero.
*/
#if defined(__arm__) && defined(CORE_TEENSY)
#define USE_NATIVE_MK20DX128_SPI 1
#else
#define USE_NATIVE_MK20DX128_SPI 0
#endif
//------------------------------------------------------------------------------
/**
* Use fast SAM3X SPI library if USE_NATIVE_SAM3X_SPI is nonzero.
*/
#if defined(__arm__) && !defined(CORE_TEENSY)
#define USE_NATIVE_SAM3X_SPI 1
#else
#define USE_NATIVE_SAM3X_SPI 0
#endif
//------------------------------------------------------------------------------
/**
* To enable SD card CRC checking set USE_SD_CRC nonzero.
*
* Set USE_SD_CRC to 1 to use a smaller slower CRC-CCITT function.
*
* Set USE_SD_CRC to 2 to used a larger faster table driven CRC-CCITT function.
*/
#define USE_SD_CRC 0
//------------------------------------------------------------------------------
/**
* To use multiple SD cards set USE_MULTIPLE_CARDS nonzero.
*
* Using multiple cards costs 400 - 500 bytes of flash.
*
* Each card requires about 550 bytes of SRAM so use of a Mega is recommended.
*/
#define USE_MULTIPLE_CARDS 0
//------------------------------------------------------------------------------
/**
* Set DESTRUCTOR_CLOSES_FILE nonzero to close a file in its destructor.
*
* Causes use of lots of heap in ARM.
*/
#define DESTRUCTOR_CLOSES_FILE 0
//------------------------------------------------------------------------------
/**
* For AVR
*
* Set nonzero to use Serial (the HardwareSerial class) for error messages
* and output from print functions like ls().
*
* If USE_SERIAL_FOR_STD_OUT is zero, a small non-interrupt driven class
* is used to output messages to serial port zero. This allows an alternate
* Serial library like SerialPort to be used with SdFat.
*
* You can redirect stdOut with SdFat::setStdOut(Print* stream) and
* get the current stream with SdFat::stdOut().
*/
#define USE_SERIAL_FOR_STD_OUT 0
//------------------------------------------------------------------------------
/**
* Call flush for endl if ENDL_CALLS_FLUSH is nonzero
*
* The standard for iostreams is to call flush. This is very costly for
* SdFat. Each call to flush causes 2048 bytes of I/O to the SD.
*
* SdFat has a single 512 byte buffer for SD I/O so it must write the current
* data block to the SD, read the directory block from the SD, update the
* directory entry, write the directory block to the SD and read the data
* block back into the buffer.
*
* The SD flash memory controller is not designed for this many rewrites
* so performance may be reduced by more than a factor of 100.
*
* If ENDL_CALLS_FLUSH is zero, you must call flush and/or close to force
* all data to be written to the SD.
*/
#define ENDL_CALLS_FLUSH 0
//------------------------------------------------------------------------------
/**
* Allow use of deprecated functions if ALLOW_DEPRECATED_FUNCTIONS is nonzero
*/
#define ALLOW_DEPRECATED_FUNCTIONS 0
//------------------------------------------------------------------------------
/**
* Allow FAT12 volumes if FAT12_SUPPORT is nonzero.
* FAT12 has not been well tested.
*/
#define FAT12_SUPPORT 0
//------------------------------------------------------------------------------
/**
* SPI init rate for SD initialization commands. Must be 10 (F_CPU/64)
* or greater
*/
#define SPI_SD_INIT_RATE 11
//------------------------------------------------------------------------------
/**
* Define MEGA_SOFT_SPI nonzero to use software SPI on Mega Arduinos.
* Default pins used are SS 10, MOSI 11, MISO 12, and SCK 13.
* Edit Software Spi pins to change pin numbers.
*
* MEGA_SOFT_SPI allows an unmodified Adafruit GPS Shield to be used
* on Mega Arduinos. Software SPI works well with GPS Shield V1.1
* but many SD cards will fail with GPS Shield V1.0.
*/
#define MEGA_SOFT_SPI 1
//------------------------------------------------------------------------------
/**
* Define LEONARDO_SOFT_SPI nonzero to use software SPI on Leonardo Arduinos.
* Default pins used are SS 10, MOSI 11, MISO 12, and SCK 13.
* Edit Software Spi pins to change pin numbers.
*
* LEONARDO_SOFT_SPI allows an unmodified Adafruit GPS Shield to be used
* on Leonardo Arduinos. Software SPI works well with GPS Shield V1.1
* but many SD cards will fail with GPS Shield V1.0.
*/
#define LEONARDO_SOFT_SPI 1
//------------------------------------------------------------------------------
/**
* Set USE_SOFTWARE_SPI nonzero to always use software SPI on AVR.
*/
#define USE_SOFTWARE_SPI 0
// define software SPI pins so Mega can use unmodified 168/328 shields
/** Default Software SPI chip select pin */
uint8_t const SOFT_SPI_CS_PIN = 10;
/** Software SPI Master Out Slave In pin */
uint8_t const SOFT_SPI_MOSI_PIN = 11;
/** Software SPI Master In Slave Out pin */
uint8_t const SOFT_SPI_MISO_PIN = 12;
/** Software SPI Clock pin */
uint8_t const SOFT_SPI_SCK_PIN = 13;
#endif // SdFatConfig_h

View file

@ -0,0 +1,604 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef SdFatStructs_h
#define SdFatStructs_h
/**
* \file
* \brief FAT file structures
*/
/*
* mostly from Microsoft document fatgen103.doc
* http://www.microsoft.com/whdc/system/platform/firmware/fatgen.mspx
*/
//------------------------------------------------------------------------------
/** Value for byte 510 of boot block or MBR */
uint8_t const BOOTSIG0 = 0X55;
/** Value for byte 511 of boot block or MBR */
uint8_t const BOOTSIG1 = 0XAA;
/** Value for bootSignature field int FAT/FAT32 boot sector */
uint8_t const EXTENDED_BOOT_SIG = 0X29;
//------------------------------------------------------------------------------
/**
* \struct partitionTable
* \brief MBR partition table entry
*
* A partition table entry for a MBR formatted storage device.
* The MBR partition table has four entries.
*/
struct partitionTable {
/**
* Boot Indicator . Indicates whether the volume is the active
* partition. Legal values include: 0X00. Do not use for booting.
* 0X80 Active partition.
*/
uint8_t boot;
/**
* Head part of Cylinder-head-sector address of the first block in
* the partition. Legal values are 0-255. Only used in old PC BIOS.
*/
uint8_t beginHead;
/**
* Sector part of Cylinder-head-sector address of the first block in
* the partition. Legal values are 1-63. Only used in old PC BIOS.
*/
unsigned beginSector : 6;
/** High bits cylinder for first block in partition. */
unsigned beginCylinderHigh : 2;
/**
* Combine beginCylinderLow with beginCylinderHigh. Legal values
* are 0-1023. Only used in old PC BIOS.
*/
uint8_t beginCylinderLow;
/**
* Partition type. See defines that begin with PART_TYPE_ for
* some Microsoft partition types.
*/
uint8_t type;
/**
* head part of cylinder-head-sector address of the last sector in the
* partition. Legal values are 0-255. Only used in old PC BIOS.
*/
uint8_t endHead;
/**
* Sector part of cylinder-head-sector address of the last sector in
* the partition. Legal values are 1-63. Only used in old PC BIOS.
*/
unsigned endSector : 6;
/** High bits of end cylinder */
unsigned endCylinderHigh : 2;
/**
* Combine endCylinderLow with endCylinderHigh. Legal values
* are 0-1023. Only used in old PC BIOS.
*/
uint8_t endCylinderLow;
/** Logical block address of the first block in the partition. */
uint32_t firstSector;
/** Length of the partition, in blocks. */
uint32_t totalSectors;
}__attribute__((packed));
/** Type name for partitionTable */
typedef struct partitionTable part_t;
//------------------------------------------------------------------------------
/**
* \struct masterBootRecord
*
* \brief Master Boot Record
*
* The first block of a storage device that is formatted with a MBR.
*/
struct masterBootRecord {
/** Code Area for master boot program. */
uint8_t codeArea[440];
/** Optional Windows NT disk signature. May contain boot code. */
uint32_t diskSignature;
/** Usually zero but may be more boot code. */
uint16_t usuallyZero;
/** Partition tables. */
part_t part[4];
/** First MBR signature byte. Must be 0X55 */
uint8_t mbrSig0;
/** Second MBR signature byte. Must be 0XAA */
uint8_t mbrSig1;
}__attribute__((packed));
/** Type name for masterBootRecord */
typedef struct masterBootRecord mbr_t;
//------------------------------------------------------------------------------
/**
* \struct fat_boot
*
* \brief Boot sector for a FAT12/FAT16 volume.
*
*/
struct fat_boot {
/**
* The first three bytes of the boot sector must be valid,
* executable x 86-based CPU instructions. This includes a
* jump instruction that skips the next nonexecutable bytes.
*/
uint8_t jump[3];
/**
* This is typically a string of characters that identifies
* the operating system that formatted the volume.
*/
char oemId[8];
/**
* The size of a hardware sector. Valid decimal values for this
* field are 512, 1024, 2048, and 4096. For most disks used in
* the United States, the value of this field is 512.
*/
uint16_t bytesPerSector;
/**
* Number of sectors per allocation unit. This value must be a
* power of 2 that is greater than 0. The legal values are
* 1, 2, 4, 8, 16, 32, 64, and 128. 128 should be avoided.
*/
uint8_t sectorsPerCluster;
/**
* The number of sectors preceding the start of the first FAT,
* including the boot sector. The value of this field is always 1.
*/
uint16_t reservedSectorCount;
/**
* The number of copies of the FAT on the volume.
* The value of this field is always 2.
*/
uint8_t fatCount;
/**
* For FAT12 and FAT16 volumes, this field contains the count of
* 32-byte directory entries in the root directory. For FAT32 volumes,
* this field must be set to 0. For FAT12 and FAT16 volumes, this
* value should always specify a count that when multiplied by 32
* results in a multiple of bytesPerSector. FAT16 volumes should
* use the value 512.
*/
uint16_t rootDirEntryCount;
/**
* This field is the old 16-bit total count of sectors on the volume.
* This count includes the count of all sectors in all four regions
* of the volume. This field can be 0; if it is 0, then totalSectors32
* must be nonzero. For FAT32 volumes, this field must be 0. For
* FAT12 and FAT16 volumes, this field contains the sector count, and
* totalSectors32 is 0 if the total sector count fits
* (is less than 0x10000).
*/
uint16_t totalSectors16;
/**
* This dates back to the old MS-DOS 1.x media determination and is
* no longer usually used for anything. 0xF8 is the standard value
* for fixed (nonremovable) media. For removable media, 0xF0 is
* frequently used. Legal values are 0xF0 or 0xF8-0xFF.
*/
uint8_t mediaType;
/**
* Count of sectors occupied by one FAT on FAT12/FAT16 volumes.
* On FAT32 volumes this field must be 0, and sectorsPerFat32
* contains the FAT size count.
*/
uint16_t sectorsPerFat16;
/** Sectors per track for interrupt 0x13. Not used otherwise. */
uint16_t sectorsPerTrack;
/** Number of heads for interrupt 0x13. Not used otherwise. */
uint16_t headCount;
/**
* Count of hidden sectors preceding the partition that contains this
* FAT volume. This field is generally only relevant for media
* visible on interrupt 0x13.
*/
uint32_t hidddenSectors;
/**
* This field is the new 32-bit total count of sectors on the volume.
* This count includes the count of all sectors in all four regions
* of the volume. This field can be 0; if it is 0, then
* totalSectors16 must be nonzero.
*/
uint32_t totalSectors32;
/**
* Related to the BIOS physical drive number. Floppy drives are
* identified as 0x00 and physical hard disks are identified as
* 0x80, regardless of the number of physical disk drives.
* Typically, this value is set prior to issuing an INT 13h BIOS
* call to specify the device to access. The value is only
* relevant if the device is a boot device.
*/
uint8_t driveNumber;
/** used by Windows NT - should be zero for FAT */
uint8_t reserved1;
/** 0X29 if next three fields are valid */
uint8_t bootSignature;
/**
* A random serial number created when formatting a disk,
* which helps to distinguish between disks.
* Usually generated by combining date and time.
*/
uint32_t volumeSerialNumber;
/**
* A field once used to store the volume label. The volume label
* is now stored as a special file in the root directory.
*/
char volumeLabel[11];
/**
* A field with a value of either FAT, FAT12 or FAT16,
* depending on the disk format.
*/
char fileSystemType[8];
/** X86 boot code */
uint8_t bootCode[448];
/** must be 0X55 */
uint8_t bootSectorSig0;
/** must be 0XAA */
uint8_t bootSectorSig1;
}__attribute__((packed));
/** Type name for FAT Boot Sector */
typedef struct fat_boot fat_boot_t;
//------------------------------------------------------------------------------
/**
* \struct fat32_boot
*
* \brief Boot sector for a FAT32 volume.
*
*/
struct fat32_boot {
/**
* The first three bytes of the boot sector must be valid,
* executable x 86-based CPU instructions. This includes a
* jump instruction that skips the next nonexecutable bytes.
*/
uint8_t jump[3];
/**
* This is typically a string of characters that identifies
* the operating system that formatted the volume.
*/
char oemId[8];
/**
* The size of a hardware sector. Valid decimal values for this
* field are 512, 1024, 2048, and 4096. For most disks used in
* the United States, the value of this field is 512.
*/
uint16_t bytesPerSector;
/**
* Number of sectors per allocation unit. This value must be a
* power of 2 that is greater than 0. The legal values are
* 1, 2, 4, 8, 16, 32, 64, and 128. 128 should be avoided.
*/
uint8_t sectorsPerCluster;
/**
* The number of sectors preceding the start of the first FAT,
* including the boot sector. Must not be zero
*/
uint16_t reservedSectorCount;
/**
* The number of copies of the FAT on the volume.
* The value of this field is always 2.
*/
uint8_t fatCount;
/**
* FAT12/FAT16 only. For FAT32 volumes, this field must be set to 0.
*/
uint16_t rootDirEntryCount;
/**
* For FAT32 volumes, this field must be 0.
*/
uint16_t totalSectors16;
/**
* This dates back to the old MS-DOS 1.x media determination and is
* no longer usually used for anything. 0xF8 is the standard value
* for fixed (nonremovable) media. For removable media, 0xF0 is
* frequently used. Legal values are 0xF0 or 0xF8-0xFF.
*/
uint8_t mediaType;
/**
* On FAT32 volumes this field must be 0, and sectorsPerFat32
* contains the FAT size count.
*/
uint16_t sectorsPerFat16;
/** Sectors per track for interrupt 0x13. Not used otherwise. */
uint16_t sectorsPerTrack;
/** Number of heads for interrupt 0x13. Not used otherwise. */
uint16_t headCount;
/**
* Count of hidden sectors preceding the partition that contains this
* FAT volume. This field is generally only relevant for media
* visible on interrupt 0x13.
*/
uint32_t hidddenSectors;
/**
* Contains the total number of sectors in the FAT32 volume.
*/
uint32_t totalSectors32;
/**
* Count of sectors occupied by one FAT on FAT32 volumes.
*/
uint32_t sectorsPerFat32;
/**
* This field is only defined for FAT32 media and does not exist on
* FAT12 and FAT16 media.
* Bits 0-3 -- Zero-based number of active FAT.
* Only valid if mirroring is disabled.
* Bits 4-6 -- Reserved.
* Bit 7 -- 0 means the FAT is mirrored at runtime into all FATs.
* -- 1 means only one FAT is active; it is the one referenced
* in bits 0-3.
* Bits 8-15 -- Reserved.
*/
uint16_t fat32Flags;
/**
* FAT32 version. High byte is major revision number.
* Low byte is minor revision number. Only 0.0 define.
*/
uint16_t fat32Version;
/**
* Cluster number of the first cluster of the root directory for FAT32.
* This usually 2 but not required to be 2.
*/
uint32_t fat32RootCluster;
/**
* Sector number of FSINFO structure in the reserved area of the
* FAT32 volume. Usually 1.
*/
uint16_t fat32FSInfo;
/**
* If nonzero, indicates the sector number in the reserved area
* of the volume of a copy of the boot record. Usually 6.
* No value other than 6 is recommended.
*/
uint16_t fat32BackBootBlock;
/**
* Reserved for future expansion. Code that formats FAT32 volumes
* should always set all of the bytes of this field to 0.
*/
uint8_t fat32Reserved[12];
/**
* Related to the BIOS physical drive number. Floppy drives are
* identified as 0x00 and physical hard disks are identified as
* 0x80, regardless of the number of physical disk drives.
* Typically, this value is set prior to issuing an INT 13h BIOS
* call to specify the device to access. The value is only
* relevant if the device is a boot device.
*/
uint8_t driveNumber;
/** used by Windows NT - should be zero for FAT */
uint8_t reserved1;
/** 0X29 if next three fields are valid */
uint8_t bootSignature;
/**
* A random serial number created when formatting a disk,
* which helps to distinguish between disks.
* Usually generated by combining date and time.
*/
uint32_t volumeSerialNumber;
/**
* A field once used to store the volume label. The volume label
* is now stored as a special file in the root directory.
*/
char volumeLabel[11];
/**
* A text field with a value of FAT32.
*/
char fileSystemType[8];
/** X86 boot code */
uint8_t bootCode[420];
/** must be 0X55 */
uint8_t bootSectorSig0;
/** must be 0XAA */
uint8_t bootSectorSig1;
}__attribute__((packed));
/** Type name for FAT32 Boot Sector */
typedef struct fat32_boot fat32_boot_t;
//------------------------------------------------------------------------------
/** Lead signature for a FSINFO sector */
uint32_t const FSINFO_LEAD_SIG = 0x41615252;
/** Struct signature for a FSINFO sector */
uint32_t const FSINFO_STRUCT_SIG = 0x61417272;
/**
* \struct fat32_fsinfo
*
* \brief FSINFO sector for a FAT32 volume.
*
*/
struct fat32_fsinfo {
/** must be 0X52, 0X52, 0X61, 0X41 */
uint32_t leadSignature;
/** must be zero */
uint8_t reserved1[480];
/** must be 0X72, 0X72, 0X41, 0X61 */
uint32_t structSignature;
/**
* Contains the last known free cluster count on the volume.
* If the value is 0xFFFFFFFF, then the free count is unknown
* and must be computed. Any other value can be used, but is
* not necessarily correct. It should be range checked at least
* to make sure it is <= volume cluster count.
*/
uint32_t freeCount;
/**
* This is a hint for the FAT driver. It indicates the cluster
* number at which the driver should start looking for free clusters.
* If the value is 0xFFFFFFFF, then there is no hint and the driver
* should start looking at cluster 2.
*/
uint32_t nextFree;
/** must be zero */
uint8_t reserved2[12];
/** must be 0X00, 0X00, 0X55, 0XAA */
uint8_t tailSignature[4];
}__attribute__((packed));
/** Type name for FAT32 FSINFO Sector */
typedef struct fat32_fsinfo fat32_fsinfo_t;
//------------------------------------------------------------------------------
// End Of Chain values for FAT entries
/** FAT12 end of chain value used by Microsoft. */
uint16_t const FAT12EOC = 0XFFF;
/** Minimum value for FAT12 EOC. Use to test for EOC. */
uint16_t const FAT12EOC_MIN = 0XFF8;
/** FAT16 end of chain value used by Microsoft. */
uint16_t const FAT16EOC = 0XFFFF;
/** Minimum value for FAT16 EOC. Use to test for EOC. */
uint16_t const FAT16EOC_MIN = 0XFFF8;
/** FAT32 end of chain value used by Microsoft. */
uint32_t const FAT32EOC = 0X0FFFFFFF;
/** Minimum value for FAT32 EOC. Use to test for EOC. */
uint32_t const FAT32EOC_MIN = 0X0FFFFFF8;
/** Mask a for FAT32 entry. Entries are 28 bits. */
uint32_t const FAT32MASK = 0X0FFFFFFF;
//------------------------------------------------------------------------------
/**
* \struct directoryEntry
* \brief FAT short directory entry
*
* Short means short 8.3 name, not the entry size.
*
* Date Format. A FAT directory entry date stamp is a 16-bit field that is
* basically a date relative to the MS-DOS epoch of 01/01/1980. Here is the
* format (bit 0 is the LSB of the 16-bit word, bit 15 is the MSB of the
* 16-bit word):
*
* Bits 9-15: Count of years from 1980, valid value range 0-127
* inclusive (1980-2107).
*
* Bits 5-8: Month of year, 1 = January, valid value range 1-12 inclusive.
*
* Bits 0-4: Day of month, valid value range 1-31 inclusive.
*
* Time Format. A FAT directory entry time stamp is a 16-bit field that has
* a granularity of 2 seconds. Here is the format (bit 0 is the LSB of the
* 16-bit word, bit 15 is the MSB of the 16-bit word).
*
* Bits 11-15: Hours, valid value range 0-23 inclusive.
*
* Bits 5-10: Minutes, valid value range 0-59 inclusive.
*
* Bits 0-4: 2-second count, valid value range 0-29 inclusive (0 - 58 seconds).
*
* The valid time range is from Midnight 00:00:00 to 23:59:58.
*/
struct directoryEntry {
/** Short 8.3 name.
*
* The first eight bytes contain the file name with blank fill.
* The last three bytes contain the file extension with blank fill.
*/
uint8_t name[11];
/** Entry attributes.
*
* The upper two bits of the attribute byte are reserved and should
* always be set to 0 when a file is created and never modified or
* looked at after that. See defines that begin with DIR_ATT_.
*/
uint8_t attributes;
/**
* Reserved for use by Windows NT. Set value to 0 when a file is
* created and never modify or look at it after that.
*/
uint8_t reservedNT;
/**
* The granularity of the seconds part of creationTime is 2 seconds
* so this field is a count of tenths of a second and its valid
* value range is 0-199 inclusive. (WHG note - seems to be hundredths)
*/
uint8_t creationTimeTenths;
/** Time file was created. */
uint16_t creationTime;
/** Date file was created. */
uint16_t creationDate;
/**
* Last access date. Note that there is no last access time, only
* a date. This is the date of last read or write. In the case of
* a write, this should be set to the same date as lastWriteDate.
*/
uint16_t lastAccessDate;
/**
* High word of this entry's first cluster number (always 0 for a
* FAT12 or FAT16 volume).
*/
uint16_t firstClusterHigh;
/** Time of last write. File creation is considered a write. */
uint16_t lastWriteTime;
/** Date of last write. File creation is considered a write. */
uint16_t lastWriteDate;
/** Low word of this entry's first cluster number. */
uint16_t firstClusterLow;
/** 32-bit unsigned holding this file's size in bytes. */
uint32_t fileSize;
}__attribute__((packed));
//------------------------------------------------------------------------------
// Definitions for directory entries
//
/** Type name for directoryEntry */
typedef struct directoryEntry dir_t;
/** escape for name[0] = 0XE5 */
uint8_t const DIR_NAME_0XE5 = 0X05;
/** name[0] value for entry that is free after being "deleted" */
uint8_t const DIR_NAME_DELETED = 0XE5;
/** name[0] value for entry that is free and no allocated entries follow */
uint8_t const DIR_NAME_FREE = 0X00;
/** file is read-only */
uint8_t const DIR_ATT_READ_ONLY = 0X01;
/** File should hidden in directory listings */
uint8_t const DIR_ATT_HIDDEN = 0X02;
/** Entry is for a system file */
uint8_t const DIR_ATT_SYSTEM = 0X04;
/** Directory entry contains the volume label */
uint8_t const DIR_ATT_VOLUME_ID = 0X08;
/** Entry is for a directory */
uint8_t const DIR_ATT_DIRECTORY = 0X10;
/** Old DOS archive bit for backup support */
uint8_t const DIR_ATT_ARCHIVE = 0X20;
/** Test value for long name entry. Test is
(d->attributes & DIR_ATT_LONG_NAME_MASK) == DIR_ATT_LONG_NAME. */
uint8_t const DIR_ATT_LONG_NAME = 0X0F;
/** Test mask for long name entry */
uint8_t const DIR_ATT_LONG_NAME_MASK = 0X3F;
/** defined attribute bits */
uint8_t const DIR_ATT_DEFINED_BITS = 0X3F;
/** Directory entry is part of a long name
* \param[in] dir Pointer to a directory entry.
*
* \return true if the entry is for part of a long name else false.
*/
static inline uint8_t DIR_IS_LONG_NAME(const dir_t* dir) {
return (dir->attributes & DIR_ATT_LONG_NAME_MASK) == DIR_ATT_LONG_NAME;
}
/** Mask for file/subdirectory tests */
uint8_t const DIR_ATT_FILE_TYPE_MASK = (DIR_ATT_VOLUME_ID | DIR_ATT_DIRECTORY);
/** Directory entry is for a file
* \param[in] dir Pointer to a directory entry.
*
* \return true if the entry is for a normal file else false.
*/
static inline uint8_t DIR_IS_FILE(const dir_t* dir) {
return (dir->attributes & DIR_ATT_FILE_TYPE_MASK) == 0;
}
/** Directory entry is for a subdirectory
* \param[in] dir Pointer to a directory entry.
*
* \return true if the entry is for a subdirectory else false.
*/
static inline uint8_t DIR_IS_SUBDIR(const dir_t* dir) {
return (dir->attributes & DIR_ATT_FILE_TYPE_MASK) == DIR_ATT_DIRECTORY;
}
/** Directory entry is for a file or subdirectory
* \param[in] dir Pointer to a directory entry.
*
* \return true if the entry is for a normal file or subdirectory else false.
*/
static inline uint8_t DIR_IS_FILE_OR_SUBDIR(const dir_t* dir) {
return (dir->attributes & DIR_ATT_VOLUME_ID) == 0;
}
#endif // SdFatStructs_h

View file

@ -0,0 +1,74 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#include <SdFat.h>
#include <SdFatUtil.h>
#ifdef __arm__
// should use uinstd.h to define sbrk but Due causes a conflict
extern "C" char* sbrk(int incr);
#endif // __arm__
//------------------------------------------------------------------------------
/** Amount of free RAM
* \return The number of free bytes.
*/
int SdFatUtil::FreeRam() {
char top;
#ifdef __arm__
return &top - reinterpret_cast<char*>(sbrk(0));
#else // __arm__
extern char *__malloc_heap_start;
extern char *__brkval;
return __brkval ? &top - __brkval : &top - __malloc_heap_start;
#endif // __arm__
}
//------------------------------------------------------------------------------
/** %Print a string in flash memory.
*
* \param[in] pr Print object for output.
* \param[in] str Pointer to string stored in flash memory.
*/
void SdFatUtil::print_P(Print* pr, PGM_P str) {
for (uint8_t c; (c = pgm_read_byte(str)); str++) pr->write(c);
}
//------------------------------------------------------------------------------
/** %Print a string in flash memory followed by a CR/LF.
*
* \param[in] pr Print object for output.
* \param[in] str Pointer to string stored in flash memory.
*/
void SdFatUtil::println_P(Print* pr, PGM_P str) {
print_P(pr, str);
pr->println();
}
//------------------------------------------------------------------------------
/** %Print a string in flash memory to Serial.
*
* \param[in] str Pointer to string stored in flash memory.
*/
void SdFatUtil::SerialPrint_P(PGM_P str) {
print_P(SdFat::stdOut(), str);
}
//------------------------------------------------------------------------------
/** %Print a string in flash memory to Serial followed by a CR/LF.
*
* \param[in] str Pointer to string stored in flash memory.
*/
void SdFatUtil::SerialPrintln_P(PGM_P str) {
println_P(SdFat::stdOut(), str);
}

View file

@ -0,0 +1,40 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef SdFatUtil_h
#define SdFatUtil_h
/**
* \file
* \brief Useful utility functions.
*/
#include <SdFat.h>
/** Store and print a string in flash memory.*/
#define PgmPrint(x) SerialPrint_P(PSTR(x))
/** Store and print a string in flash memory followed by a CR/LF.*/
#define PgmPrintln(x) SerialPrintln_P(PSTR(x))
namespace SdFatUtil {
int FreeRam();
void print_P(Print* pr, PGM_P str);
void println_P(Print* pr, PGM_P str);
void SerialPrint_P(PGM_P str);
void SerialPrintln_P(PGM_P str);
}
using namespace SdFatUtil; // NOLINT
#endif // #define SdFatUtil_h

View file

@ -0,0 +1,227 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
/**
\mainpage Arduino %SdFat Library
<CENTER>Copyright &copy; 2012 by William Greiman
</CENTER>
\section Intro Introduction
The Arduino %SdFat Library is a minimal implementation of FAT16 and FAT32
file systems on SD flash memory cards. Standard SD and high capacity SDHC
cards are supported.
Experimental support for FAT12 can be enabled by setting FAT12_SUPPORT
nonzero in SdFatConfig.h.
The %SdFat library only supports short 8.3 names.
The main classes in %SdFat are SdFat, SdFile, \ref fstream, \ref ifstream,
and \ref ofstream.
The SdFat class maintains a volume working directories, a current working
directory, and simplifies initialization of other classes.
The SdFile class provides binary file access functions such as open(), read(),
remove(), write(), close() and sync(). This class supports access to the root
directory and subdirectories.
The \ref fstream class implements C++ iostreams for both reading and writing
text files.
The \ref ifstream class implements the C++ iostreams for reading text files.
The \ref ofstream class implements the C++ iostreams for writing text files.
The classes \ref ibufstream and \ref obufstream format and parse character
strings in memory buffers.
the classes ArduinoInStream and ArduinoOutStream provide iostream functions
for Serial, LiquidCrystal, and other devices.
The SdVolume class supports FAT16 and FAT32 partitions. Most applications
will not need to call SdVolume member function.
The Sd2Card class supports access to standard SD cards and SDHC cards. Most
applications will not need to call Sd2Card functions. The Sd2Card class can
be used for raw access to the SD card.
A number of example are provided in the %SdFat/examples folder. These were
developed to test %SdFat and illustrate its use.
%SdFat was developed for high speed data recording. %SdFat was used to
implement an audio record/play class, WaveRP, for the Adafruit Wave Shield.
This application uses special Sd2Card calls to write to contiguous files in
raw mode. These functions reduce write latency so that audio can be
recorded with the small amount of RAM in the Arduino.
\section SDcard SD\SDHC Cards
Arduinos access SD cards using the cards SPI protocol. PCs, Macs, and
most consumer devices use the 4-bit parallel SD protocol. A card that
functions well on A PC or Mac may not work well on the Arduino.
Most cards have good SPI read performance but cards vary widely in SPI
write performance. Write performance is limited by how efficiently the
card manages internal erase/remapping operations. The Arduino cannot
optimize writes to reduce erase operations because of its limit RAM.
SanDisk cards generally have good write performance. They seem to have
more internal RAM buffering than other cards and therefore can limit
the number of flash erase operations that the Arduino forces due to its
limited RAM.
\section Hardware Hardware Configuration
%SdFat was developed using an
<A HREF = "http://www.adafruit.com/"> Adafruit Industries</A>
<A HREF = "http://www.ladyada.net/make/waveshield/"> Wave Shield</A>.
The hardware interface to the SD card should not use a resistor based level
shifter. %SdFat sets the SPI bus frequency to 8 MHz which results in signal
rise times that are too slow for the edge detectors in many newer SD card
controllers when resistor voltage dividers are used.
The 5 to 3.3 V level shifter for 5 V Arduinos should be IC based like the
74HC4050N based circuit shown in the file SdLevel.png. The Adafruit Wave Shield
uses a 74AHC125N. Gravitech sells SD and MicroSD Card Adapters based on the
74LCX245.
If you are using a resistor based level shifter and are having problems try
setting the SPI bus frequency to 4 MHz. This can be done by using
card.init(SPI_HALF_SPEED) to initialize the SD card.
\section comment Bugs and Comments
If you wish to report bugs or have comments, send email to fat16lib@sbcglobal.net.
\section SdFatClass SdFat Usage
%SdFat uses a slightly restricted form of short names.
Only printable ASCII characters are supported. No characters with code point
values greater than 127 are allowed. Space is not allowed even though space
was allowed in the API of early versions of DOS.
Short names are limited to 8 characters followed by an optional period (.)
and extension of up to 3 characters. The characters may be any combination
of letters and digits. The following special characters are also allowed:
$ % ' - _ @ ~ ` ! ( ) { } ^ # &
Short names are always converted to upper case and their original case
value is lost.
\note
The Arduino Print class uses character
at a time writes so it was necessary to use a \link SdFile::sync() sync() \endlink
function to control when data is written to the SD card.
\par
An application which writes to a file using print(), println() or
\link SdFile::write write() \endlink must call \link SdFile::sync() sync() \endlink
at the appropriate time to force data and directory information to be written
to the SD Card. Data and directory information are also written to the SD card
when \link SdFile::close() close() \endlink is called.
\par
Applications must use care calling \link SdFile::sync() sync() \endlink
since 2048 bytes of I/O is required to update file and
directory information. This includes writing the current data block, reading
the block that contains the directory entry for update, writing the directory
block back and reading back the current data block.
It is possible to open a file with two or more instances of SdFile. A file may
be corrupted if data is written to the file by more than one instance of SdFile.
\section HowTo How to format SD Cards as FAT Volumes
You should use a freshly formatted SD card for best performance. FAT
file systems become slower if many files have been created and deleted.
This is because the directory entry for a deleted file is marked as deleted,
but is not deleted. When a new file is created, these entries must be scanned
before creating the file, a flaw in the FAT design. Also files can become
fragmented which causes reads and writes to be slower.
A formatter sketch, SdFormatter.pde, is included in the
%SdFat/examples/SdFormatter directory. This sketch attempts to
emulate SD Association's SDFormatter.
The best way to restore an SD card's format on a PC is to use SDFormatter
which can be downloaded from:
http://www.sdcard.org/consumers/formatter/
SDFormatter aligns flash erase boundaries with file
system structures which reduces write latency and file system overhead.
SDFormatter does not have an option for FAT type so it may format
small cards as FAT12.
After the MBR is restored by SDFormatter you may need to reformat small
cards that have been formatted FAT12 to force the volume type to be FAT16.
If you reformat the SD card with an OS utility, choose a cluster size that
will result in:
4084 < CountOfClusters && CountOfClusters < 65525
The volume will then be FAT16.
If you are formatting an SD card on OS X or Linux, be sure to use the first
partition. Format this partition with a cluster count in above range for FAT16.
SDHC cards should be formatted FAT32 with a cluster size of 32 KB.
Microsoft operating systems support removable media formatted with a
Master Boot Record, MBR, or formatted as a super floppy with a FAT Boot Sector
in block zero.
Microsoft operating systems expect MBR formatted removable media
to have only one partition. The first partition should be used.
Microsoft operating systems do not support partitioning SD flash cards.
If you erase an SD card with a program like KillDisk, Most versions of
Windows will format the card as a super floppy.
\section References References
Adafruit Industries:
http://www.adafruit.com/
http://www.ladyada.net/make/waveshield/
The Arduino site:
http://www.arduino.cc/
For more information about FAT file systems see:
http://www.microsoft.com/whdc/system/platform/firmware/fatgen.mspx
For information about using SD cards as SPI devices see:
http://www.sdcard.org/developers/tech/sdcard/pls/Simplified_Physical_Layer_Spec.pdf
The ATmega328 datasheet:
http://www.atmel.com/dyn/resources/prod_documents/doc8161.pdf
*/

View file

@ -0,0 +1,83 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#include <SdFile.h>
/** Create a file object and open it in the current working directory.
*
* \param[in] path A path with a valid 8.3 DOS name for a file to be opened.
*
* \param[in] oflag Values for \a oflag are constructed by a bitwise-inclusive
* OR of open flags. see SdBaseFile::open(SdBaseFile*, const char*, uint8_t).
*/
SdFile::SdFile(const char* path, uint8_t oflag) : SdBaseFile(path, oflag) {
}
//------------------------------------------------------------------------------
/** Write data to an open file.
*
* \note Data is moved to the cache but may not be written to the
* storage device until sync() is called.
*
* \param[in] buf Pointer to the location of the data to be written.
*
* \param[in] nbyte Number of bytes to write.
*
* \return For success write() returns the number of bytes written, always
* \a nbyte. If an error occurs, write() returns -1. Possible errors
* include write() is called before a file has been opened, write is called
* for a read-only file, device is full, a corrupt file system or an I/O error.
*
*/
int SdFile::write(const void* buf, size_t nbyte) {
return SdBaseFile::write(buf, nbyte);
}
//------------------------------------------------------------------------------
/** Write a byte to a file. Required by the Arduino Print class.
* \param[in] b the byte to be written.
* Use getWriteError to check for errors.
* \return 1 for success and 0 for failure.
*/
size_t SdFile::write(uint8_t b) {
return SdBaseFile::write(&b, 1) == 1 ? 1 : 0;
}
//------------------------------------------------------------------------------
/** Write a string to a file. Used by the Arduino Print class.
* \param[in] str Pointer to the string.
* Use getWriteError to check for errors.
* \return count of characters written for success or -1 for failure.
*/
int SdFile::write(const char* str) {
return SdBaseFile::write(str, strlen(str));
}
//------------------------------------------------------------------------------
/** Write a PROGMEM string to a file.
* \param[in] str Pointer to the PROGMEM string.
* Use getWriteError to check for errors.
*/
void SdFile::write_P(PGM_P str) {
for (uint8_t c; (c = pgm_read_byte(str)); str++) write(c);
}
//------------------------------------------------------------------------------
/** Write a PROGMEM string followed by CR/LF to a file.
* \param[in] str Pointer to the PROGMEM string.
* Use getWriteError to check for errors.
*/
void SdFile::writeln_P(PGM_P str) {
write_P(str);
write_P(PSTR("\r\n"));
}

View file

@ -0,0 +1,49 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
/**
* \file
* \brief SdFile class
*/
#include <SdBaseFile.h>
#ifndef SdFile_h
#define SdFile_h
//------------------------------------------------------------------------------
/**
* \class SdFile
* \brief SdBaseFile with Print.
*/
class SdFile : public SdBaseFile, public Print {
public:
SdFile() {}
SdFile(const char* name, uint8_t oflag);
#if DESTRUCTOR_CLOSES_FILE
~SdFile() {}
#endif // DESTRUCTOR_CLOSES_FILE
/** \return value of writeError */
bool getWriteError() {return SdBaseFile::getWriteError();}
/** Set writeError to zero */
void clearWriteError() {SdBaseFile::clearWriteError();}
size_t write(uint8_t b);
int write(const char* str);
int write(const void* buf, size_t nbyte);
void write_P(PGM_P str);
void writeln_P(PGM_P str);
};
#endif // SdFile_h

View file

@ -0,0 +1,277 @@
/* Arduino Sd2Card Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino Sd2Card Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino Sd2Card Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef SdInfo_h
#define SdInfo_h
#include <stdint.h>
// Based on the document:
//
// SD Specifications
// Part 1
// Physical Layer
// Simplified Specification
// Version 3.01
// May 18, 2010
//
// http://www.sdcard.org/developers/tech/sdcard/pls/simplified_specs
//------------------------------------------------------------------------------
// SD card commands
/** GO_IDLE_STATE - init card in spi mode if CS low */
uint8_t const CMD0 = 0X00;
/** SEND_IF_COND - verify SD Memory Card interface operating condition.*/
uint8_t const CMD8 = 0X08;
/** SEND_CSD - read the Card Specific Data (CSD register) */
uint8_t const CMD9 = 0X09;
/** SEND_CID - read the card identification information (CID register) */
uint8_t const CMD10 = 0X0A;
/** STOP_TRANSMISSION - end multiple block read sequence */
uint8_t const CMD12 = 0X0C;
/** SEND_STATUS - read the card status register */
uint8_t const CMD13 = 0X0D;
/** READ_SINGLE_BLOCK - read a single data block from the card */
uint8_t const CMD17 = 0X11;
/** READ_MULTIPLE_BLOCK - read a multiple data blocks from the card */
uint8_t const CMD18 = 0X12;
/** WRITE_BLOCK - write a single data block to the card */
uint8_t const CMD24 = 0X18;
/** WRITE_MULTIPLE_BLOCK - write blocks of data until a STOP_TRANSMISSION */
uint8_t const CMD25 = 0X19;
/** ERASE_WR_BLK_START - sets the address of the first block to be erased */
uint8_t const CMD32 = 0X20;
/** ERASE_WR_BLK_END - sets the address of the last block of the continuous
range to be erased*/
uint8_t const CMD33 = 0X21;
/** ERASE - erase all previously selected blocks */
uint8_t const CMD38 = 0X26;
/** APP_CMD - escape for application specific command */
uint8_t const CMD55 = 0X37;
/** READ_OCR - read the OCR register of a card */
uint8_t const CMD58 = 0X3A;
/** CRC_ON_OFF - enable or disable CRC checking */
uint8_t const CMD59 = 0X3B;
/** SET_WR_BLK_ERASE_COUNT - Set the number of write blocks to be
pre-erased before writing */
uint8_t const ACMD23 = 0X17;
/** SD_SEND_OP_COMD - Sends host capacity support information and
activates the card's initialization process */
uint8_t const ACMD41 = 0X29;
//------------------------------------------------------------------------------
/** status for card in the ready state */
uint8_t const R1_READY_STATE = 0X00;
/** status for card in the idle state */
uint8_t const R1_IDLE_STATE = 0X01;
/** status bit for illegal command */
uint8_t const R1_ILLEGAL_COMMAND = 0X04;
/** start data token for read or write single block*/
uint8_t const DATA_START_BLOCK = 0XFE;
/** stop token for write multiple blocks*/
uint8_t const STOP_TRAN_TOKEN = 0XFD;
/** start data token for write multiple blocks*/
uint8_t const WRITE_MULTIPLE_TOKEN = 0XFC;
/** mask for data response tokens after a write block operation */
uint8_t const DATA_RES_MASK = 0X1F;
/** write data accepted token */
uint8_t const DATA_RES_ACCEPTED = 0X05;
//------------------------------------------------------------------------------
/** Card IDentification (CID) register */
typedef struct CID {
// byte 0
/** Manufacturer ID */
unsigned char mid;
// byte 1-2
/** OEM/Application ID */
char oid[2];
// byte 3-7
/** Product name */
char pnm[5];
// byte 8
/** Product revision least significant digit */
unsigned char prv_m : 4;
/** Product revision most significant digit */
unsigned char prv_n : 4;
// byte 9-12
/** Product serial number */
uint32_t psn;
// byte 13
/** Manufacturing date year low digit */
unsigned char mdt_year_high : 4;
/** not used */
unsigned char reserved : 4;
// byte 14
/** Manufacturing date month */
unsigned char mdt_month : 4;
/** Manufacturing date year low digit */
unsigned char mdt_year_low :4;
// byte 15
/** not used always 1 */
unsigned char always1 : 1;
/** CRC7 checksum */
unsigned char crc : 7;
}__attribute__((packed)) cid_t;
//------------------------------------------------------------------------------
/** CSD for version 1.00 cards */
typedef struct CSDV1 {
// byte 0
unsigned char reserved1 : 6;
unsigned char csd_ver : 2;
// byte 1
unsigned char taac;
// byte 2
unsigned char nsac;
// byte 3
unsigned char tran_speed;
// byte 4
unsigned char ccc_high;
// byte 5
unsigned char read_bl_len : 4;
unsigned char ccc_low : 4;
// byte 6
unsigned char c_size_high : 2;
unsigned char reserved2 : 2;
unsigned char dsr_imp : 1;
unsigned char read_blk_misalign :1;
unsigned char write_blk_misalign : 1;
unsigned char read_bl_partial : 1;
// byte 7
unsigned char c_size_mid;
// byte 8
unsigned char vdd_r_curr_max : 3;
unsigned char vdd_r_curr_min : 3;
unsigned char c_size_low :2;
// byte 9
unsigned char c_size_mult_high : 2;
unsigned char vdd_w_cur_max : 3;
unsigned char vdd_w_curr_min : 3;
// byte 10
unsigned char sector_size_high : 6;
unsigned char erase_blk_en : 1;
unsigned char c_size_mult_low : 1;
// byte 11
unsigned char wp_grp_size : 7;
unsigned char sector_size_low : 1;
// byte 12
unsigned char write_bl_len_high : 2;
unsigned char r2w_factor : 3;
unsigned char reserved3 : 2;
unsigned char wp_grp_enable : 1;
// byte 13
unsigned char reserved4 : 5;
unsigned char write_partial : 1;
unsigned char write_bl_len_low : 2;
// byte 14
unsigned char reserved5: 2;
unsigned char file_format : 2;
unsigned char tmp_write_protect : 1;
unsigned char perm_write_protect : 1;
unsigned char copy : 1;
/** Indicates the file format on the card */
unsigned char file_format_grp : 1;
// byte 15
unsigned char always1 : 1;
unsigned char crc : 7;
}__attribute__((packed)) csd1_t;
//------------------------------------------------------------------------------
/** CSD for version 2.00 cards */
typedef struct CSDV2 {
// byte 0
unsigned char reserved1 : 6;
unsigned char csd_ver : 2;
// byte 1
/** fixed to 0X0E */
unsigned char taac;
// byte 2
/** fixed to 0 */
unsigned char nsac;
// byte 3
unsigned char tran_speed;
// byte 4
unsigned char ccc_high;
// byte 5
/** This field is fixed to 9h, which indicates READ_BL_LEN=512 Byte */
unsigned char read_bl_len : 4;
unsigned char ccc_low : 4;
// byte 6
/** not used */
unsigned char reserved2 : 4;
unsigned char dsr_imp : 1;
/** fixed to 0 */
unsigned char read_blk_misalign :1;
/** fixed to 0 */
unsigned char write_blk_misalign : 1;
/** fixed to 0 - no partial read */
unsigned char read_bl_partial : 1;
// byte 7
/** high part of card size */
unsigned char c_size_high : 6;
/** not used */
unsigned char reserved3 : 2;
// byte 8
/** middle part of card size */
unsigned char c_size_mid;
// byte 9
/** low part of card size */
unsigned char c_size_low;
// byte 10
/** sector size is fixed at 64 KB */
unsigned char sector_size_high : 6;
/** fixed to 1 - erase single is supported */
unsigned char erase_blk_en : 1;
/** not used */
unsigned char reserved4 : 1;
// byte 11
unsigned char wp_grp_size : 7;
/** sector size is fixed at 64 KB */
unsigned char sector_size_low : 1;
// byte 12
/** write_bl_len fixed for 512 byte blocks */
unsigned char write_bl_len_high : 2;
/** fixed value of 2 */
unsigned char r2w_factor : 3;
/** not used */
unsigned char reserved5 : 2;
/** fixed value of 0 - no write protect groups */
unsigned char wp_grp_enable : 1;
// byte 13
unsigned char reserved6 : 5;
/** always zero - no partial block read*/
unsigned char write_partial : 1;
/** write_bl_len fixed for 512 byte blocks */
unsigned char write_bl_len_low : 2;
// byte 14
unsigned char reserved7: 2;
/** Do not use always 0 */
unsigned char file_format : 2;
unsigned char tmp_write_protect : 1;
unsigned char perm_write_protect : 1;
unsigned char copy : 1;
/** Do not use always 0 */
unsigned char file_format_grp : 1;
// byte 15
/** not used always 1 */
unsigned char always1 : 1;
/** checksum */
unsigned char crc : 7;
}__attribute__((packed)) csd2_t;
//------------------------------------------------------------------------------
/** union of old and new style CSD register */
union csd_t {
csd1_t v1;
csd2_t v2;
};
#endif // SdInfo_h

View file

@ -0,0 +1,151 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#include <SdFat.h>
//==============================================================================
/// @cond SHOW_PROTECTED
int16_t SdStreamBase::getch() {
uint8_t c;
int8_t s = read(&c, 1);
if (s != 1) {
if (s < 0) {
setstate(badbit);
} else {
setstate(eofbit);
}
return -1;
}
if (c != '\r' || (getmode() & ios::binary)) return c;
s = read(&c, 1);
if (s == 1 && c == '\n') return c;
if (s == 1) seekCur(-1);
return '\r';
}
//------------------------------------------------------------------------------
void SdStreamBase::open(const char* path, ios::openmode mode) {
uint8_t flags;
switch (mode & (app | in | out | trunc)) {
case app | in:
case app | in | out:
flags = O_RDWR | O_APPEND | O_CREAT;
break;
case app:
case app | out:
flags = O_WRITE | O_APPEND | O_CREAT;
break;
case in:
flags = O_READ;
break;
case in | out:
flags = O_RDWR;
break;
case in | out | trunc:
flags = O_RDWR | O_TRUNC | O_CREAT;
break;
case out:
case out | trunc:
flags = O_WRITE | O_TRUNC | O_CREAT;
break;
default:
goto fail;
}
if (mode & ios::ate) flags |= O_AT_END;
if (!SdBaseFile::open(path, flags)) goto fail;
setmode(mode);
clear();
return;
fail:
SdBaseFile::close();
setstate(failbit);
return;
}
//------------------------------------------------------------------------------
void SdStreamBase::putch(char c) {
if (c == '\n' && !(getmode() & ios::binary)) {
write('\r');
}
write(c);
if (writeError) setstate(badbit);
}
//------------------------------------------------------------------------------
void SdStreamBase::putstr(const char* str) {
size_t n = 0;
while (1) {
char c = str[n];
if (c == '\0' || (c == '\n' && !(getmode() & ios::binary))) {
if (n > 0) write(str, n);
if (c == '\0') break;
write('\r');
str += n;
n = 0;
}
n++;
}
if (writeError) setstate(badbit);
}
//------------------------------------------------------------------------------
/** Internal do not use
* \param[in] off
* \param[in] way
*/
bool SdStreamBase::seekoff(off_type off, seekdir way) {
pos_type pos;
switch (way) {
case beg:
pos = off;
break;
case cur:
pos = curPosition() + off;
break;
case end:
pos = fileSize() + off;
break;
default:
return false;
}
return seekpos(pos);
}
//------------------------------------------------------------------------------
/** Internal do not use
* \param[in] pos
*/
bool SdStreamBase::seekpos(pos_type pos) {
return seekSet(pos);
}
//------------------------------------------------------------------------------
int SdStreamBase::write(const void* buf, size_t n) {
return SdBaseFile::write(buf, n);
}
//------------------------------------------------------------------------------
void SdStreamBase::write(char c) {
write(&c, 1);
}
/// @endcond

View file

@ -0,0 +1,263 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef SdStream_h
#define SdStream_h
/**
* \file
* \brief \ref fstream, \ref ifstream, and \ref ofstream classes
*/
#include <SdBaseFile.h>
#include <iostream.h>
//==============================================================================
/**
* \class SdStreamBase
* \brief Base class for SD streams
*/
class SdStreamBase : protected SdBaseFile, virtual public ios {
protected:
/// @cond SHOW_PROTECTED
int16_t getch();
void putch(char c);
void putstr(const char *str);
void open(const char* path, ios::openmode mode);
/** Internal do not use
* \return mode
*/
ios::openmode getmode() {return mode_;}
/** Internal do not use
* \param[in] mode
*/
void setmode(ios::openmode mode) {mode_ = mode;}
bool seekoff(off_type off, seekdir way);
bool seekpos(pos_type pos);
int write(const void* buf, size_t n);
void write(char c);
/// @endcond
private:
ios::openmode mode_;
};
//==============================================================================
/**
* \class fstream
* \brief SD file input/output stream.
*/
class fstream : public iostream, SdStreamBase {
public:
using iostream::peek;
fstream() {}
/** Constructor with open
*
* \param[in] path path to open
* \param[in] mode open mode
*/
explicit fstream(const char* path, openmode mode = in | out) {
open(path, mode);
}
#if DESTRUCTOR_CLOSES_FILE
~fstream() {}
#endif // DESTRUCTOR_CLOSES_FILE
/** Clear state and writeError
* \param[in] state new state for stream
*/
void clear(iostate state = goodbit) {
ios::clear(state);
SdBaseFile::writeError = false;
}
/** Close a file and force cached data and directory information
* to be written to the storage device.
*/
void close() {SdBaseFile::close();}
/** Open a fstream
* \param[in] path file to open
* \param[in] mode open mode
*
* Valid open modes are (at end, ios::ate, and/or ios::binary may be added):
*
* ios::in - Open file for reading.
*
* ios::out or ios::out | ios::trunc - Truncate to 0 length, if existent,
* or create a file for writing only.
*
* ios::app or ios::out | ios::app - Append; open or create file for
* writing at end-of-file.
*
* ios::in | ios::out - Open file for update (reading and writing).
*
* ios::in | ios::out | ios::trunc - Truncate to zero length, if existent,
* or create file for update.
*
* ios::in | ios::app or ios::in | ios::out | ios::app - Append; open or
* create text file for update, writing at end of file.
*/
void open(const char* path, openmode mode = in | out) {
SdStreamBase::open(path, mode);
}
/** \return True if stream is open else false. */
bool is_open () {return SdBaseFile::isOpen();}
protected:
/// @cond SHOW_PROTECTED
/** Internal - do not use
* \return
*/
int16_t getch() {return SdStreamBase::getch();}
/** Internal - do not use
* \param[out] pos
*/
void getpos(FatPos_t* pos) {SdBaseFile::getpos(pos);}
/** Internal - do not use
* \param[in] c
*/
void putch(char c) {SdStreamBase::putch(c);}
/** Internal - do not use
* \param[in] str
*/
void putstr(const char *str) {SdStreamBase::putstr(str);}
/** Internal - do not use
* \param[in] pos
*/
bool seekoff(off_type off, seekdir way) {
return SdStreamBase::seekoff(off, way);
}
bool seekpos(pos_type pos) {return SdStreamBase::seekpos(pos);}
void setpos(FatPos_t* pos) {SdBaseFile::setpos(pos);}
bool sync() {return SdStreamBase::sync();}
pos_type tellpos() {return SdStreamBase::curPosition();}
/// @endcond
};
//==============================================================================
/**
* \class ifstream
* \brief SD file input stream.
*/
class ifstream : public istream, SdStreamBase {
public:
using istream::peek;
ifstream() {}
/** Constructor with open
* \param[in] path file to open
* \param[in] mode open mode
*/
explicit ifstream(const char* path, openmode mode = in) {
open(path, mode);
}
#if DESTRUCTOR_CLOSES_FILE
~ifstream() {}
#endif // DESTRUCTOR_CLOSES_FILE
/** Close a file and force cached data and directory information
* to be written to the storage device.
*/
void close() {SdBaseFile::close();}
/** \return True if stream is open else false. */
bool is_open() {return SdBaseFile::isOpen();}
/** Open an ifstream
* \param[in] path file to open
* \param[in] mode open mode
*
* \a mode See fstream::open() for valid modes.
*/
void open(const char* path, openmode mode = in) {
SdStreamBase::open(path, mode | in);
}
protected:
/// @cond SHOW_PROTECTED
/** Internal - do not use
* \return
*/
int16_t getch() {return SdStreamBase::getch();}
/** Internal - do not use
* \param[out] pos
*/
void getpos(FatPos_t* pos) {SdBaseFile::getpos(pos);}
/** Internal - do not use
* \param[in] pos
*/
bool seekoff(off_type off, seekdir way) {
return SdStreamBase::seekoff(off, way);
}
bool seekpos(pos_type pos) {return SdStreamBase::seekpos(pos);}
void setpos(FatPos_t* pos) {SdBaseFile::setpos(pos);}
pos_type tellpos() {return SdStreamBase::curPosition();}
/// @endcond
};
//==============================================================================
/**
* \class ofstream
* \brief SD card output stream.
*/
class ofstream : public ostream, SdStreamBase {
public:
ofstream() {}
/** Constructor with open
* \param[in] path file to open
* \param[in] mode open mode
*/
explicit ofstream(const char* path, ios::openmode mode = out) {
open(path, mode);
}
#if DESTRUCTOR_CLOSES_FILE
~ofstream() {}
#endif // DESTRUCTOR_CLOSES_FILE
/** Clear state and writeError
* \param[in] state new state for stream
*/
void clear(iostate state = goodbit) {
ios::clear(state);
SdBaseFile::writeError = false;
}
/** Close a file and force cached data and directory information
* to be written to the storage device.
*/
void close() {SdBaseFile::close();}
/** Open an ofstream
* \param[in] path file to open
* \param[in] mode open mode
*
* \a mode See fstream::open() for valid modes.
*/
void open(const char* path, openmode mode = out) {
SdStreamBase::open(path, mode | out);
}
/** \return True if stream is open else false. */
bool is_open() {return SdBaseFile::isOpen();}
protected:
/// @cond SHOW_PROTECTED
/**
* Internal do not use
* \param[in] c
*/
void putch(char c) {SdStreamBase::putch(c);}
void putstr(const char* str) {SdStreamBase::putstr(str);}
bool seekoff(off_type off, seekdir way) {
return SdStreamBase::seekoff(off, way);
}
bool seekpos(pos_type pos) {return SdStreamBase::seekpos(pos);}
/**
* Internal do not use
* \param[in] b
*/
bool sync() {return SdStreamBase::sync();}
pos_type tellpos() {return SdStreamBase::curPosition();}
/// @endcond
};
//------------------------------------------------------------------------------
#endif // SdStream_h

View file

@ -0,0 +1,599 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#include <SdVolume.h>
// macro for debug
#define DBG_FAIL_MACRO // Serial.print(__FILE__);Serial.println(__LINE__)
//------------------------------------------------------------------------------
#if !USE_MULTIPLE_CARDS
// raw block cache
cache_t SdVolume::cacheBuffer_; // 512 byte cache for Sd2Card
uint32_t SdVolume::cacheBlockNumber_; // current block number
uint8_t SdVolume::cacheStatus_; // status of cache block
uint32_t SdVolume::cacheFatOffset_; // offset for mirrored FAT
#if USE_SEPARATE_FAT_CACHE
cache_t SdVolume::cacheFatBuffer_; // 512 byte cache for FAT
uint32_t SdVolume::cacheFatBlockNumber_; // current Fat block number
uint8_t SdVolume::cacheFatStatus_; // status of cache Fatblock
#endif // USE_SEPARATE_FAT_CACHE
Sd2Card* SdVolume::sdCard_; // pointer to SD card object
#endif // USE_MULTIPLE_CARDS
//------------------------------------------------------------------------------
// find a contiguous group of clusters
bool SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) {
// start of group
uint32_t bgnCluster;
// end of group
uint32_t endCluster;
// last cluster of FAT
uint32_t fatEnd = clusterCount_ + 1;
// flag to save place to start next search
bool setStart;
// set search start cluster
if (*curCluster) {
// try to make file contiguous
bgnCluster = *curCluster + 1;
// don't save new start location
setStart = false;
} else {
// start at likely place for free cluster
bgnCluster = allocSearchStart_;
// save next search start if one cluster
setStart = count == 1;
}
// end of group
endCluster = bgnCluster;
// search the FAT for free clusters
for (uint32_t n = 0;; n++, endCluster++) {
// can't find space checked all clusters
if (n >= clusterCount_) {
DBG_FAIL_MACRO;
goto fail;
}
// past end - start from beginning of FAT
if (endCluster > fatEnd) {
bgnCluster = endCluster = 2;
}
uint32_t f;
if (!fatGet(endCluster, &f)) {
DBG_FAIL_MACRO;
goto fail;
}
if (f != 0) {
// cluster in use try next cluster as bgnCluster
bgnCluster = endCluster + 1;
} else if ((endCluster - bgnCluster + 1) == count) {
// done - found space
break;
}
}
// mark end of chain
if (!fatPutEOC(endCluster)) {
DBG_FAIL_MACRO;
goto fail;
}
// link clusters
while (endCluster > bgnCluster) {
if (!fatPut(endCluster - 1, endCluster)) {
DBG_FAIL_MACRO;
goto fail;
}
endCluster--;
}
if (*curCluster != 0) {
// connect chains
if (!fatPut(*curCluster, bgnCluster)) {
DBG_FAIL_MACRO;
goto fail;
}
}
// return first cluster number to caller
*curCluster = bgnCluster;
// remember possible next free cluster
if (setStart) allocSearchStart_ = bgnCluster + 1;
return true;
fail:
return false;
}
//==============================================================================
// cache functions
#if USE_SEPARATE_FAT_CACHE
//------------------------------------------------------------------------------
cache_t* SdVolume::cacheFetch(uint32_t blockNumber, uint8_t options) {
return cacheFetchData(blockNumber, options);
}
//------------------------------------------------------------------------------
cache_t* SdVolume::cacheFetchData(uint32_t blockNumber, uint8_t options) {
if (cacheBlockNumber_ != blockNumber) {
if (!cacheWriteData()) {
DBG_FAIL_MACRO;
goto fail;
}
if (!(options & CACHE_OPTION_NO_READ)) {
if (!sdCard_->readBlock(blockNumber, cacheBuffer_.data)) {
DBG_FAIL_MACRO;
goto fail;
}
}
cacheStatus_ = 0;
cacheBlockNumber_ = blockNumber;
}
cacheStatus_ |= options & CACHE_STATUS_MASK;
return &cacheBuffer_;
fail:
return 0;
}
//------------------------------------------------------------------------------
cache_t* SdVolume::cacheFetchFat(uint32_t blockNumber, uint8_t options) {
if (cacheFatBlockNumber_ != blockNumber) {
if (!cacheWriteFat()) {
DBG_FAIL_MACRO;
goto fail;
}
if (!(options & CACHE_OPTION_NO_READ)) {
if (!sdCard_->readBlock(blockNumber, cacheFatBuffer_.data)) {
DBG_FAIL_MACRO;
goto fail;
}
}
cacheFatStatus_ = 0;
cacheFatBlockNumber_ = blockNumber;
}
cacheFatStatus_ |= options & CACHE_STATUS_MASK;
return &cacheFatBuffer_;
fail:
return 0;
}
//------------------------------------------------------------------------------
bool SdVolume::cacheSync() {
return cacheWriteData() && cacheWriteFat();
}
//------------------------------------------------------------------------------
bool SdVolume::cacheWriteData() {
if (cacheStatus_ & CACHE_STATUS_DIRTY) {
if (!sdCard_->writeBlock(cacheBlockNumber_, cacheBuffer_.data)) {
DBG_FAIL_MACRO;
goto fail;
}
cacheStatus_ &= ~CACHE_STATUS_DIRTY;
}
return true;
fail:
return false;
}
//------------------------------------------------------------------------------
bool SdVolume::cacheWriteFat() {
if (cacheFatStatus_ & CACHE_STATUS_DIRTY) {
if (!sdCard_->writeBlock(cacheFatBlockNumber_, cacheFatBuffer_.data)) {
DBG_FAIL_MACRO;
goto fail;
}
// mirror second FAT
if (cacheFatOffset_) {
uint32_t lbn = cacheFatBlockNumber_ + cacheFatOffset_;
if (!sdCard_->writeBlock(lbn, cacheFatBuffer_.data)) {
DBG_FAIL_MACRO;
goto fail;
}
}
cacheFatStatus_ &= ~CACHE_STATUS_DIRTY;
}
return true;
fail:
return false;
}
#else // USE_SEPARATE_FAT_CACHE
//------------------------------------------------------------------------------
cache_t* SdVolume::cacheFetch(uint32_t blockNumber, uint8_t options) {
if (cacheBlockNumber_ != blockNumber) {
if (!cacheSync()) {
DBG_FAIL_MACRO;
goto fail;
}
if (!(options & CACHE_OPTION_NO_READ)) {
if (!sdCard_->readBlock(blockNumber, cacheBuffer_.data)) {
DBG_FAIL_MACRO;
goto fail;
}
}
cacheStatus_ = 0;
cacheBlockNumber_ = blockNumber;
}
cacheStatus_ |= options & CACHE_STATUS_MASK;
return &cacheBuffer_;
fail:
return 0;
}
//------------------------------------------------------------------------------
cache_t* SdVolume::cacheFetchFat(uint32_t blockNumber, uint8_t options) {
return cacheFetch(blockNumber, options | CACHE_STATUS_FAT_BLOCK);
}
//------------------------------------------------------------------------------
bool SdVolume::cacheSync() {
if (cacheStatus_ & CACHE_STATUS_DIRTY) {
if (!sdCard_->writeBlock(cacheBlockNumber_, cacheBuffer_.data)) {
DBG_FAIL_MACRO;
goto fail;
}
// mirror second FAT
if ((cacheStatus_ & CACHE_STATUS_FAT_BLOCK) && cacheFatOffset_) {
uint32_t lbn = cacheBlockNumber_ + cacheFatOffset_;
if (!sdCard_->writeBlock(lbn, cacheBuffer_.data)) {
DBG_FAIL_MACRO;
goto fail;
}
}
cacheStatus_ &= ~CACHE_STATUS_DIRTY;
}
return true;
fail:
return false;
}
//------------------------------------------------------------------------------
bool SdVolume::cacheWriteData() {
return cacheSync();
}
#endif // USE_SEPARATE_FAT_CACHE
//------------------------------------------------------------------------------
void SdVolume::cacheInvalidate() {
cacheBlockNumber_ = 0XFFFFFFFF;
cacheStatus_ = 0;
}
//==============================================================================
//------------------------------------------------------------------------------
uint32_t SdVolume::clusterStartBlock(uint32_t cluster) const {
return dataStartBlock_ + ((cluster - 2)*blocksPerCluster_);
}
//------------------------------------------------------------------------------
// Fetch a FAT entry
bool SdVolume::fatGet(uint32_t cluster, uint32_t* value) {
uint32_t lba;
cache_t* pc;
// error if reserved cluster of beyond FAT
if (cluster < 2 || cluster > (clusterCount_ + 1)) {
DBG_FAIL_MACRO;
goto fail;
}
if (FAT12_SUPPORT && fatType_ == 12) {
uint16_t index = cluster;
index += index >> 1;
lba = fatStartBlock_ + (index >> 9);
pc = cacheFetchFat(lba, CACHE_FOR_READ);
if (!pc) {
DBG_FAIL_MACRO;
goto fail;
}
index &= 0X1FF;
uint16_t tmp = pc->data[index];
index++;
if (index == 512) {
pc = cacheFetchFat(lba + 1, CACHE_FOR_READ);
if (!pc) {
DBG_FAIL_MACRO;
goto fail;
}
index = 0;
}
tmp |= pc->data[index] << 8;
*value = cluster & 1 ? tmp >> 4 : tmp & 0XFFF;
return true;
}
if (fatType_ == 16) {
lba = fatStartBlock_ + (cluster >> 8);
} else if (fatType_ == 32) {
lba = fatStartBlock_ + (cluster >> 7);
} else {
DBG_FAIL_MACRO;
goto fail;
}
pc = cacheFetchFat(lba, CACHE_FOR_READ);
if (!pc) {
DBG_FAIL_MACRO;
goto fail;
}
if (fatType_ == 16) {
*value = pc->fat16[cluster & 0XFF];
} else {
*value = pc->fat32[cluster & 0X7F] & FAT32MASK;
}
return true;
fail:
return false;
}
//------------------------------------------------------------------------------
// Store a FAT entry
bool SdVolume::fatPut(uint32_t cluster, uint32_t value) {
uint32_t lba;
cache_t* pc;
// error if reserved cluster of beyond FAT
if (cluster < 2 || cluster > (clusterCount_ + 1)) {
DBG_FAIL_MACRO;
goto fail;
}
if (FAT12_SUPPORT && fatType_ == 12) {
uint16_t index = cluster;
index += index >> 1;
lba = fatStartBlock_ + (index >> 9);
pc = cacheFetchFat(lba, CACHE_FOR_WRITE);
if (!pc) {
DBG_FAIL_MACRO;
goto fail;
}
index &= 0X1FF;
uint8_t tmp = value;
if (cluster & 1) {
tmp = (pc->data[index] & 0XF) | tmp << 4;
}
pc->data[index] = tmp;
index++;
if (index == 512) {
lba++;
index = 0;
pc = cacheFetchFat(lba, CACHE_FOR_WRITE);
if (!pc) {
DBG_FAIL_MACRO;
goto fail;
}
}
tmp = value >> 4;
if (!(cluster & 1)) {
tmp = ((pc->data[index] & 0XF0)) | tmp >> 4;
}
pc->data[index] = tmp;
return true;
}
if (fatType_ == 16) {
lba = fatStartBlock_ + (cluster >> 8);
} else if (fatType_ == 32) {
lba = fatStartBlock_ + (cluster >> 7);
} else {
DBG_FAIL_MACRO;
goto fail;
}
pc = cacheFetchFat(lba, CACHE_FOR_WRITE);
if (!pc) {
DBG_FAIL_MACRO;
goto fail;
}
// store entry
if (fatType_ == 16) {
pc->fat16[cluster & 0XFF] = value;
} else {
pc->fat32[cluster & 0X7F] = value;
}
return true;
fail:
return false;
}
//------------------------------------------------------------------------------
// free a cluster chain
bool SdVolume::freeChain(uint32_t cluster) {
uint32_t next;
// clear free cluster location
allocSearchStart_ = 2;
do {
if (!fatGet(cluster, &next)) {
DBG_FAIL_MACRO;
goto fail;
}
// free cluster
if (!fatPut(cluster, 0)) {
DBG_FAIL_MACRO;
goto fail;
}
cluster = next;
} while (!isEOC(cluster));
return true;
fail:
return false;
}
//------------------------------------------------------------------------------
/** Volume free space in clusters.
*
* \return Count of free clusters for success or -1 if an error occurs.
*/
int32_t SdVolume::freeClusterCount() {
uint32_t free = 0;
uint32_t lba;
uint32_t todo = clusterCount_ + 2;
uint16_t n;
if (FAT12_SUPPORT && fatType_ == 12) {
for (unsigned i = 2; i < todo; i++) {
uint32_t c;
if (!fatGet(i, &c)) {
DBG_FAIL_MACRO;
goto fail;
}
if (c == 0) free++;
}
} else if (fatType_ == 16 || fatType_ == 32) {
lba = fatStartBlock_;
while (todo) {
cache_t* pc = cacheFetchFat(lba++, CACHE_FOR_READ);
if (!pc) {
DBG_FAIL_MACRO;
goto fail;
}
n = fatType_ == 16 ? 256 : 128;
if (todo < n) n = todo;
if (fatType_ == 16) {
for (uint16_t i = 0; i < n; i++) {
if (pc->fat16[i] == 0) free++;
}
} else {
for (uint16_t i = 0; i < n; i++) {
if (pc->fat32[i] == 0) free++;
}
}
todo -= n;
}
} else {
// invalid FAT type
DBG_FAIL_MACRO;
goto fail;
}
return free;
fail:
return -1;
}
//------------------------------------------------------------------------------
/** Initialize a FAT volume.
*
* \param[in] dev The SD card where the volume is located.
*
* \param[in] part The partition to be used. Legal values for \a part are
* 1-4 to use the corresponding partition on a device formatted with
* a MBR, Master Boot Record, or zero if the device is formatted as
* a super floppy with the FAT boot sector in block zero.
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure. Reasons for
* failure include not finding a valid partition, not finding a valid
* FAT file system in the specified partition or an I/O error.
*/
bool SdVolume::init(Sd2Card* dev, uint8_t part) {
uint32_t totalBlocks;
uint32_t volumeStartBlock = 0;
fat32_boot_t* fbs;
cache_t* pc;
sdCard_ = dev;
fatType_ = 0;
allocSearchStart_ = 2;
cacheStatus_ = 0; // cacheSync() will write block if true
cacheBlockNumber_ = 0XFFFFFFFF;
cacheFatOffset_ = 0;
#if USE_SERARATEFAT_CACHE
cacheFatStatus_ = 0; // cacheSync() will write block if true
cacheFatBlockNumber_ = 0XFFFFFFFF;
#endif // USE_SERARATEFAT_CACHE
// if part == 0 assume super floppy with FAT boot sector in block zero
// if part > 0 assume mbr volume with partition table
if (part) {
if (part > 4) {
DBG_FAIL_MACRO;
goto fail;
}
pc = cacheFetch(volumeStartBlock, CACHE_FOR_READ);
if (!pc) {
DBG_FAIL_MACRO;
goto fail;
}
part_t* p = &pc->mbr.part[part-1];
if ((p->boot & 0X7F) !=0 ||
p->totalSectors < 100 ||
p->firstSector == 0) {
// not a valid partition
DBG_FAIL_MACRO;
goto fail;
}
volumeStartBlock = p->firstSector;
}
pc = cacheFetch(volumeStartBlock, CACHE_FOR_READ);
if (!pc) {
DBG_FAIL_MACRO;
goto fail;
}
fbs = &(pc->fbs32);
if (fbs->bytesPerSector != 512 ||
fbs->fatCount == 0 ||
fbs->reservedSectorCount == 0 ||
fbs->sectorsPerCluster == 0) {
// not valid FAT volume
DBG_FAIL_MACRO;
goto fail;
}
fatCount_ = fbs->fatCount;
blocksPerCluster_ = fbs->sectorsPerCluster;
// determine shift that is same as multiply by blocksPerCluster_
clusterSizeShift_ = 0;
while (blocksPerCluster_ != (1 << clusterSizeShift_)) {
// error if not power of 2
if (clusterSizeShift_++ > 7) {
DBG_FAIL_MACRO;
goto fail;
}
}
blocksPerFat_ = fbs->sectorsPerFat16 ?
fbs->sectorsPerFat16 : fbs->sectorsPerFat32;
if (fatCount_ > 0) cacheFatOffset_ = blocksPerFat_;
fatStartBlock_ = volumeStartBlock + fbs->reservedSectorCount;
// count for FAT16 zero for FAT32
rootDirEntryCount_ = fbs->rootDirEntryCount;
// directory start for FAT16 dataStart for FAT32
rootDirStart_ = fatStartBlock_ + fbs->fatCount * blocksPerFat_;
// data start for FAT16 and FAT32
dataStartBlock_ = rootDirStart_ + ((32 * fbs->rootDirEntryCount + 511)/512);
// total blocks for FAT16 or FAT32
totalBlocks = fbs->totalSectors16 ?
fbs->totalSectors16 : fbs->totalSectors32;
// total data blocks
clusterCount_ = totalBlocks - (dataStartBlock_ - volumeStartBlock);
// divide by cluster size to get cluster count
clusterCount_ >>= clusterSizeShift_;
// FAT type is determined by cluster count
if (clusterCount_ < 4085) {
fatType_ = 12;
if (!FAT12_SUPPORT) {
DBG_FAIL_MACRO;
goto fail;
}
} else if (clusterCount_ < 65525) {
fatType_ = 16;
} else {
rootDirStart_ = fbs->fat32RootCluster;
fatType_ = 32;
}
return true;
fail:
return false;
}

View file

@ -0,0 +1,234 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef SdVolume_h
#define SdVolume_h
/**
* \file
* \brief SdVolume class
*/
#include <SdFatConfig.h>
#include <Sd2Card.h>
#include <SdFatStructs.h>
//==============================================================================
// SdVolume class
/**
* \brief Cache for an SD data block
*/
union cache_t {
/** Used to access cached file data blocks. */
uint8_t data[512];
/** Used to access cached FAT16 entries. */
uint16_t fat16[256];
/** Used to access cached FAT32 entries. */
uint32_t fat32[128];
/** Used to access cached directory entries. */
dir_t dir[16];
/** Used to access a cached Master Boot Record. */
mbr_t mbr;
/** Used to access to a cached FAT boot sector. */
fat_boot_t fbs;
/** Used to access to a cached FAT32 boot sector. */
fat32_boot_t fbs32;
/** Used to access to a cached FAT32 FSINFO sector. */
fat32_fsinfo_t fsinfo;
};
//------------------------------------------------------------------------------
/**
* \class SdVolume
* \brief Access FAT16 and FAT32 volumes on SD and SDHC cards.
*/
class SdVolume {
public:
/** Create an instance of SdVolume */
SdVolume() : fatType_(0) {}
/** Clear the cache and returns a pointer to the cache. Used by the WaveRP
* recorder to do raw write to the SD card. Not for normal apps.
* \return A pointer to the cache buffer or zero if an error occurs.
*/
cache_t* cacheClear() {
if (!cacheSync()) return 0;
cacheBlockNumber_ = 0XFFFFFFFF;
return &cacheBuffer_;
}
/** Initialize a FAT volume. Try partition one first then try super
* floppy format.
*
* \param[in] dev The Sd2Card where the volume is located.
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure. Reasons for
* failure include not finding a valid partition, not finding a valid
* FAT file system or an I/O error.
*/
bool init(Sd2Card* dev) { return init(dev, 1) ? true : init(dev, 0);}
bool init(Sd2Card* dev, uint8_t part);
// inline functions that return volume info
/** \return The volume's cluster size in blocks. */
uint8_t blocksPerCluster() const {return blocksPerCluster_;}
/** \return The number of blocks in one FAT. */
uint32_t blocksPerFat() const {return blocksPerFat_;}
/** \return The total number of clusters in the volume. */
uint32_t clusterCount() const {return clusterCount_;}
/** \return The shift count required to multiply by blocksPerCluster. */
uint8_t clusterSizeShift() const {return clusterSizeShift_;}
/** \return The logical block number for the start of file data. */
uint32_t dataStartBlock() const {return dataStartBlock_;}
/** \return The number of FAT structures on the volume. */
uint8_t fatCount() const {return fatCount_;}
/** \return The logical block number for the start of the first FAT. */
uint32_t fatStartBlock() const {return fatStartBlock_;}
/** \return The FAT type of the volume. Values are 12, 16 or 32. */
uint8_t fatType() const {return fatType_;}
int32_t freeClusterCount();
/** \return The number of entries in the root directory for FAT16 volumes. */
uint32_t rootDirEntryCount() const {return rootDirEntryCount_;}
/** \return The logical block number for the start of the root directory
on FAT16 volumes or the first cluster number on FAT32 volumes. */
uint32_t rootDirStart() const {return rootDirStart_;}
/** Sd2Card object for this volume
* \return pointer to Sd2Card object.
*/
Sd2Card* sdCard() {return sdCard_;}
/** Debug access to FAT table
*
* \param[in] n cluster number.
* \param[out] v value of entry
* \return true for success or false for failure
*/
bool dbgFat(uint32_t n, uint32_t* v) {return fatGet(n, v);}
//------------------------------------------------------------------------------
private:
// Allow SdBaseFile access to SdVolume private data.
friend class SdBaseFile;
//------------------------------------------------------------------------------
uint32_t allocSearchStart_; // start cluster for alloc search
uint8_t blocksPerCluster_; // cluster size in blocks
uint32_t blocksPerFat_; // FAT size in blocks
uint32_t clusterCount_; // clusters in one FAT
uint8_t clusterSizeShift_; // shift to convert cluster count to block count
uint32_t dataStartBlock_; // first data block number
uint8_t fatCount_; // number of FATs on volume
uint32_t fatStartBlock_; // start block for first FAT
uint8_t fatType_; // volume type (12, 16, OR 32)
uint16_t rootDirEntryCount_; // number of entries in FAT16 root dir
uint32_t rootDirStart_; // root start block for FAT16, cluster for FAT32
//------------------------------------------------------------------------------
// block caches
// use of static functions save a bit of flash - maybe not worth complexity
//
static const uint8_t CACHE_STATUS_DIRTY = 1;
static const uint8_t CACHE_STATUS_FAT_BLOCK = 2;
static const uint8_t CACHE_STATUS_MASK
= CACHE_STATUS_DIRTY | CACHE_STATUS_FAT_BLOCK;
static const uint8_t CACHE_OPTION_NO_READ = 4;
// value for option argument in cacheFetch to indicate read from cache
static uint8_t const CACHE_FOR_READ = 0;
// value for option argument in cacheFetch to indicate write to cache
static uint8_t const CACHE_FOR_WRITE = CACHE_STATUS_DIRTY;
// reserve cache block with no read
static uint8_t const CACHE_RESERVE_FOR_WRITE
= CACHE_STATUS_DIRTY | CACHE_OPTION_NO_READ;
#if USE_MULTIPLE_CARDS
cache_t cacheBuffer_; // 512 byte cache for device blocks
uint32_t cacheBlockNumber_; // Logical number of block in the cache
uint32_t cacheFatOffset_; // offset for mirrored FAT
Sd2Card* sdCard_; // Sd2Card object for cache
uint8_t cacheStatus_; // status of cache block
#if USE_SEPARATE_FAT_CACHE
cache_t cacheFatBuffer_; // 512 byte cache for FAT
uint32_t cacheFatBlockNumber_; // current Fat block number
uint8_t cacheFatStatus_; // status of cache Fatblock
#endif // USE_SEPARATE_FAT_CACHE
#else // USE_MULTIPLE_CARDS
static cache_t cacheBuffer_; // 512 byte cache for device blocks
static uint32_t cacheBlockNumber_; // Logical number of block in the cache
static uint32_t cacheFatOffset_; // offset for mirrored FAT
static uint8_t cacheStatus_; // status of cache block
#if USE_SEPARATE_FAT_CACHE
static cache_t cacheFatBuffer_; // 512 byte cache for FAT
static uint32_t cacheFatBlockNumber_; // current Fat block number
static uint8_t cacheFatStatus_; // status of cache Fatblock
#endif // USE_SEPARATE_FAT_CACHE
static Sd2Card* sdCard_; // Sd2Card object for cache
#endif // USE_MULTIPLE_CARDS
cache_t *cacheAddress() {return &cacheBuffer_;}
uint32_t cacheBlockNumber() {return cacheBlockNumber_;}
#if USE_MULTIPLE_CARDS
cache_t* cacheFetch(uint32_t blockNumber, uint8_t options);
cache_t* cacheFetchData(uint32_t blockNumber, uint8_t options);
cache_t* cacheFetchFat(uint32_t blockNumber, uint8_t options);
void cacheInvalidate();
bool cacheSync();
bool cacheWriteData();
bool cacheWriteFat();
#else // USE_MULTIPLE_CARDS
static cache_t* cacheFetch(uint32_t blockNumber, uint8_t options);
static cache_t* cacheFetchData(uint32_t blockNumber, uint8_t options);
static cache_t* cacheFetchFat(uint32_t blockNumber, uint8_t options);
static void cacheInvalidate();
static bool cacheSync();
static bool cacheWriteData();
static bool cacheWriteFat();
#endif // USE_MULTIPLE_CARDS
//------------------------------------------------------------------------------
bool allocContiguous(uint32_t count, uint32_t* curCluster);
uint8_t blockOfCluster(uint32_t position) const {
return (position >> 9) & (blocksPerCluster_ - 1);}
uint32_t clusterStartBlock(uint32_t cluster) const;
bool fatGet(uint32_t cluster, uint32_t* value);
bool fatPut(uint32_t cluster, uint32_t value);
bool fatPutEOC(uint32_t cluster) {
return fatPut(cluster, 0x0FFFFFFF);
}
bool freeChain(uint32_t cluster);
bool isEOC(uint32_t cluster) const {
if (FAT12_SUPPORT && fatType_ == 12) return cluster >= FAT12EOC_MIN;
if (fatType_ == 16) return cluster >= FAT16EOC_MIN;
return cluster >= FAT32EOC_MIN;
}
bool readBlock(uint32_t block, uint8_t* dst) {
return sdCard_->readBlock(block, dst);}
bool writeBlock(uint32_t block, const uint8_t* dst) {
return sdCard_->writeBlock(block, dst);
}
//------------------------------------------------------------------------------
// Deprecated functions - suppress cpplint warnings with NOLINT comment
#if ALLOW_DEPRECATED_FUNCTIONS && !defined(DOXYGEN)
public:
/** \deprecated Use: bool SdVolume::init(Sd2Card* dev);
* \param[in] dev The SD card where the volume is located.
* \return true for success or false for failure.
*/
bool init(Sd2Card& dev) {return init(&dev);} // NOLINT
/** \deprecated Use: bool SdVolume::init(Sd2Card* dev, uint8_t vol);
* \param[in] dev The SD card where the volume is located.
* \param[in] part The partition to be used.
* \return true for success or false for failure.
*/
bool init(Sd2Card& dev, uint8_t part) { // NOLINT
return init(&dev, part);
}
#endif // ALLOW_DEPRECATED_FUNCTIONS
};
#endif // SdVolume

View file

@ -0,0 +1,146 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef bufstream_h
#define bufstream_h
/**
* \file
* \brief \ref ibufstream and \ref obufstream classes
*/
#include <iostream.h>
//==============================================================================
/**
* \class ibufstream
* \brief parse a char string
*/
class ibufstream : public istream {
public:
/** Constructor */
ibufstream() : buf_(0), len_(0) {}
/** Constructor
* \param[in] str pointer to string to be parsed
* Warning: The string will not be copied so must stay in scope.
*/
explicit ibufstream(const char* str) {
init(str);
}
/** Initialize an ibufstream
* \param[in] str pointer to string to be parsed
* Warning: The string will not be copied so must stay in scope.
*/
void init(const char* str) {
buf_ = str;
len_ = strlen(buf_);
pos_ = 0;
clear();
}
protected:
/// @cond SHOW_PROTECTED
int16_t getch() {
if (pos_ < len_) return buf_[pos_++];
setstate(eofbit);
return -1;
}
void getpos(FatPos_t *pos) {
pos->position = pos_;
}
bool seekoff(off_type off, seekdir way) {return false;}
bool seekpos(pos_type pos) {
if (pos < len_) {
pos_ = pos;
return true;
}
return false;
}
void setpos(FatPos_t *pos) {
pos_ = pos->position;
}
pos_type tellpos() {
return pos_;
}
/// @endcond
private:
const char* buf_;
size_t len_;
size_t pos_;
};
//==============================================================================
/**
* \class obufstream
* \brief format a char string
*/
class obufstream : public ostream {
public:
/** constructor */
obufstream() : in_(0) {}
/** Constructor
* \param[in] buf buffer for formatted string
* \param[in] size buffer size
*/
obufstream(char *buf, size_t size) {
init(buf, size);
}
/** Initialize an obufstream
* \param[in] buf buffer for formatted string
* \param[in] size buffer size
*/
void init(char *buf, size_t size) {
buf_ = buf;
buf[0] = '\0';
size_ = size;
in_ = 0;
}
/** \return a pointer to the buffer */
char* buf() {return buf_;}
/** \return the length of the formatted string */
size_t length() {return in_;}
protected:
/// @cond SHOW_PROTECTED
void putch(char c) {
if (in_ >= (size_ - 1)) {
setstate(badbit);
return;
}
buf_[in_++] = c;
buf_[in_]= '\0';
}
void putstr(const char *str) {
while (*str) putch(*str++);
}
bool seekoff(off_type off, seekdir way) {return false;}
bool seekpos(pos_type pos) {
if (pos > in_) return false;
in_ = pos;
buf_[in_] = '\0';
return true;
}
bool sync() {return true;}
pos_type tellpos() {
return in_;
}
/// @endcond
private:
char *buf_;
size_t size_;
size_t in_;
};
#endif // bufstream_h

View file

@ -0,0 +1,172 @@
// A simple data logger for the Arduino analog pins with optional DS1307
// uses RTClib from https://github.com/adafruit/RTClib
#include <SdFat.h>
#include <SdFatUtil.h> // define FreeRam()
#define SD_CHIP_SELECT SS // SD chip select pin
#define USE_DS1307 0 // set nonzero to use DS1307 RTC
#define LOG_INTERVAL 1000 // mills between entries
#define SENSOR_COUNT 3 // number of analog pins to log
#define ECHO_TO_SERIAL 1 // echo data to serial port if nonzero
#define WAIT_TO_START 1 // Wait for serial input in setup()
#define ADC_DELAY 10 // ADC delay for high impedence sensors
// file system object
SdFat sd;
// text file for logging
ofstream logfile;
// Serial print stream
ArduinoOutStream cout(Serial);
// buffer to format data - makes it eaiser to echo to Serial
char buf[80];
//------------------------------------------------------------------------------
#if SENSOR_COUNT > 6
#error SENSOR_COUNT too large
#endif // SENSOR_COUNT
//------------------------------------------------------------------------------
// store error strings in flash to save RAM
#define error(s) sd.errorHalt_P(PSTR(s))
//------------------------------------------------------------------------------
#if USE_DS1307
// use RTClib from Adafruit
// https://github.com/adafruit/RTClib
// The Arduino IDE has a bug that causes Wire and RTClib to be loaded even
// if USE_DS1307 is false.
#error remove this line and uncomment the next two lines.
//#include <Wire.h>
//#include <RTClib.h>
RTC_DS1307 RTC; // define the Real Time Clock object
//------------------------------------------------------------------------------
// call back for file timestamps
void dateTime(uint16_t* date, uint16_t* time) {
DateTime now = RTC.now();
// return date using FAT_DATE macro to format fields
*date = FAT_DATE(now.year(), now.month(), now.day());
// return time using FAT_TIME macro to format fields
*time = FAT_TIME(now.hour(), now.minute(), now.second());
}
//------------------------------------------------------------------------------
// format date/time
ostream& operator << (ostream& os, DateTime& dt) {
os << dt.year() << '/' << int(dt.month()) << '/' << int(dt.day()) << ',';
os << int(dt.hour()) << ':' << setfill('0') << setw(2) << int(dt.minute());
os << ':' << setw(2) << int(dt.second()) << setfill(' ');
return os;
}
#endif // USE_DS1307
//------------------------------------------------------------------------------
void setup() {
Serial.begin(9600);
while (!Serial){} // wait for Leonardo
// pstr stores strings in flash to save RAM
cout << endl << pstr("FreeRam: ") << FreeRam() << endl;
#if WAIT_TO_START
cout << pstr("Type any character to start\n");
while (Serial.read() <= 0) {}
delay(400); // catch Due reset problem
#endif // WAIT_TO_START
#if USE_DS1307
// connect to RTC
Wire.begin();
if (!RTC.begin()) error("RTC failed");
// set date time callback function
SdFile::dateTimeCallback(dateTime);
DateTime now = RTC.now();
cout << now << endl;
#endif // USE_DS1307
// initialize the SD card at SPI_HALF_SPEED to avoid bus errors with
if (!sd.begin(SD_CHIP_SELECT, SPI_HALF_SPEED)) sd.initErrorHalt();
// create a new file in root, the current working directory
char name[] = "LOGGER00.CSV";
for (uint8_t i = 0; i < 100; i++) {
name[6] = i/10 + '0';
name[7] = i%10 + '0';
if (sd.exists(name)) continue;
logfile.open(name);
break;
}
if (!logfile.is_open()) error("file.open");
cout << pstr("Logging to: ") << name << endl;
cout << pstr("Type any character to stop\n\n");
// format header in buffer
obufstream bout(buf, sizeof(buf));
bout << pstr("millis");
#if USE_DS1307
bout << pstr(",date,time");
#endif // USE_DS1307
for (uint8_t i = 0; i < SENSOR_COUNT; i++) {
bout << pstr(",sens") << int(i);
}
logfile << buf << endl;
#if ECHO_TO_SERIAL
cout << buf << endl;
#endif // ECHO_TO_SERIAL
}
//------------------------------------------------------------------------------
void loop() {
uint32_t m;
// wait for time to be a multiple of interval
do {
m = millis();
} while (m % LOG_INTERVAL);
// use buffer stream to format line
obufstream bout(buf, sizeof(buf));
// start with time in millis
bout << m;
#if USE_DS1307
DateTime now = RTC.now();
bout << ',' << now;
#endif // USE_DS1307
// read analog pins and format data
for (uint8_t ia = 0; ia < SENSOR_COUNT; ia++) {
#if ADC_DELAY
analogRead(ia);
delay(ADC_DELAY);
#endif // ADC_DELAY
bout << ',' << analogRead(ia);
}
bout << endl;
// log data and flush to SD
logfile << buf << flush;
// check for error
if (!logfile) error("write data failed");
#if ECHO_TO_SERIAL
cout << buf;
#endif // ECHO_TO_SERIAL
// don't log two points in the same millis
if (m == millis()) delay(1);
if (!Serial.available()) return;
logfile.close();
cout << pstr("Done!");
while (1);
}

View file

@ -0,0 +1,15 @@
#include <SdFat.h>
// create a serial output stream
ArduinoOutStream cout(Serial);
void setup() {
Serial.begin(9600);
while (!Serial) {} // wait for Leonardo
delay(2000);
cout << "Hello, World!\n";
}
void loop() {}

View file

@ -0,0 +1,18 @@
// This example illustrates use of SdFat's
// minimal unbuffered AVR Serial support.
//
// This is useful for debug and saves RAM
// Will not work on Due, Leonardo, or Teensy
#include <SdFat.h>
#include <SdFatUtil.h>
#ifndef UDR0
#error no AVR serial port0
#endif
void setup() {
MiniSerial.begin(9600);
MiniSerial.println(FreeRam());
MiniSerial.println(F("Type any Character"));
while(MiniSerial.read() < 0) {}
MiniSerial.println(F("Done"));
}
void loop() {}

View file

@ -0,0 +1,37 @@
/*
* Open all files in the root dir and print their filename and modify date/time
*/
#include <SdFat.h>
// SD chip select pin
const uint8_t chipSelect = SS;
// file system object
SdFat sd;
SdFile file;
// define a serial output stream
ArduinoOutStream cout(Serial);
//------------------------------------------------------------------------------
void setup() {
Serial.begin(9600);
while (!Serial) {} // wait for Leonardo
delay(1000);
// initialize the SD card at SPI_HALF_SPEED to avoid bus errors with
// breadboards. use SPI_FULL_SPEED for better performance.
if (!sd.begin(chipSelect, SPI_HALF_SPEED)) sd.initErrorHalt();
// open next file in root. The volume working directory, vwd, is root
while (file.openNext(sd.vwd(), O_READ)) {
file.printName(&Serial);
cout << ' ';
file.printModifyDateTime(&Serial);
cout << endl;
file.close();
}
cout << "\nDone!" << endl;
}
//------------------------------------------------------------------------------
void loop() {}

View file

@ -0,0 +1,90 @@
/*
* This sketch is a simple Print benchmark.
*/
#include <SdFat.h>
#include <SdFatUtil.h>
// SD chip select pin
const uint8_t chipSelect = SS;
// number of lines to print
#define N_PRINT 20000
#define PRINT_DOUBLE false
// file system
SdFat sd;
// test file
SdFile file;
// Serial output stream
ArduinoOutStream cout(Serial);
//------------------------------------------------------------------------------
// store error strings in flash to save RAM
#define error(s) sd.errorHalt_P(PSTR(s))
//------------------------------------------------------------------------------
void setup() {
Serial.begin(9600);
while (!Serial) {} // wait for Leonardo
}
//------------------------------------------------------------------------------
void loop() {
uint32_t maxLatency;
uint32_t minLatency;
uint32_t totalLatency;
while (Serial.read() >= 0) {}
// pstr stores strings in flash to save RAM
cout << pstr("Type any character to start\n");
while (Serial.read() <= 0) {}
delay(400); // catch Due reset problem
cout << pstr("Free RAM: ") << FreeRam() << endl;
// initialize the SD card at SPI_FULL_SPEED for best performance.
// try SPI_HALF_SPEED if bus errors occur.
if (!sd.begin(chipSelect, SPI_FULL_SPEED)) sd.initErrorHalt();
cout << pstr("Type is FAT") << int(sd.vol()->fatType()) << endl;
// open or create file - truncate existing file.
if (!file.open("BENCH.TXT", O_CREAT | O_TRUNC | O_RDWR)) {
error("open failed");
}
cout << pstr("Starting print test. Please wait.\n");
// do write test
maxLatency = 0;
minLatency = 999999;
totalLatency = 0;
uint32_t t = millis();
for (uint32_t i = 0; i < N_PRINT; i++) {
uint32_t m = micros();
#if PRINT_DOUBLE
file.println((double)0.01*i);
#else // PRINT_DOUBLE
file.println(i);
#endif // PRINT_DOUBLW
if (file.writeError) {
error("write failed");
}
m = micros() - m;
if (maxLatency < m) maxLatency = m;
if (minLatency > m) minLatency = m;
totalLatency += m;
}
file.sync();
t = millis() - t;
double s = file.fileSize();
cout << pstr("Time ") << 0.001*t << pstr(" sec\n");
cout << pstr("File size ") << 0.001*s << pstr("KB\n");
cout << pstr("Write ") << s/t << pstr(" KB/sec\n");
cout << pstr("Maximum latency: ") << maxLatency;
cout << pstr(" usec, Minimum Latency: ") << minLatency;
cout << pstr(" usec, Avg Latency: ") << totalLatency/N_PRINT << pstr(" usec\n\n");
file.close();
cout << pstr("Done!\n\n");
}

View file

@ -0,0 +1,129 @@
// Quick hardware test
#include <SdFat.h>
// Test with reduced SPI speed for breadboards.
// Change spiSpeed to SPI_FULL_SPEED for better performance
// Use SPI_QUARTER_SPEED for even slower SPI bus speed
const uint8_t spiSpeed = SPI_HALF_SPEED;
//------------------------------------------------------------------------------
// Normally SdFat is used in applications in place
// of Sd2Card, SdVolume, and SdFile for root.
Sd2Card card;
SdVolume volume;
SdFile root;
// Serial streams
ArduinoOutStream cout(Serial);
// input buffer for line
char cinBuf[40];
ArduinoInStream cin(Serial, cinBuf, sizeof(cinBuf));
// SD card chip select
int chipSelect;
void cardOrSpeed() {
cout << pstr(
"Try another SD card or reduce the SPI bus speed.\n"
"The current SPI speed is: ");
uint8_t divisor = 1;
for (uint8_t i = 0; i < spiSpeed; i++) divisor *= 2;
cout << F_CPU * 0.5e-6 / divisor << pstr(" MHz\n");
cout << pstr("Edit spiSpeed in this sketch to change it.\n");
}
void reformatMsg() {
cout << pstr("Try reformatting the card. For best results use\n");
cout << pstr("the SdFormatter sketch in SdFat/examples or download\n");
cout << pstr("and use SDFormatter from www.sdcard.org/consumer.\n");
}
void setup() {
Serial.begin(9600);
while (!Serial) {} // wait for Leonardo
cout << pstr(
"\nSD chip select is the key hardware option.\n"
"Common values are:\n"
"Arduino Ethernet shield, pin 4\n"
"Sparkfun SD shield, pin 8\n"
"Adafruit SD shields and modules, pin 10\n");
}
bool firstTry = true;
void loop() {
// read any existing Serial data
while (Serial.read() >= 0) {}
if (!firstTry) cout << pstr("\nRestarting\n");
firstTry = false;
cout << pstr("\nEnter the chip select pin number: ");
cin.readline();
if (cin >> chipSelect) {
cout << chipSelect << endl;
} else {
cout << pstr("\nInvalid pin number\n");
return;
}
if (!card.init(spiSpeed, chipSelect)) {
cout << pstr(
"\nSD initialization failed.\n"
"Do not reformat the card!\n"
"Is the card correctly inserted?\n"
"Is chipSelect set to the correct value?\n"
"Is there a wiring/soldering problem?\n");
cout << pstr("errorCode: ") << hex << showbase << int(card.errorCode());
cout << pstr(", errorData: ") << int(card.errorData());
cout << dec << noshowbase << endl;
return;
}
cout << pstr("\nCard successfully initialized.\n");
cout << endl;
uint32_t size = card.cardSize();
if (size == 0) {
cout << pstr("Can't determine the card size.\n");
cardOrSpeed();
return;
}
uint32_t sizeMB = 0.000512 * size + 0.5;
cout << pstr("Card size: ") << sizeMB;
cout << pstr(" MB (MB = 1,000,000 bytes)\n");
cout << endl;
if (!volume.init(&card)) {
if (card.errorCode()) {
cout << pstr("Can't read the card.\n");
cardOrSpeed();
} else {
cout << pstr("Can't find a valid FAT16/FAT32 partition.\n");
reformatMsg();
}
return;
}
cout << pstr("Volume is FAT") << int(volume.fatType());
cout << pstr(", Cluster size (bytes): ") << 512L * volume.blocksPerCluster();
cout << endl << endl;
root.close();
if (!root.openRoot(&volume)) {
cout << pstr("Can't open root directory.\n");
reformatMsg();
return;
}
cout << pstr("Files found (name date time size):\n");
root.ls(LS_R | LS_DATE | LS_SIZE);
if ((sizeMB > 1100 && volume.blocksPerCluster() < 64)
|| (sizeMB < 2200 && volume.fatType() == 32)) {
cout << pstr("\nThis card should be reformatted for best performance.\n");
cout << pstr("Use a cluster size of 32 KB for cards larger than 1 GB.\n");
cout << pstr("Only cards larger than 2 GB should be formatted FAT32.\n");
reformatMsg();
return;
}
// read any existing Serial data
while (Serial.read() >= 0) {}
cout << pstr("\nSuccess! Type any character to restart.\n");
while (Serial.read() < 0) {}
}

View file

@ -0,0 +1,175 @@
/*
* This sketch illustrates raw write functions in SdFat that
* can be used for high speed data logging. These functions
* are used in the WaveRP library to record audio with the
* Adafruit Wave Shield using the built-in Arduino ADC.
*
* The WaveRP library captures data from the ADC in an ISR
* that is driven driven by timer one. Data is collected in
* two 512 byte buffers and written to the SD card.
*
* This sketch simulates logging from a source that produces
* data at a constant rate of one block every MICROS_PER_BLOCK.
*
* If a high quality SanDisk card is used with this sketch
* no overruns occur and the maximum block write time is
* under 2000 micros.
*
* Note: WaveRP creates a very large file then truncates it
* to the length that is used for a recording. It only takes
* a few seconds to erase a 500 MB file since the card only
* marks the blocks as erased; no data transfer is required.
*/
#include <SdFat.h>
#include <SdFatUtil.h>
// SD chip select pin
const uint8_t chipSelect = SS;
// number of blocks in the contiguous file
const uint32_t BLOCK_COUNT = 10000UL;
// time to produce a block of data
const uint32_t MICROS_PER_BLOCK = 10000;
// file system
SdFat sd;
// test file
SdFile file;
// file extent
uint32_t bgnBlock, endBlock;
// Serial output stream
ArduinoOutStream cout(Serial);
//------------------------------------------------------------------------------
// store error strings in flash to save RAM
#define error(s) sd.errorHalt_P(PSTR(s))
//------------------------------------------------------------------------------
// log of first overruns
#define OVER_DIM 20
struct {
uint32_t block;
uint32_t micros;
} over[OVER_DIM];
//------------------------------------------------------------------------------
void setup(void) {
Serial.begin(9600);
while (!Serial) {} // wait for Leonardo
}
//------------------------------------------------------------------------------
void loop(void) {
while (Serial.read() >= 0) {}
// pstr stores strings in flash to save RAM
cout << pstr("Type any character to start\n");
while (Serial.read() <= 0) {}
delay(400); // catch Due reset problem
cout << pstr("Free RAM: ") << FreeRam() << endl;
// initialize the SD card at SPI_FULL_SPEED for best performance.
// try SPI_HALF_SPEED if bus errors occur.
if (!sd.begin(chipSelect, SPI_FULL_SPEED)) sd.initErrorHalt();
// delete possible existing file
sd.remove("RAW.TXT");
// create a contiguous file
if (!file.createContiguous(sd.vwd(), "RAW.TXT", 512UL*BLOCK_COUNT)) {
error("createContiguous failed");
}
// get the location of the file's blocks
if (!file.contiguousRange(&bgnBlock, &endBlock)) {
error("contiguousRange failed");
}
//*********************NOTE**************************************
// NO SdFile calls are allowed while cache is used for raw writes
//***************************************************************
// clear the cache and use it as a 512 byte buffer
uint8_t* pCache = (uint8_t*)sd.vol()->cacheClear();
// fill cache with eight lines of 64 bytes each
memset(pCache, ' ', 512);
for (uint16_t i = 0; i < 512; i += 64) {
// put line number at end of line then CR/LF
pCache[i + 61] = '0' + (i/64);
pCache[i + 62] = '\r';
pCache[i + 63] = '\n';
}
cout << pstr("Start raw write of ") << file.fileSize() << pstr(" bytes at\n");
cout << 512000000UL/MICROS_PER_BLOCK << pstr(" bytes per second\n");
cout << pstr("Please wait ") << (BLOCK_COUNT*MICROS_PER_BLOCK)/1000000UL;
cout << pstr(" seconds\n");
// tell card to setup for multiple block write with pre-erase
if (!sd.card()->erase(bgnBlock, endBlock)) error("card.erase failed");
if (!sd.card()->writeStart(bgnBlock, BLOCK_COUNT)) {
error("writeStart failed");
}
// init stats
uint16_t overruns = 0;
uint32_t maxWriteTime = 0;
uint32_t t = micros();
uint32_t tNext = t;
// write data
for (uint32_t b = 0; b < BLOCK_COUNT; b++) {
// write must be done by this time
tNext += MICROS_PER_BLOCK;
// put block number at start of first line in block
uint32_t n = b;
for (int8_t d = 5; d >= 0; d--){
pCache[d] = n || d == 5 ? n % 10 + '0' : ' ';
n /= 10;
}
// write a 512 byte block
uint32_t tw = micros();
if (!sd.card()->writeData(pCache)) error("writeData failed");
tw = micros() - tw;
// check for max write time
if (tw > maxWriteTime) {
maxWriteTime = tw;
}
// check for overrun
if (micros() > tNext) {
if (overruns < OVER_DIM) {
over[overruns].block = b;
over[overruns].micros = tw;
}
overruns++;
// advance time to reflect overrun
tNext = micros();
}
else {
// wait for time to write next block
while(micros() < tNext);
}
}
// total write time
t = micros() - t;
// end multiple block write mode
if (!sd.card()->writeStop()) error("writeStop failed");
cout << pstr("Done\n");
cout << pstr("Elapsed time: ") << setprecision(3)<< 1.e-6*t;
cout << pstr(" seconds\n");
cout << pstr("Max write time: ") << maxWriteTime << pstr(" micros\n");
cout << pstr("Overruns: ") << overruns << endl;
if (overruns) {
uint8_t n = overruns > OVER_DIM ? OVER_DIM : overruns;
cout << pstr("fileBlock,micros") << endl;
for (uint8_t i = 0; i < n; i++) {
cout << over[i].block << ',' << over[i].micros << endl;
}
}
// close file for next pass of loop
file.close();
Serial.println();
}

View file

@ -0,0 +1,68 @@
// Ported to SdFat from the native Arduino SD library example by Bill Greiman
// On the Ethernet Shield, CS is pin 4. SdFat handles setting SS
const int chipSelect = 4;
/*
SD card read/write
This example shows how to read and write data to and from an SD card file
The circuit:
* SD card attached to SPI bus as follows:
** MOSI - pin 11
** MISO - pin 12
** CLK - pin 13
** CS - pin 4
created Nov 2010
by David A. Mellis
updated 2 Dec 2010
by Tom Igoe
modified by Bill Greiman 11 Apr 2011
This example code is in the public domain.
*/
#include <SdFat.h>
SdFat sd;
SdFile myFile;
void setup() {
Serial.begin(9600);
while (!Serial) {} // wait for Leonardo
Serial.println("Type any character to start");
while (Serial.read() <= 0) {}
delay(400); // catch Due reset problem
// Initialize SdFat or print a detailed error message and halt
// Use half speed like the native library.
// change to SPI_FULL_SPEED for more performance.
if (!sd.begin(chipSelect, SPI_HALF_SPEED)) sd.initErrorHalt();
// open the file for write at end like the Native SD library
if (!myFile.open("test.txt", O_RDWR | O_CREAT | O_AT_END)) {
sd.errorHalt("opening test.txt for write failed");
}
// if the file opened okay, write to it:
Serial.print("Writing to test.txt...");
myFile.println("testing 1, 2, 3.");
// close the file:
myFile.close();
Serial.println("done.");
// re-open the file for reading:
if (!myFile.open("test.txt", O_READ)) {
sd.errorHalt("opening test.txt for read failed");
}
Serial.println("test.txt:");
// read from the file until there's nothing else in it:
int data;
while ((data = myFile.read()) >= 0) Serial.write(data);
// close the file:
myFile.close();
}
void loop() {
// nothing happens after setup
}

View file

@ -0,0 +1,26 @@
/*
* Sketch to compare size of Arduino SD library with SdFat V2.
* See SdFatSize.pde for SdFat sketch.
*/
#include <SPI.h>
#include <SD.h>
File file;
//------------------------------------------------------------------------------
void setup() {
Serial.begin(9600);
while (!Serial) {} // wait for Leonardo
if (!SD.begin()) {
Serial.println("begin failed");
return;
}
file = SD.open("TEST_SD.TXT", FILE_WRITE);
file.println("Hello");
file.close();
Serial.println("Done");
}
//------------------------------------------------------------------------------
void loop() {}

View file

@ -0,0 +1,28 @@
/*
* Sketch to compare size of SdFat V2 with Arduino SD library.
* See SD_Size.pde for Arduino SD sketch.
*
*/
#include <SdFat.h>
SdFat sd;
SdFile file;
//------------------------------------------------------------------------------
void setup() {
Serial.begin(9600);
while (!Serial) {} // wait for Leonardo
if (!sd.begin()) {
Serial.println("begin failed");
return;
}
file.open("SIZE_TST.TXT", O_RDWR | O_CREAT | O_AT_END);
file.println("Hello");
file.close();
Serial.println("Done");
}
//------------------------------------------------------------------------------
void loop() {}

View file

@ -0,0 +1,486 @@
/*
* This sketch will format an SD or SDHC card.
* Warning all data will be deleted!
*
* For SD/SDHC cards larger than 64 MB this
* sketch attempts to match the format
* generated by SDFormatter available here:
*
* http://www.sdcard.org/consumers/formatter/
*
* For smaller cards this sketch uses FAT16
* and SDFormatter uses FAT12.
*/
// Print extra info for debug if DEBUG_PRINT is nonzero
#define DEBUG_PRINT 0
#include <SdFat.h>
#if DEBUG_PRINT
#include <SdFatUtil.h>
#endif // DEBUG_PRINT
//
// Change the value of chipSelect if your hardware does
// not use the default value, SS. Common values are:
// Arduino Ethernet shield: pin 4
// Sparkfun SD shield: pin 8
// Adafruit SD shields and modules: pin 10
const uint8_t chipSelect = SS;
// Change spiSpeed to SPI_FULL_SPEED for better performance
// Use SPI_QUARTER_SPEED for even slower SPI bus speed
const uint8_t spiSpeed = SPI_HALF_SPEED;
// Serial output stream
ArduinoOutStream cout(Serial);
Sd2Card card;
uint32_t cardSizeBlocks;
uint16_t cardCapacityMB;
// cache for SD block
cache_t cache;
// MBR information
uint8_t partType;
uint32_t relSector;
uint32_t partSize;
// Fake disk geometry
uint8_t numberOfHeads;
uint8_t sectorsPerTrack;
// FAT parameters
uint16_t reservedSectors;
uint8_t sectorsPerCluster;
uint32_t fatStart;
uint32_t fatSize;
uint32_t dataStart;
// constants for file system structure
uint16_t const BU16 = 128;
uint16_t const BU32 = 8192;
// strings needed in file system structures
char noName[] = "NO NAME ";
char fat16str[] = "FAT16 ";
char fat32str[] = "FAT32 ";
//------------------------------------------------------------------------------
#define sdError(msg) sdError_P(PSTR(msg))
void sdError_P(const char* str) {
cout << pstr("error: ");
cout << pgm(str) << endl;
if (card.errorCode()) {
cout << pstr("SD error: ") << hex << int(card.errorCode());
cout << ',' << int(card.errorData()) << dec << endl;
}
while (1);
}
//------------------------------------------------------------------------------
#if DEBUG_PRINT
void debugPrint() {
cout << pstr("FreeRam: ") << FreeRam() << endl;
cout << pstr("partStart: ") << relSector << endl;
cout << pstr("partSize: ") << partSize << endl;
cout << pstr("reserved: ") << reservedSectors << endl;
cout << pstr("fatStart: ") << fatStart << endl;
cout << pstr("fatSize: ") << fatSize << endl;
cout << pstr("dataStart: ") << dataStart << endl;
cout << pstr("clusterCount: ");
cout << ((relSector + partSize - dataStart)/sectorsPerCluster) << endl;
cout << endl;
cout << pstr("Heads: ") << int(numberOfHeads) << endl;
cout << pstr("Sectors: ") << int(sectorsPerTrack) << endl;
cout << pstr("Cylinders: ");
cout << cardSizeBlocks/(numberOfHeads*sectorsPerTrack) << endl;
}
#endif // DEBUG_PRINT
//------------------------------------------------------------------------------
// write cached block to the card
uint8_t writeCache(uint32_t lbn) {
return card.writeBlock(lbn, cache.data);
}
//------------------------------------------------------------------------------
// initialize appropriate sizes for SD capacity
void initSizes() {
if (cardCapacityMB <= 6) {
sdError("Card is too small.");
} else if (cardCapacityMB <= 16) {
sectorsPerCluster = 2;
} else if (cardCapacityMB <= 32) {
sectorsPerCluster = 4;
} else if (cardCapacityMB <= 64) {
sectorsPerCluster = 8;
} else if (cardCapacityMB <= 128) {
sectorsPerCluster = 16;
} else if (cardCapacityMB <= 1024) {
sectorsPerCluster = 32;
} else if (cardCapacityMB <= 32768) {
sectorsPerCluster = 64;
} else {
// SDXC cards
sectorsPerCluster = 128;
}
cout << pstr("Blocks/Cluster: ") << int(sectorsPerCluster) << endl;
// set fake disk geometry
sectorsPerTrack = cardCapacityMB <= 256 ? 32 : 63;
if (cardCapacityMB <= 16) {
numberOfHeads = 2;
} else if (cardCapacityMB <= 32) {
numberOfHeads = 4;
} else if (cardCapacityMB <= 128) {
numberOfHeads = 8;
} else if (cardCapacityMB <= 504) {
numberOfHeads = 16;
} else if (cardCapacityMB <= 1008) {
numberOfHeads = 32;
} else if (cardCapacityMB <= 2016) {
numberOfHeads = 64;
} else if (cardCapacityMB <= 4032) {
numberOfHeads = 128;
} else {
numberOfHeads = 255;
}
}
//------------------------------------------------------------------------------
// zero cache and optionally set the sector signature
void clearCache(uint8_t addSig) {
memset(&cache, 0, sizeof(cache));
if (addSig) {
cache.mbr.mbrSig0 = BOOTSIG0;
cache.mbr.mbrSig1 = BOOTSIG1;
}
}
//------------------------------------------------------------------------------
// zero FAT and root dir area on SD
void clearFatDir(uint32_t bgn, uint32_t count) {
clearCache(false);
if (!card.writeStart(bgn, count)) {
sdError("Clear FAT/DIR writeStart failed");
}
for (uint32_t i = 0; i < count; i++) {
if ((i & 0XFF) == 0) cout << '.';
if (!card.writeData(cache.data)) {
sdError("Clear FAT/DIR writeData failed");
}
}
if (!card.writeStop()) {
sdError("Clear FAT/DIR writeStop failed");
}
cout << endl;
}
//------------------------------------------------------------------------------
// return cylinder number for a logical block number
uint16_t lbnToCylinder(uint32_t lbn) {
return lbn / (numberOfHeads * sectorsPerTrack);
}
//------------------------------------------------------------------------------
// return head number for a logical block number
uint8_t lbnToHead(uint32_t lbn) {
return (lbn % (numberOfHeads * sectorsPerTrack)) / sectorsPerTrack;
}
//------------------------------------------------------------------------------
// return sector number for a logical block number
uint8_t lbnToSector(uint32_t lbn) {
return (lbn % sectorsPerTrack) + 1;
}
//------------------------------------------------------------------------------
// format and write the Master Boot Record
void writeMbr() {
clearCache(true);
part_t* p = cache.mbr.part;
p->boot = 0;
uint16_t c = lbnToCylinder(relSector);
if (c > 1023) sdError("MBR CHS");
p->beginCylinderHigh = c >> 8;
p->beginCylinderLow = c & 0XFF;
p->beginHead = lbnToHead(relSector);
p->beginSector = lbnToSector(relSector);
p->type = partType;
uint32_t endLbn = relSector + partSize - 1;
c = lbnToCylinder(endLbn);
if (c <= 1023) {
p->endCylinderHigh = c >> 8;
p->endCylinderLow = c & 0XFF;
p->endHead = lbnToHead(endLbn);
p->endSector = lbnToSector(endLbn);
} else {
// Too big flag, c = 1023, h = 254, s = 63
p->endCylinderHigh = 3;
p->endCylinderLow = 255;
p->endHead = 254;
p->endSector = 63;
}
p->firstSector = relSector;
p->totalSectors = partSize;
if (!writeCache(0)) sdError("write MBR");
}
//------------------------------------------------------------------------------
// generate serial number from card size and micros since boot
uint32_t volSerialNumber() {
return (cardSizeBlocks << 8) + micros();
}
//------------------------------------------------------------------------------
// format the SD as FAT16
void makeFat16() {
uint32_t nc;
for (dataStart = 2 * BU16;; dataStart += BU16) {
nc = (cardSizeBlocks - dataStart)/sectorsPerCluster;
fatSize = (nc + 2 + 255)/256;
uint32_t r = BU16 + 1 + 2 * fatSize + 32;
if (dataStart < r) continue;
relSector = dataStart - r + BU16;
break;
}
// check valid cluster count for FAT16 volume
if (nc < 4085 || nc >= 65525) sdError("Bad cluster count");
reservedSectors = 1;
fatStart = relSector + reservedSectors;
partSize = nc * sectorsPerCluster + 2 * fatSize + reservedSectors + 32;
if (partSize < 32680) {
partType = 0X01;
} else if (partSize < 65536) {
partType = 0X04;
} else {
partType = 0X06;
}
// write MBR
writeMbr();
clearCache(true);
fat_boot_t* pb = &cache.fbs;
pb->jump[0] = 0XEB;
pb->jump[1] = 0X00;
pb->jump[2] = 0X90;
for (uint8_t i = 0; i < sizeof(pb->oemId); i++) {
pb->oemId[i] = ' ';
}
pb->bytesPerSector = 512;
pb->sectorsPerCluster = sectorsPerCluster;
pb->reservedSectorCount = reservedSectors;
pb->fatCount = 2;
pb->rootDirEntryCount = 512;
pb->mediaType = 0XF8;
pb->sectorsPerFat16 = fatSize;
pb->sectorsPerTrack = sectorsPerTrack;
pb->headCount = numberOfHeads;
pb->hidddenSectors = relSector;
pb->totalSectors32 = partSize;
pb->driveNumber = 0X80;
pb->bootSignature = EXTENDED_BOOT_SIG;
pb->volumeSerialNumber = volSerialNumber();
memcpy(pb->volumeLabel, noName, sizeof(pb->volumeLabel));
memcpy(pb->fileSystemType, fat16str, sizeof(pb->fileSystemType));
// write partition boot sector
if (!writeCache(relSector)) {
sdError("FAT16 write PBS failed");
}
// clear FAT and root directory
clearFatDir(fatStart, dataStart - fatStart);
clearCache(false);
cache.fat16[0] = 0XFFF8;
cache.fat16[1] = 0XFFFF;
// write first block of FAT and backup for reserved clusters
if (!writeCache(fatStart)
|| !writeCache(fatStart + fatSize)) {
sdError("FAT16 reserve failed");
}
}
//------------------------------------------------------------------------------
// format the SD as FAT32
void makeFat32() {
uint32_t nc;
relSector = BU32;
for (dataStart = 2 * BU32;; dataStart += BU32) {
nc = (cardSizeBlocks - dataStart)/sectorsPerCluster;
fatSize = (nc + 2 + 127)/128;
uint32_t r = relSector + 9 + 2 * fatSize;
if (dataStart >= r) break;
}
// error if too few clusters in FAT32 volume
if (nc < 65525) sdError("Bad cluster count");
reservedSectors = dataStart - relSector - 2 * fatSize;
fatStart = relSector + reservedSectors;
partSize = nc * sectorsPerCluster + dataStart - relSector;
// type depends on address of end sector
// max CHS has lbn = 16450560 = 1024*255*63
if ((relSector + partSize) <= 16450560) {
// FAT32
partType = 0X0B;
} else {
// FAT32 with INT 13
partType = 0X0C;
}
writeMbr();
clearCache(true);
fat32_boot_t* pb = &cache.fbs32;
pb->jump[0] = 0XEB;
pb->jump[1] = 0X00;
pb->jump[2] = 0X90;
for (uint8_t i = 0; i < sizeof(pb->oemId); i++) {
pb->oemId[i] = ' ';
}
pb->bytesPerSector = 512;
pb->sectorsPerCluster = sectorsPerCluster;
pb->reservedSectorCount = reservedSectors;
pb->fatCount = 2;
pb->mediaType = 0XF8;
pb->sectorsPerTrack = sectorsPerTrack;
pb->headCount = numberOfHeads;
pb->hidddenSectors = relSector;
pb->totalSectors32 = partSize;
pb->sectorsPerFat32 = fatSize;
pb->fat32RootCluster = 2;
pb->fat32FSInfo = 1;
pb->fat32BackBootBlock = 6;
pb->driveNumber = 0X80;
pb->bootSignature = EXTENDED_BOOT_SIG;
pb->volumeSerialNumber = volSerialNumber();
memcpy(pb->volumeLabel, noName, sizeof(pb->volumeLabel));
memcpy(pb->fileSystemType, fat32str, sizeof(pb->fileSystemType));
// write partition boot sector and backup
if (!writeCache(relSector)
|| !writeCache(relSector + 6)) {
sdError("FAT32 write PBS failed");
}
clearCache(true);
// write extra boot area and backup
if (!writeCache(relSector + 2)
|| !writeCache(relSector + 8)) {
sdError("FAT32 PBS ext failed");
}
fat32_fsinfo_t* pf = &cache.fsinfo;
pf->leadSignature = FSINFO_LEAD_SIG;
pf->structSignature = FSINFO_STRUCT_SIG;
pf->freeCount = 0XFFFFFFFF;
pf->nextFree = 0XFFFFFFFF;
// write FSINFO sector and backup
if (!writeCache(relSector + 1)
|| !writeCache(relSector + 7)) {
sdError("FAT32 FSINFO failed");
}
clearFatDir(fatStart, 2 * fatSize + sectorsPerCluster);
clearCache(false);
cache.fat32[0] = 0x0FFFFFF8;
cache.fat32[1] = 0x0FFFFFFF;
cache.fat32[2] = 0x0FFFFFFF;
// write first block of FAT and backup for reserved clusters
if (!writeCache(fatStart)
|| !writeCache(fatStart + fatSize)) {
sdError("FAT32 reserve failed");
}
}
//------------------------------------------------------------------------------
// flash erase all data
uint32_t const ERASE_SIZE = 262144L;
void eraseCard() {
cout << endl << pstr("Erasing\n");
uint32_t firstBlock = 0;
uint32_t lastBlock;
uint16_t n = 0;
do {
lastBlock = firstBlock + ERASE_SIZE - 1;
if (lastBlock >= cardSizeBlocks) lastBlock = cardSizeBlocks - 1;
if (!card.erase(firstBlock, lastBlock)) sdError("erase failed");
cout << '.';
if ((n++)%32 == 31) cout << endl;
firstBlock += ERASE_SIZE;
} while (firstBlock < cardSizeBlocks);
cout << endl;
if (!card.readBlock(0, cache.data)) sdError("readBlock");
cout << hex << showbase << setfill('0') << internal;
cout << pstr("All data set to ") << setw(4) << int(cache.data[0]) << endl;
cout << dec << noshowbase << setfill(' ') << right;
cout << pstr("Erase done\n");
}
//------------------------------------------------------------------------------
void formatCard() {
cout << endl;
cout << pstr("Formatting\n");
initSizes();
if (card.type() != SD_CARD_TYPE_SDHC) {
cout << pstr("FAT16\n");
makeFat16();
} else {
cout << pstr("FAT32\n");
makeFat32();
}
#if DEBUG_PRINT
debugPrint();
#endif // DEBUG_PRINT
cout << pstr("Format done\n");
}
//------------------------------------------------------------------------------
void setup() {
char c;
Serial.begin(9600);
while (!Serial) {} // wait for Leonardo
cout << pstr(
"\n"
"This sketch can erase and/or format SD/SDHC cards.\n"
"\n"
"Erase uses the card's fast flash erase command.\n"
"Flash erase sets all data to 0X00 for most cards\n"
"and 0XFF for a few vendor's cards.\n"
"\n"
"Cards larger than 2 GB will be formatted FAT32 and\n"
"smaller cards will be formatted FAT16.\n"
"\n"
"Warning, all data on the card will be erased.\n"
"Enter 'Y' to continue: ");
while (!Serial.available()) {}
delay(400); // catch Due restart problem
c = Serial.read();
cout << c << endl;
if (c != 'Y') {
cout << pstr("Quiting, you did not enter 'Y'.\n");
return;
}
// read any existing Serial data
while (Serial.read() >= 0) {}
cout << pstr(
"\n"
"Options are:\n"
"E - erase the card and skip formatting.\n"
"F - erase and then format the card. (recommended)\n"
"Q - quick format the card without erase.\n"
"\n"
"Enter option: ");
while (!Serial.available()) {}
c = Serial.read();
cout << c << endl;
if (!strchr("EFQ", c)) {
cout << pstr("Quiting, invalid option entered.") << endl;
return;
}
if (!card.init(spiSpeed, chipSelect)) {
cout << pstr(
"\nSD initialization failure!\n"
"Is the SD card inserted correctly?\n"
"Is chip select correct at the top of this sketch?\n");
sdError("card.init failed");
}
cardSizeBlocks = card.cardSize();
if (cardSizeBlocks == 0) sdError("cardSize");
cardCapacityMB = (cardSizeBlocks + 2047)/2048;
cout << pstr("Card Size: ") << cardCapacityMB;
cout << pstr(" MB, (MB = 1,048,576 bytes)") << endl;
if (c == 'E' || c == 'F') {
eraseCard();
}
if (c == 'F' || c == 'Q') {
formatCard();
}
}
//------------------------------------------------------------------------------
void loop() {}

View file

@ -0,0 +1,197 @@
/*
* This sketch attempts to initialize an SD card and analyze its structure.
*/
#include <SdFat.h>
/*
* SD chip select pin. Common values are:
*
* Arduino Ethernet shield, pin 4.
* SparkFun SD shield, pin 8.
* Adafruit SD shields and modules, pin 10.
* Default SD chip select is the SPI SS pin.
*/
const uint8_t SdChipSelect = SS;
Sd2Card card;
SdVolume vol;
// serial output steam
ArduinoOutStream cout(Serial);
// global for card size
uint32_t cardSize;
// global for card erase size
uint32_t eraseSize;
//------------------------------------------------------------------------------
// store error strings in flash
#define sdErrorMsg(msg) sdErrorMsg_P(PSTR(msg));
void sdErrorMsg_P(const char* str) {
cout << pgm(str) << endl;
if (card.errorCode()) {
cout << pstr("SD errorCode: ");
cout << hex << int(card.errorCode()) << endl;
cout << pstr("SD errorData: ");
cout << int(card.errorData()) << dec << endl;
}
}
//------------------------------------------------------------------------------
uint8_t cidDmp() {
cid_t cid;
if (!card.readCID(&cid)) {
sdErrorMsg("readCID failed");
return false;
}
cout << pstr("\nManufacturer ID: ");
cout << hex << int(cid.mid) << dec << endl;
cout << pstr("OEM ID: ") << cid.oid[0] << cid.oid[1] << endl;
cout << pstr("Product: ");
for (uint8_t i = 0; i < 5; i++) {
cout << cid.pnm[i];
}
cout << pstr("\nVersion: ");
cout << int(cid.prv_n) << '.' << int(cid.prv_m) << endl;
cout << pstr("Serial number: ") << cid.psn << endl;
cout << pstr("Manufacturing date: ");
cout << int(cid.mdt_month) << '/';
cout << (2000 + cid.mdt_year_low + 10 * cid.mdt_year_high) << endl;
cout << endl;
return true;
}
//------------------------------------------------------------------------------
uint8_t csdDmp() {
csd_t csd;
uint8_t eraseSingleBlock;
if (!card.readCSD(&csd)) {
sdErrorMsg("readCSD failed");
return false;
}
if (csd.v1.csd_ver == 0) {
eraseSingleBlock = csd.v1.erase_blk_en;
eraseSize = (csd.v1.sector_size_high << 1) | csd.v1.sector_size_low;
} else if (csd.v2.csd_ver == 1) {
eraseSingleBlock = csd.v2.erase_blk_en;
eraseSize = (csd.v2.sector_size_high << 1) | csd.v2.sector_size_low;
} else {
cout << pstr("csd version error\n");
return false;
}
eraseSize++;
cout << pstr("cardSize: ") << 0.000512*cardSize;
cout << pstr(" MB (MB = 1,000,000 bytes)\n");
cout << pstr("flashEraseSize: ") << int(eraseSize) << pstr(" blocks\n");
cout << pstr("eraseSingleBlock: ");
if (eraseSingleBlock) {
cout << pstr("true\n");
} else {
cout << pstr("false\n");
}
return true;
}
//------------------------------------------------------------------------------
// print partition table
uint8_t partDmp() {
cache_t *p = vol.cacheClear();
if (!p) {
sdErrorMsg("cacheClear failed");
return false;
}
if (!card.readBlock(0, p->data)) {
sdErrorMsg("read MBR failed");
return false;
}
cout << pstr("\nSD Partition Table\n");
cout << pstr("part,boot,type,start,length\n");
for (uint8_t ip = 1; ip < 5; ip++) {
part_t *pt = &p->mbr.part[ip - 1];
cout << int(ip) << ',' << hex << int(pt->boot) << ',' << int(pt->type);
cout << dec << ',' << pt->firstSector <<',' << pt->totalSectors << endl;
}
return true;
}
//------------------------------------------------------------------------------
void volDmp() {
cout << pstr("\nVolume is FAT") << int(vol.fatType()) << endl;
cout << pstr("blocksPerCluster: ") << int(vol.blocksPerCluster()) << endl;
cout << pstr("clusterCount: ") << vol.clusterCount() << endl;
uint32_t volFree = vol.freeClusterCount();
cout << pstr("freeClusters: ") << volFree << endl;
float fs = 0.000512*volFree*vol.blocksPerCluster();
cout << pstr("freeSpace: ") << fs << pstr(" MB (MB = 1,000,000 bytes)\n");
cout << pstr("fatStartBlock: ") << vol.fatStartBlock() << endl;
cout << pstr("fatCount: ") << int(vol.fatCount()) << endl;
cout << pstr("blocksPerFat: ") << vol.blocksPerFat() << endl;
cout << pstr("rootDirStart: ") << vol.rootDirStart() << endl;
cout << pstr("dataStartBlock: ") << vol.dataStartBlock() << endl;
if (vol.dataStartBlock() % eraseSize) {
cout << pstr("Data area is not aligned on flash erase boundaries!\n");
cout << pstr("Download and use formatter from www.sdcard.org/consumer!\n");
}
}
//------------------------------------------------------------------------------
void setup() {
Serial.begin(9600);
while(!Serial) {} // wait for Leonardo
// use uppercase in hex and use 0X base prefix
cout << uppercase << showbase << endl;
// pstr stores strings in flash to save RAM
cout << pstr("SdFat version: ") << SD_FAT_VERSION << endl;
}
//------------------------------------------------------------------------------
void loop() {
// read any existing Serial data
while (Serial.read() >= 0) {}
// pstr stores strings in flash to save RAM
cout << pstr("\ntype any character to start\n");
while (Serial.read() <= 0) {}
delay(400); // catch Due reset problem
uint32_t t = millis();
// initialize the SD card at SPI_HALF_SPEED to avoid bus errors with
// breadboards. use SPI_FULL_SPEED for better performance.
if (!card.init(SPI_HALF_SPEED, SdChipSelect)) {
sdErrorMsg("\ncard.init failed");
return;
}
t = millis() - t;
cardSize = card.cardSize();
if (cardSize == 0) {
sdErrorMsg("cardSize failed");
return;
}
cout << pstr("\ninit time: ") << t << " ms" << endl;
cout << pstr("\nCard type: ");
switch (card.type()) {
case SD_CARD_TYPE_SD1:
cout << pstr("SD1\n");
break;
case SD_CARD_TYPE_SD2:
cout << pstr("SD2\n");
break;
case SD_CARD_TYPE_SDHC:
if (cardSize < 70000000) {
cout << pstr("SDHC\n");
} else {
cout << pstr("SDXC\n");
}
break;
default:
cout << pstr("Unknown\n");
}
if (!cidDmp()) return;
if (!csdDmp()) return;
if (!partDmp()) return;
if (!vol.init(&card)) {
sdErrorMsg("\nvol.init failed");
return;
}
volDmp();
}

View file

@ -0,0 +1,168 @@
/*
* This sketch tests the dateTimeCallback() function
* and the timestamp() function.
*/
#include <SdFat.h>
SdFat sd;
SdFile file;
// Default SD chip select is SS pin
const uint8_t chipSelect = SS;
// create Serial stream
ArduinoOutStream cout(Serial);
//------------------------------------------------------------------------------
// store error strings in flash to save RAM
#define error(s) sd.errorHalt_P(PSTR(s))
//------------------------------------------------------------------------------
/*
* date/time values for debug
* normally supplied by a real-time clock or GPS
*/
// date 1-Oct-09
uint16_t year = 2009;
uint8_t month = 10;
uint8_t day = 1;
// time 20:30:40
uint8_t hour = 20;
uint8_t minute = 30;
uint8_t second = 40;
//------------------------------------------------------------------------------
/*
* User provided date time callback function.
* See SdFile::dateTimeCallback() for usage.
*/
void dateTime(uint16_t* date, uint16_t* time) {
// User gets date and time from GPS or real-time
// clock in real callback function
// return date using FAT_DATE macro to format fields
*date = FAT_DATE(year, month, day);
// return time using FAT_TIME macro to format fields
*time = FAT_TIME(hour, minute, second);
}
//------------------------------------------------------------------------------
/*
* Function to print all timestamps.
*/
void printTimestamps(SdFile& f) {
dir_t d;
if (!f.dirEntry(&d)) error("f.dirEntry failed");
cout << pstr("Creation: ");
f.printFatDate(d.creationDate);
cout << ' ';
f.printFatTime(d.creationTime);
cout << endl;
cout << pstr("Modify: ");
f.printFatDate(d.lastWriteDate);
cout <<' ';
f.printFatTime(d.lastWriteTime);
cout << endl;
cout << pstr("Access: ");
f.printFatDate(d.lastAccessDate);
cout << endl;
}
//------------------------------------------------------------------------------
void setup(void) {
Serial.begin(9600);
while (!Serial) {} // wait for Leonardo
cout << pstr("Type any character to start\n");
while (!Serial.available());
delay(400); // catch Due reset problem
// initialize the SD card at SPI_HALF_SPEED to avoid bus errors with
// breadboards. use SPI_FULL_SPEED for better performance.
if (!sd.begin(chipSelect, SPI_HALF_SPEED)) sd.initErrorHalt();
// remove files if they exist
sd.remove("CALLBACK.TXT");
sd.remove("DEFAULT.TXT");
sd.remove("STAMP.TXT");
// create a new file with default timestamps
if (!file.open("DEFAULT.TXT", O_CREAT | O_WRITE)) {
error("open DEFAULT.TXT failed");
}
cout << pstr("\nOpen with default times\n");
printTimestamps(file);
// close file
file.close();
/*
* Test the date time callback function.
*
* dateTimeCallback() sets the function
* that is called when a file is created
* or when a file's directory entry is
* modified by sync().
*
* The callback can be disabled by the call
* SdFile::dateTimeCallbackCancel()
*/
// set date time callback function
SdFile::dateTimeCallback(dateTime);
// create a new file with callback timestamps
if (!file.open("CALLBACK.TXT", O_CREAT | O_WRITE)) {
error("open CALLBACK.TXT failed");
}
cout << ("\nOpen with callback times\n");
printTimestamps(file);
// change call back date
day += 1;
// must add two to see change since FAT second field is 5-bits
second += 2;
// modify file by writing a byte
file.write('t');
// force dir update
file.sync();
cout << pstr("\nTimes after write\n");
printTimestamps(file);
// close file
file.close();
/*
* Test timestamp() function
*
* Cancel callback so sync will not
* change access/modify timestamp
*/
SdFile::dateTimeCallbackCancel();
// create a new file with default timestamps
if (!file.open("STAMP.TXT", O_CREAT | O_WRITE)) {
error("open STAMP.TXT failed");
}
// set creation date time
if (!file.timestamp(T_CREATE, 2009, 11, 10, 1, 2, 3)) {
error("set create time failed");
}
// set write/modification date time
if (!file.timestamp(T_WRITE, 2009, 11, 11, 4, 5, 6)) {
error("set write time failed");
}
// set access date
if (!file.timestamp(T_ACCESS, 2009, 11, 12, 7, 8, 9)) {
error("set access time failed");
}
cout << pstr("\nTimes after timestamp() calls\n");
printTimestamps(file);
file.close();
cout << pstr("\nDone\n");
}
void loop(void){}

View file

@ -0,0 +1,140 @@
/*
* Example use of two SD cards.
*/
#include <SdFat.h>
#include <SdFatUtil.h>
#if !USE_MULTIPLE_CARDS
#error You must set USE_MULTIPLE_CARDS nonzero in SdFatConfig.h
#endif
SdFat sd1;
const uint8_t SD1_CS = 10; // chip select for sd1
SdFat sd2;
const uint8_t SD2_CS = 9; // chip select for sd2
const uint8_t BUF_DIM = 100;
uint8_t buf[BUF_DIM];
const uint32_t FILE_SIZE = 1000000;
const uint16_t NWRITE = FILE_SIZE/BUF_DIM;
//------------------------------------------------------------------------------
// print error msg, any SD error codes, and halt.
// store messages in flash
#define errorExit(msg) errorHalt_P(PSTR(msg))
#define initError(msg) initErrorHalt_P(PSTR(msg))
//------------------------------------------------------------------------------
void setup() {
Serial.begin(9600);
while (!Serial) {} // wait for Leonardo
PgmPrint("FreeRam: ");
Serial.println(FreeRam());
// fill buffer with known data
for (int i = 0; i < sizeof(buf); i++) buf[i] = i;
PgmPrintln("type any character to start");
while (Serial.read() <= 0) {}
delay(400); // catch Due reset problem
// disable sd2 while initializing sd1
pinMode(SD2_CS, OUTPUT);
digitalWrite(SD2_CS, HIGH);
// initialize the first card
if (!sd1.begin(SD1_CS)) {
sd1.initError("sd1:");
}
// create DIR1 on sd1 if it does not exist
if (!sd1.exists("/DIR1")) {
if (!sd1.mkdir("/DIR1")) sd1.errorExit("sd1.mkdir");
}
// initialize the second card
if (!sd2.begin(SD2_CS)) {
sd2.initError("sd2:");
}
// create DIR2 on sd2 if it does not exist
if (!sd2.exists("/DIR2")) {
if (!sd2.mkdir("/DIR2")) sd2.errorExit("sd2.mkdir");
}
// list root directory on both cards
PgmPrintln("------sd1 root-------");
sd1.ls();
PgmPrintln("------sd2 root-------");
sd2.ls();
// make /DIR1 the default directory for sd1
if (!sd1.chdir("/DIR1")) sd1.errorExit("sd1.chdir");
// make /DIR2 the default directory for sd2
if (!sd2.chdir("/DIR2")) sd2.errorExit("sd2.chdir");
// list current directory on both cards
PgmPrintln("------sd1 DIR1-------");
sd1.ls();
PgmPrintln("------sd2 DIR2-------");
sd2.ls();
PgmPrintln("---------------------");
// remove RENAME.BIN from /DIR2 directory of sd2
if (sd2.exists("RENAME.BIN")) {
if (!sd2.remove("RENAME.BIN")) {
sd2.errorExit("remove RENAME.BIN");
}
}
// set the current working directory for open() to sd1
sd1.chvol();
// create or open /DIR1/TEST.BIN and truncate it to zero length
SdFile file1;
if (!file1.open("TEST.BIN", O_RDWR | O_CREAT | O_TRUNC)) {
sd1.errorExit("file1");
}
PgmPrintln("Writing TEST.BIN to sd1");
// write data to /DIR1/TEST.BIN on sd1
for (int i = 0; i < NWRITE; i++) {
if (file1.write(buf, sizeof(buf)) != sizeof(buf)) {
sd1.errorExit("sd1.write");
}
}
// set the current working directory for open() to sd2
sd2.chvol();
// create or open /DIR2/COPY.BIN and truncate it to zero length
SdFile file2;
if (!file2.open("COPY.BIN", O_WRITE | O_CREAT | O_TRUNC)) {
sd2.errorExit("file2");
}
PgmPrintln("Copying TEST.BIN to COPY.BIN");
// copy file1 to file2
file1.rewind();
uint32_t t = millis();
while (1) {
int n = file1.read(buf, sizeof(buf));
if (n < 0) sd1.errorExit("read1");
if (n == 0) break;
if (file2.write(buf, n) != n) sd2.errorExit("write2");
}
t = millis() - t;
PgmPrint("File size: ");
Serial.println(file2.fileSize());
PgmPrint("Copy time: ");
Serial.print(t);
PgmPrintln(" millis");
// close TEST.BIN
file1.close();
// rename the copy
file2.close();
if (!sd2.rename("COPY.BIN", "RENAME.BIN")) {
sd2.errorExit("sd2.rename");
}
PgmPrintln("Done");
}
//------------------------------------------------------------------------------
void loop() {}

View file

@ -0,0 +1,63 @@
/*
* Append Example
*
* This sketch shows how to use open for append.
* The sketch will append 100 line each time it opens the file.
* The sketch will open and close the file 100 times.
*/
#include <SdFat.h>
// SD chip select pin
const uint8_t chipSelect = SS;
// file system object
SdFat sd;
// create Serial stream
ArduinoOutStream cout(Serial);
// store error strings in flash to save RAM
#define error(s) sd.errorHalt_P(PSTR(s))
//------------------------------------------------------------------------------
void setup() {
// filename for this example
char name[] = "APPEND.TXT";
Serial.begin(9600);
while (!Serial) {} // wait for Leonardo
// pstr() stores strings in flash to save RAM
cout << endl << pstr("Type any character to start\n");
while (Serial.read() <= 0) {}
delay(400); // Catch Due reset problem
// initialize the SD card at SPI_HALF_SPEED to avoid bus errors with
// breadboards. use SPI_FULL_SPEED for better performance.
if (!sd.begin(chipSelect, SPI_HALF_SPEED)) sd.initErrorHalt();
cout << pstr("Appending to: ") << name;
for (uint8_t i = 0; i < 100; i++) {
// open stream for append
ofstream sdout(name, ios::out | ios::app);
if (!sdout) error("open failed");
// append 100 lines to the file
for (uint8_t j = 0; j < 100; j++) {
// use int() so byte will print as decimal number
sdout << "line " << int(j) << " of pass " << int(i);
sdout << " millis = " << millis() << endl;
}
// close the stream
sdout.close();
if (!sdout) error("append data failed");
// output progress indicator
if (i % 25 == 0) cout << endl;
cout << '.';
}
cout << endl << "Done" << endl;
}
//------------------------------------------------------------------------------
void loop() {}

View file

@ -0,0 +1,70 @@
/*
* Calculate the sum and average of a list of floating point numbers
*/
#include <SdFat.h>
// SD chip select pin
const uint8_t chipSelect = SS;
// object for the SD file system
SdFat sd;
// define a serial output stream
ArduinoOutStream cout(Serial);
//------------------------------------------------------------------------------
void writeTestFile() {
// open the output file
ofstream sdout("AVG_TEST.TXT");
// write a series of float numbers
for (int16_t i = -1001; i < 2000; i += 13) {
sdout << 0.1 * i << endl;
}
if (!sdout) sd.errorHalt("sdout failed");
sdout.close();
}
//------------------------------------------------------------------------------
void calcAverage() {
uint16_t n = 0; // count of input numbers
double num; // current input number
double sum = 0; // sum of input numbers
// open the input file
ifstream sdin("AVG_TEST.TXT");
// check for an open failure
if (!sdin) sd.errorHalt("sdin failed");
// read and sum the numbers
while (sdin >> num) {
n++;
sum += num;
}
// print the results
cout << "sum of " << n << " numbers = " << sum << endl;
cout << "average = " << sum/n << endl;
}
//------------------------------------------------------------------------------
void setup() {
Serial.begin(9600);
while (!Serial) {} // wait for Leonardo
// pstr stores strings in flash to save RAM
cout << pstr("Type any character to start\n");
while (Serial.read() <= 0) {}
delay(400); // Catch Due reset problem
// initialize the SD card at SPI_HALF_SPEED to avoid bus errors with
// breadboards. use SPI_FULL_SPEED for better performance.
if (!sd.begin(chipSelect, SPI_HALF_SPEED)) sd.initErrorHalt();
// write the test file
writeTestFile();
// read the test file and calculate the average
calcAverage();
}
//------------------------------------------------------------------------------
void loop() {}

View file

@ -0,0 +1,122 @@
/*
* This sketch is a simple binary write/read benchmark.
*/
#include <SdFat.h>
#include <SdFatUtil.h>
// SD chip select pin
const uint8_t chipSelect = SS;
#define FILE_SIZE_MB 5
#define FILE_SIZE (1000000UL*FILE_SIZE_MB)
#define BUF_SIZE 100
uint8_t buf[BUF_SIZE];
// file system
SdFat sd;
// test file
SdFile file;
// Serial output stream
ArduinoOutStream cout(Serial);
//------------------------------------------------------------------------------
// store error strings in flash to save RAM
#define error(s) sd.errorHalt_P(PSTR(s))
//------------------------------------------------------------------------------
void setup() {
Serial.begin(9600);
while (!Serial){} // wait for Leonardo
Serial.println();
}
//------------------------------------------------------------------------------
void loop() {
uint32_t maxLatency;
uint32_t minLatency;
uint32_t totalLatency;
// discard any input
while (Serial.read() >= 0) {}
// pstr stores strings in flash to save RAM
cout << pstr("Type any character to start\n");
while (Serial.read() <= 0) {}
delay(400); // catch Due reset problem
cout << pstr("Free RAM: ") << FreeRam() << endl;
// initialize the SD card at SPI_FULL_SPEED for best performance.
// try SPI_HALF_SPEED if bus errors occur.
if (!sd.begin(chipSelect, SPI_FULL_SPEED)) sd.initErrorHalt();
cout << pstr("Type is FAT") << int(sd.vol()->fatType()) << endl;
// open or create file - truncate existing file.
if (!file.open("BENCH.DAT", O_CREAT | O_TRUNC | O_RDWR)) {
error("open failed");
}
// fill buf with known data
for (uint16_t i = 0; i < (BUF_SIZE-2); i++) {
buf[i] = 'A' + (i % 26);
}
buf[BUF_SIZE-2] = '\r';
buf[BUF_SIZE-1] = '\n';
cout << pstr("File size ") << FILE_SIZE_MB << pstr("MB\n");
cout << pstr("Buffer size ") << BUF_SIZE << pstr(" bytes\n");
cout << pstr("Starting write test. Please wait up to a minute\n");
// do write test
uint32_t n = FILE_SIZE/sizeof(buf);
maxLatency = 0;
minLatency = 9999999;
totalLatency = 0;
uint32_t t = millis();
for (uint32_t i = 0; i < n; i++) {
uint32_t m = micros();
if (file.write(buf, sizeof(buf)) != sizeof(buf)) {
error("write failed");
}
m = micros() - m;
if (maxLatency < m) maxLatency = m;
if (minLatency > m) minLatency = m;
totalLatency += m;
}
file.sync();
t = millis() - t;
double s = file.fileSize();
cout << pstr("Write ") << s/t << pstr(" KB/sec\n");
cout << pstr("Maximum latency: ") << maxLatency;
cout << pstr(" usec, Minimum Latency: ") << minLatency;
cout << pstr(" usec, Avg Latency: ") << totalLatency/n << pstr(" usec\n\n");
cout << pstr("Starting read test. Please wait up to a minute\n");
// do read test
file.rewind();
maxLatency = 0;
minLatency = 9999999;
totalLatency = 0;
t = millis();
for (uint32_t i = 0; i < n; i++) {
buf[BUF_SIZE-1] = 0;
uint32_t m = micros();
if (file.read(buf, sizeof(buf)) != sizeof(buf)) {
error("read failed");
}
m = micros() - m;
if (maxLatency < m) maxLatency = m;
if (minLatency > m) minLatency = m;
totalLatency += m;
if (buf[BUF_SIZE-1] != '\n') {
error("data check");
}
}
t = millis() - t;
cout << pstr("Read ") << s/t << pstr(" KB/sec\n");
cout << pstr("Maximum latency: ") << maxLatency;
cout << pstr(" usec, Minimum Latency: ") << minLatency;
cout << pstr(" usec, Avg Latency: ") << totalLatency/n << pstr(" usec\n\n");
cout << pstr("Done\n\n");
file.close();
}

View file

@ -0,0 +1,134 @@
/*
* This sketch is a simple binary write/read benchmark
* for the standard Arduino SD.h library.
*/
#include <SPI.h>
#include <SD.h>
// SD chip select pin
const uint8_t chipSelect = SS;
#define FILE_SIZE_MB 5
#define FILE_SIZE (1000000UL*FILE_SIZE_MB)
#define BUF_SIZE 100
uint8_t buf[BUF_SIZE];
// test file
File file;
//------------------------------------------------------------------------------
// store error strings in flash to save RAM
void error(char* s) {
Serial.println(s);
while(1);
}
//------------------------------------------------------------------------------
void setup() {
Serial.begin(9600);
while (!Serial){} // wait for Leonardo
}
//------------------------------------------------------------------------------
void loop() {
uint32_t maxLatency;
uint32_t minLatency;
uint32_t totalLatency;
// discard any input
while (Serial.read() >= 0) {}
// pstr stores strings in flash to save RAM
Serial.println("Type any character to start");
while (Serial.read() <= 0) {}
delay(400); // catch Due reset problem
if (!SD.begin(chipSelect)) error("begin");
// open or create file - truncate existing file.
file = SD.open("BENCH.DAT", FILE_WRITE | O_TRUNC);
// file = SD.open("BENCH.DAT", O_CREAT | O_TRUNC | O_CREAT);
if (!file) {
error("open failed");
}
// fill buf with known data
for (uint16_t i = 0; i < (BUF_SIZE-2); i++) {
buf[i] = 'A' + (i % 26);
}
buf[BUF_SIZE-2] = '\r';
buf[BUF_SIZE-1] = '\n';
Serial.print("File size ");
Serial.print(FILE_SIZE_MB);
Serial.println("MB");
Serial.print("Buffer size ");
Serial.print(BUF_SIZE);
Serial.println(" bytes");
Serial.println("Starting write test. Please wait up to a minute");
// do write test
uint32_t n = FILE_SIZE/sizeof(buf);
maxLatency = 0;
minLatency = 999999;
totalLatency = 0;
uint32_t t = millis();
for (uint32_t i = 0; i < n; i++) {
uint32_t m = micros();
if (file.write(buf, sizeof(buf)) != sizeof(buf)) {
error("write failed");
}
m = micros() - m;
if (maxLatency < m) maxLatency = m;
if (minLatency > m) minLatency = m;
totalLatency += m;
}
file.flush();
t = millis() - t;
double s = file.size();
Serial.print("Write ");
Serial.print(s/t);
Serial.print(" KB/sec\n");
Serial.print("Maximum latency: ");
Serial.print(maxLatency);
Serial.print(" usec, Minimum Latency: ");
Serial.print(minLatency);
Serial.print(" usec, Avg Latency: ");
Serial.print(totalLatency/n);
Serial.print(" usec\n\n");
Serial.print("Starting read test. Please wait up to a minute\n");
// do read test
file.seek(0);
maxLatency = 0;
minLatency = 99999;
totalLatency = 0;
t = millis();
for (uint32_t i = 0; i < n; i++) {
buf[BUF_SIZE-1] = 0;
uint32_t m = micros();
if (file.read(buf, sizeof(buf)) != sizeof(buf)) {
error("read failed");
}
m = micros() - m;
if (maxLatency < m) maxLatency = m;
if (minLatency > m) minLatency = m;
totalLatency += m;
if (buf[BUF_SIZE-1] != '\n') {
error("data check");
}
}
t = millis() - t;
Serial.print("Read ");
Serial.print(s/t);
Serial.print(" KB/sec\n");
Serial.print("Maximum latency: ");
Serial.print(maxLatency);;
Serial.print(" usec, Minimum Latency: ");
Serial.print(minLatency);;
Serial.print(" usec, Avg Latency: ");
Serial.print(totalLatency/n);
Serial.print(" usec\n\n");
Serial.print("Done\n\n");
file.close();
}

View file

@ -0,0 +1,33 @@
/*
* Use of ibufsteam to parse a line and obufstream to format a line
*/
#include <SdFat.h>
// create a serial output stream
ArduinoOutStream cout(Serial);
//------------------------------------------------------------------------------
void setup() {
char buf[20]; // buffer for formatted line
int i, j, k; // values from parsed line
Serial.begin(9600);
while (!Serial) {} // wait for Leonardo
delay(2000);
// initialize input string
ibufstream bin("123 456 789");
// parse the string "123 456 789"
bin >> i >> j >> k;
// initialize output buffer
obufstream bout(buf, sizeof(buf));
// format the output string
bout << k << ',' << j << ',' << i << endl;
// write the string to serial
cout << buf;
}
void loop() {}

View file

@ -0,0 +1,34 @@
/*
* Demo of ArduinoInStream and ArduinoOutStream
*/
#include <SdFat.h>
// create serial output stream
ArduinoOutStream cout(Serial);
// input buffer for line
char cinBuf[40];
// create serial input stream
ArduinoInStream cin(Serial, cinBuf, sizeof(cinBuf));
//------------------------------------------------------------------------------
void setup() {
Serial.begin(9600);
while (!Serial) {} // wait for Leonardo
}
//------------------------------------------------------------------------------
void loop() {
int32_t n;
cout << "\nenter an integer\n";
cin.readline();
if (cin >> n) {
cout << "The number is: " << n;
} else {
// will fail if no digits or not in range [-2147483648, 2147483647]
cout << "Invalid input: " << cinBuf;
}
cout << endl;
}

View file

@ -0,0 +1,53 @@
/*
* Append a line to a file - demo of pathnames and streams
*/
#include <SdFat.h>
// SD chip select pin
const uint8_t chipSelect = SS;
// file system object
SdFat sd;
// define a serial output stream
ArduinoOutStream cout(Serial);
//------------------------------------------------------------------------------
/*
* Append a line to LOGFILE.TXT
*/
void logEvent(const char *msg) {
// create dir if needed
sd.mkdir("LOGS/2011/JAN");
// create or open a file for append
ofstream sdlog("LOGS/2011/JAN/LOGFILE.TXT", ios::out | ios::app);
// append a line to the file
sdlog << msg << endl;
// check for errors
if (!sdlog) sd.errorHalt("append failed");
sdlog.close();
}
//------------------------------------------------------------------------------
void setup() {
Serial.begin(9600);
while (!Serial) {} // wait for Leonardo
// pstr stores strings in flash to save RAM
cout << pstr("Type any character to start\n");
while (Serial.read() <= 0) {}
delay(400); // catch Due reset problem
// initialize the SD card at SPI_HALF_SPEED to avoid bus errors with
// breadboards. use SPI_FULL_SPEED for better performance.
if (!sd.begin(chipSelect, SPI_HALF_SPEED)) sd.initErrorHalt();
// append a line to the logfile
logEvent("Another line for the logfile");
cout << "Done - check /LOGS/2011/JAN/LOGFILE.TXT on the SD" << endl;
}
//------------------------------------------------------------------------------
void loop() {}

View file

@ -0,0 +1,74 @@
// Demo of fgets function to read lines from a file.
#include <SdFat.h>
// SD chip select pin
const uint8_t chipSelect = SS;
SdFat sd;
// print stream
ArduinoOutStream cout(Serial);
//------------------------------------------------------------------------------
// store error strings in flash memory
#define error(s) sd.errorHalt_P(PSTR(s))
//------------------------------------------------------------------------------
void demoFgets() {
char line[25];
int n;
// open test file
SdFile rdfile("FGETS.TXT", O_READ);
// check for open error
if (!rdfile.isOpen()) error("demoFgets");
cout << endl << pstr(
"Lines with '>' end with a '\\n' character\n"
"Lines with '#' do not end with a '\\n' character\n"
"\n");
// read lines from the file
while ((n = rdfile.fgets(line, sizeof(line))) > 0) {
if (line[n - 1] == '\n') {
cout << '>' << line;
} else {
cout << '#' << line << endl;
}
}
}
//------------------------------------------------------------------------------
void makeTestFile() {
// create or open test file
SdFile wrfile("FGETS.TXT", O_WRITE | O_CREAT | O_TRUNC);
// check for open error
if (!wrfile.isOpen()) error("MakeTestFile");
// write test file
wrfile.write_P(PSTR(
"Line with CRLF\r\n"
"Line with only LF\n"
"Long line that will require an extra read\n"
"\n" // empty line
"Line at EOF without NL"
));
wrfile.close();
}
//------------------------------------------------------------------------------
void setup(void) {
Serial.begin(9600);
while (!Serial) {} // Wait for Leonardo
cout << pstr("Type any character to start\n");
while (Serial.read() <= 0) {}
delay(400); // catch Due reset problem
// initialize the SD card at SPI_HALF_SPEED to avoid bus errors with
// breadboards. use SPI_FULL_SPEED for better performance.
if (!sd.begin(chipSelect, SPI_HALF_SPEED)) sd.initErrorHalt();
makeTestFile();
demoFgets();
cout << pstr("\nDone\n");
}
void loop(void) {}

View file

@ -0,0 +1,91 @@
// Demo of rewriting a line read by fgets
#include <SdFat.h>
// SD card chip select pin
const uint8_t chipSelect = SS;
// file system
SdFat sd;
// print stream
ArduinoOutStream cout(Serial);
//------------------------------------------------------------------------------
// store error strings in flash memory
#define error(s) sd.errorHalt_P(PSTR(s))
//------------------------------------------------------------------------------
void demoFgets() {
char line[25];
int c;
uint32_t pos;
// open test file
SdFile rdfile("FGETS.TXT", O_RDWR);
// check for open error
if (!rdfile.isOpen()) error("demoFgets");
// list file
cout << pstr("-----Before Rewrite\r\n");
while ((c = rdfile.read()) >= 0) Serial.write(c);
rdfile.rewind();
// read lines from the file to get position
while (1) {
pos = rdfile.curPosition();
if (rdfile.fgets(line, sizeof(line)) < 0) {
error("Line not found");
}
// find line that contains "Line C"
if (strstr(line, "Line C"))break;
}
// rewrite line with 'C'
if (!rdfile.seekSet(pos))error("seekSet");
rdfile.println("Line R");
rdfile.rewind();
// list file
cout << pstr("\r\n-----After Rewrite\r\n");
while ((c = rdfile.read()) >= 0) Serial.write(c);
// close so rewrite is not lost
rdfile.close();
}
//------------------------------------------------------------------------------
void makeTestFile() {
// create or open test file
SdFile wrfile("FGETS.TXT", O_WRITE | O_CREAT | O_TRUNC);
// check for open error
if (!wrfile.isOpen()) error("MakeTestFile");
// write test file
wrfile.write_P(PSTR(
"Line A\r\n"
"Line B\r\n"
"Line C\r\n"
"Line D\r\n"
"Line E\r\n"
));
wrfile.close();
}
//------------------------------------------------------------------------------
void setup(void) {
Serial.begin(9600);
while (!Serial){} // wait for Leonardo
cout << pstr("Type any character to start\n");
while (Serial.read() <= 0) {}
delay(400); // catch Due reset problem
// initialize the SD card at SPI_HALF_SPEED to avoid bus errors with
// breadboards. use SPI_FULL_SPEED for better performance.
if (!sd.begin(chipSelect, SPI_HALF_SPEED)) sd.initErrorHalt();
makeTestFile();
demoFgets();
cout << pstr("\nDone\n");
}
void loop(void) {}

View file

@ -0,0 +1,66 @@
/*
* Print a table with various formatting options
* Format dates
*/
#include <SdFat.h>
// create Serial stream
ArduinoOutStream cout(Serial);
//------------------------------------------------------------------------------
// print a table to demonstrate format manipulators
void example(void) {
const int max = 10;
const int width = 4;
for (int row = 1; row <= max; row++) {
for (int col = 1; col <= max; col++) {
cout << setw(width) << row * col << (col == max ? '\n' : ' ');
}
}
cout << endl;
}
//------------------------------------------------------------------------------
// print a date as mm/dd/yyyy with zero fill in mm and dd
// shows how to set and restore the fill character
void showDate(int m, int d, int y) {
// convert two digit year
if (y < 100) y += 2000;
// set new fill to '0' save old fill character
char old = cout.fill('0');
// print date
cout << setw(2) << m << '/' << setw(2) << d << '/' << y << endl;
// restore old fill character
cout.fill(old);
}
//------------------------------------------------------------------------------
void setup(void) {
Serial.begin(9600);
while (!Serial) {} // wait for Leonardo
delay(2000);
cout << endl << "default formatting" << endl;
example();
cout << showpos << "showpos" << endl;
example();
cout << hex << left << showbase << "hex left showbase" << endl;
example();
cout << internal << setfill('0') << uppercase;
cout << "uppercase hex internal showbase fill('0')" <<endl;
example();
// restore default format flags and fill character
cout.flags(ios::dec | ios::right | ios::skipws);
cout.fill(' ');
cout << "showDate example" <<endl;
showDate(7, 4, 11);
showDate(12, 25, 11);
}
void loop(void) {}

View file

@ -0,0 +1,75 @@
/*
* Example of getline from section 27.7.1.3 of the C++ standard
* Demonstrates the behavior of getline for various exceptions.
* See http://www.cplusplus.com/reference/iostream/istream/getline/
*
* Note: This example is meant to demonstrate subtleties the standard and
* may not the best way to read a file.
*/
#include <SdFat.h>
// SD chip select pin
const uint8_t chipSelect = SS;
// file system object
SdFat sd;
// create a serial stream
ArduinoOutStream cout(Serial);
//------------------------------------------------------------------------------
void makeTestFile() {
ofstream sdout("GETLINE.TXT");
// use flash for text to save RAM
sdout << pstr(
"short line\n"
"\n"
"17 character line\n"
"too long for buffer\n"
"line with no nl");
sdout.close();
}
//------------------------------------------------------------------------------
void testGetline() {
const int line_buffer_size = 18;
char buffer[line_buffer_size];
ifstream sdin("GETLINE.TXT");
int line_number = 0;
while (sdin.getline(buffer, line_buffer_size, '\n') || sdin.gcount()) {
int count = sdin.gcount();
if (sdin.fail()) {
cout << "Partial long line";
sdin.clear(sdin.rdstate() & ~ios_base::failbit);
} else if (sdin.eof()) {
cout << "Partial final line"; // sdin.fail() is false
} else {
count--; // Dont include newline in count
cout << "Line " << ++line_number;
}
cout << " (" << count << " chars): " << buffer << endl;
}
}
//------------------------------------------------------------------------------
void setup(void) {
Serial.begin(9600);
while (!Serial) {} // wait for Leonardo
// pstr stores strings in flash to save RAM
cout << pstr("Type any character to start\n");
while (Serial.read() <= 0) {}
delay(400); // catch Due reset problem
// initialize the SD card at SPI_HALF_SPEED to avoid bus errors with
// breadboards. use SPI_FULL_SPEED for better performance.
if (!sd.begin(chipSelect, SPI_HALF_SPEED)) sd.initErrorHalt();
// make the test file
makeTestFile();
// run the example
testGetline();
cout << "\nDone!\n";
}
//------------------------------------------------------------------------------
void loop(void) {}

View file

@ -0,0 +1,86 @@
/*
* This example reads a simple CSV, comma-separated values, file.
* Each line of the file has three values, a long and two floats.
*/
#include <SdFat.h>
// SD chip select pin
const uint8_t chipSelect = SS;
// file system object
SdFat sd;
// create Serial stream
ArduinoOutStream cout(Serial);
char fileName[] = "3V_FILE.CSV";
//------------------------------------------------------------------------------
// store error strings in flash to save RAM
#define error(s) sd.errorHalt_P(PSTR(s))
//------------------------------------------------------------------------------
// read and print CSV test file
void readFile() {
long lg;
float f1, f2;
char c1, c2;
// open input file
ifstream sdin(fileName);
// check for open error
if (!sdin.is_open()) error("open");
// read until input fails
while (sdin >> lg >> c1 >> f1 >> c2 >> f2) {
// error in line if not commas
if (c1 != ',' || c2 != ',') error("comma");
// print in six character wide columns
cout << setw(6) << lg << setw(6) << f1 << setw(6) << f2 << endl;
}
// Error in an input line if file is not at EOF.
if (!sdin.eof()) error("readFile");
}
//------------------------------------------------------------------------------
// write test file
void writeFile() {
// create or open and truncate output file
ofstream sdout(fileName);
// write file from string stored in flash
sdout << pstr(
"1,2.3,4.5\n"
"6,7.8,9.0\n"
"9,8.7,6.5\n"
"-4,-3.2,-1\n") << flush;
// check for any errors
if (!sdout) error("writeFile");
sdout.close();
}
//------------------------------------------------------------------------------
void setup() {
Serial.begin(9600);
while (!Serial) {} // wait for Leonardo
cout << pstr("Type any character to start\n");
while (Serial.read() <= 0) {}
delay(400); // catch Due reset problem
// initialize the SD card at SPI_HALF_SPEED to avoid bus errors with
// breadboards. use SPI_FULL_SPEED for better performance
if (!sd.begin(chipSelect, SPI_HALF_SPEED)) sd.initErrorHalt();
// create test file
writeFile();
cout << endl;
// read and print test
readFile();
cout << "\nDone!" << endl;
}
void loop() {}

View file

@ -0,0 +1,40 @@
/*
* Read the logfile created by the eventlog.pde example.
* Demo of pathnames and working directories
*/
#include <SdFat.h>
// SD chip select pin
const uint8_t chipSelect = SS;
// file system object
SdFat sd;
// define a serial output stream
ArduinoOutStream cout(Serial);
//------------------------------------------------------------------------------
void setup() {
int c;
Serial.begin(9600);
while (!Serial) {} // wait for Leonardo
// initialize the SD card at SPI_HALF_SPEED to avoid bus errors with
// breadboards. use SPI_FULL_SPEED for better performance.
if (!sd.begin(chipSelect, SPI_HALF_SPEED)) sd.initErrorHalt();
// set current working directory
if (!sd.chdir("LOGS/2011/JAN/")) {
sd.errorHalt("chdir failed. Did you run eventlog.pde?");
}
// open file in current working directory
ifstream file("LOGFILE.TXT");
if (!file.is_open()) sd.errorHalt("open failed");
// copy the file to Serial
while ((c = file.get()) >= 0) cout << (char)c;
cout << "Done" << endl;
}
//------------------------------------------------------------------------------
void loop() {}

View file

@ -0,0 +1,77 @@
/*
* This sketch demonstrates use of SdFile::rename()
* and SdFat::rename().
*/
#include <SdFat.h>
// SD chip select pin
const uint8_t chipSelect = SS;
// file system
SdFat sd;
// Serial print stream
ArduinoOutStream cout(Serial);
//------------------------------------------------------------------------------
// store error strings in flash to save RAM
#define error(s) sd.errorHalt_P(PSTR(s))
//------------------------------------------------------------------------------
void setup() {
Serial.begin(9600);
while (!Serial) {} // wait for Leonardo
cout << pstr("Insert an empty SD. Type any character to start.") << endl;
while (Serial.read() <= 0) {}
delay(400); // catch Due reset problem
// initialize the SD card at SPI_HALF_SPEED to avoid bus errors with
// breadboards. use SPI_FULL_SPEED for better performance.
if (!sd.begin(chipSelect, SPI_HALF_SPEED)) sd.initErrorHalt();
// create a file and write one line to the file
SdFile file("NAME1.TXT", O_WRITE | O_CREAT);
if (!file.isOpen()) error("NAME1");
file.println("A test line for NAME1.TXT");
// rename the file NAME2.TXT and add a line.
// sd.vwd() is the volume working directory, root.
if (!file.rename(sd.vwd(), "NAME2.TXT")) error("NAME2");
file.println("A test line for NAME2.TXT");
// list files
cout << pstr("------") << endl;
sd.ls(LS_R);
// make a new directory - "DIR1"
if (!sd.mkdir("DIR1")) error("DIR1");
// move file into DIR1, rename it NAME3.TXT and add a line
if (!file.rename(sd.vwd(), "DIR1/NAME3.TXT")) error("NAME3");
file.println("A line for DIR1/NAME3.TXT");
// list files
cout << pstr("------") << endl;
sd.ls(LS_R);
// make directory "DIR2"
if (!sd.mkdir("DIR2")) error("DIR2");
// close file before rename(oldPath, newPath)
file.close();
// move DIR1 into DIR2 and rename it DIR3
if (!sd.rename("DIR1", "DIR2/DIR3")) error("DIR2/DIR3");
// open file for append in new location and add a line
if (!file.open("DIR2/DIR3/NAME3.TXT", O_WRITE | O_APPEND)) {
error("DIR2/DIR3/NAME3.TXT");
}
file.println("A line for DIR2/DIR3/NAME3.TXT");
// list files
cout << pstr("------") << endl;
sd.ls(LS_R);
cout << pstr("Done") << endl;
}
void loop() {}

View file

@ -0,0 +1,394 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef ios_h
#define ios_h
#include <SdBaseFile.h>
/**
* \file
* \brief \ref ios_base and \ref ios classes
*/
//==============================================================================
/**
* \class ios_base
* \brief Base class for all streams
*/
class ios_base {
public:
/** typedef for iostate bitmask */
typedef unsigned char iostate;
// State flags.
/** iostate for no flags */
static const iostate goodbit = 0x00;
/** iostate bad bit for a nonrecoverable error. */
static const iostate badbit = 0X01;
/** iostate bit for end of file reached */
static const iostate eofbit = 0x02;
/** iostate fail bit for nonfatal error */
static const iostate failbit = 0X04;
/**
* unsigned size that can represent maximum file size.
* (violates spec - should be signed)
*/
typedef uint32_t streamsize;
/** type for absolute seek position */
typedef uint32_t pos_type;
/** type for relative seek offset */
typedef int32_t off_type;
/** enumerated type for the direction of relative seeks */
enum seekdir {
/** seek relative to the beginning of the stream */
beg,
/** seek relative to the current stream position */
cur,
/** seek relative to the end of the stream */
end
};
/** type for format flags */
typedef unsigned int fmtflags;
/** left adjust fields */
static const fmtflags left = 0x0001;
/** right adjust fields */
static const fmtflags right = 0x0002;
/** fill between sign/base prefix and number */
static const fmtflags internal = 0x0004;
/** base 10 flag*/
static const fmtflags dec = 0x0008;
/** base 16 flag */
static const fmtflags hex = 0x0010;
/** base 8 flag */
static const fmtflags oct = 0x0020;
// static const fmtflags fixed = 0x0040;
// static const fmtflags scientific = 0x0080;
/** use strings true/false for bool */
static const fmtflags boolalpha = 0x0100;
/** use prefix 0X for hex and 0 for oct */
static const fmtflags showbase = 0x0200;
/** always show '.' for floating numbers */
static const fmtflags showpoint = 0x0400;
/** show + sign for nonnegative numbers */
static const fmtflags showpos = 0x0800;
/** skip initial white space */
static const fmtflags skipws = 0x1000;
// static const fmtflags unitbuf = 0x2000;
/** use uppercase letters in number representations */
static const fmtflags uppercase = 0x4000;
/** mask for adjustfield */
static const fmtflags adjustfield = left | right | internal;
/** mask for basefield */
static const fmtflags basefield = dec | hex | oct;
// static const fmtflags floatfield = scientific | fixed;
//----------------------------------------------------------------------------
/** typedef for iostream open mode */
typedef uint8_t openmode;
// Openmode flags.
/** seek to end before each write */
static const openmode app = 0X4;
/** open and seek to end immediately after opening */
static const openmode ate = 0X8;
/** perform input and output in binary mode (as opposed to text mode) */
static const openmode binary = 0X10;
/** open for input */
static const openmode in = 0X20;
/** open for output */
static const openmode out = 0X40;
/** truncate an existing stream when opening */
static const openmode trunc = 0X80;
//----------------------------------------------------------------------------
ios_base() : fill_(' '), fmtflags_(dec | right | skipws)
, precision_(2), width_(0) {}
/** \return fill character */
char fill() {return fill_;}
/** Set fill character
* \param[in] c new fill character
* \return old fill character
*/
char fill(char c) {
char r = fill_;
fill_ = c;
return r;
}
/** \return format flags */
fmtflags flags() const {return fmtflags_;}
/** set format flags
* \param[in] fl new flag
* \return old flags
*/
fmtflags flags(fmtflags fl) {
fmtflags tmp = fmtflags_;
fmtflags_ = fl;
return tmp;
}
/** \return precision */
int precision() const {return precision_;}
/** set precision
* \param[in] n new precision
* \return old precision
*/
int precision(unsigned int n) {
int r = precision_;
precision_ = n;
return r;
}
/** set format flags
* \param[in] fl new flags to be or'ed in
* \return old flags
*/
fmtflags setf(fmtflags fl) {
fmtflags r = fmtflags_;
fmtflags_ |= fl;
return r;
}
/** modify format flags
* \param[in] mask flags to be removed
* \param[in] fl flags to be set after mask bits have been cleared
* \return old flags
*/
fmtflags setf(fmtflags fl, fmtflags mask) {
fmtflags r = fmtflags_;
fmtflags_ &= ~mask;
fmtflags_ |= fl;
return r;
}
/** clear format flags
* \param[in] fl flags to be cleared
* \return old flags
*/
void unsetf(fmtflags fl) {
fmtflags_ &= ~fl;
}
/** \return width */
unsigned width() {return width_;}
/** set width
* \param[in] n new width
* \return old width
*/
unsigned width(unsigned n) {
unsigned r = width_;
width_ = n;
return r;
}
protected:
/** \return current number base */
uint8_t flagsToBase() {
uint8_t f = flags() & basefield;
return f == oct ? 8 : f != hex ? 10 : 16;
}
private:
char fill_;
fmtflags fmtflags_;
unsigned char precision_;
unsigned int width_;
};
//------------------------------------------------------------------------------
/** function for boolalpha manipulator
* \param[in] str The stream
* \return The stream
*/
inline ios_base& boolalpha(ios_base& str) {
str.setf(ios_base::boolalpha);
return str;
}
/** function for dec manipulator
* \param[in] str The stream
* \return The stream
*/
inline ios_base& dec(ios_base& str) {
str.setf(ios_base::dec, ios_base::basefield);
return str;
}
/** function for hex manipulator
* \param[in] str The stream
* \return The stream
*/
inline ios_base& hex(ios_base& str) {
str.setf(ios_base::hex, ios_base::basefield);
return str;
}
/** function for internal manipulator
* \param[in] str The stream
* \return The stream
*/
inline ios_base& internal(ios_base& str) {
str.setf(ios_base::internal, ios_base::adjustfield);
return str;
}
/** function for left manipulator
* \param[in] str The stream
* \return The stream
*/
inline ios_base& left(ios_base& str) {
str.setf(ios_base::left, ios_base::adjustfield);
return str;
}
/** function for noboolalpha manipulator
* \param[in] str The stream
* \return The stream
*/
inline ios_base& noboolalpha(ios_base& str) {
str.unsetf(ios_base::boolalpha);
return str;
}
/** function for noshowbase manipulator
* \param[in] str The stream
* \return The stream
*/
inline ios_base& noshowbase(ios_base& str) {
str.unsetf(ios_base::showbase);
return str;
}
/** function for noshowpoint manipulator
* \param[in] str The stream
* \return The stream
*/
inline ios_base& noshowpoint(ios_base& str) {
str.unsetf(ios_base::showpoint);
return str;
}
/** function for noshowpos manipulator
* \param[in] str The stream
* \return The stream
*/
inline ios_base& noshowpos(ios_base& str) {
str.unsetf(ios_base::showpos);
return str;
}
/** function for noskipws manipulator
* \param[in] str The stream
* \return The stream
*/
inline ios_base& noskipws(ios_base& str) {
str.unsetf(ios_base::skipws);
return str;
}
/** function for nouppercase manipulator
* \param[in] str The stream
* \return The stream
*/
inline ios_base& nouppercase(ios_base& str) {
str.unsetf(ios_base::uppercase);
return str;
}
/** function for oct manipulator
* \param[in] str The stream
* \return The stream
*/
inline ios_base& oct(ios_base& str) {
str.setf(ios_base::oct, ios_base::basefield);
return str;
}
/** function for right manipulator
* \param[in] str The stream
* \return The stream
*/
inline ios_base& right(ios_base& str) {
str.setf(ios_base::right, ios_base::adjustfield);
return str;
}
/** function for showbase manipulator
* \param[in] str The stream
* \return The stream
*/
inline ios_base& showbase(ios_base& str) {
str.setf(ios_base::showbase);
return str;
}
/** function for showpos manipulator
* \param[in] str The stream
* \return The stream
*/
inline ios_base& showpos(ios_base& str) {
str.setf(ios_base::showpos);
return str;
}
/** function for showpoint manipulator
* \param[in] str The stream
* \return The stream
*/
inline ios_base& showpoint(ios_base& str) {
str.setf(ios_base::showpoint);
return str;
}
/** function for skipws manipulator
* \param[in] str The stream
* \return The stream
*/
inline ios_base& skipws(ios_base& str) {
str.setf(ios_base::skipws);
return str;
}
/** function for uppercase manipulator
* \param[in] str The stream
* \return The stream
*/
inline ios_base& uppercase(ios_base& str) {
str.setf(ios_base::uppercase);
return str;
}
//==============================================================================
/**
* \class ios
* \brief Error and state information for all streams
*/
class ios : public ios_base {
public:
/** Create ios with no error flags set */
ios() : iostate_(0) {}
/** \return null pointer if fail() is true. */
operator const void*() const {
return !fail() ? reinterpret_cast<const void*>(this) : 0;
}
/** \return true if fail() else false. */
bool operator!() const {return fail();}
/** \return The iostate flags for this file. */
iostate rdstate() const {return iostate_;}
/** \return True if no iostate flags are set else false. */
bool good() const {return iostate_ == goodbit;}
/** \return true if end of file has been reached else false.
*
* Warning: An empty file returns false before the first read.
*
* Moral: eof() is only useful in combination with fail(), to find out
* whether EOF was the cause for failure
*/
bool eof() const {return iostate_ & eofbit;}
/** \return true if any iostate bit other than eof are set else false. */
bool fail() const {return iostate_ & (failbit | badbit);}
/** \return true if bad bit is set else false. */
bool bad() const {return iostate_ & badbit;}
/** Clear iostate bits.
*
* \param[in] state The flags you want to set after clearing all flags.
**/
void clear(iostate state = goodbit) {iostate_ = state;}
/** Set iostate bits.
*
* \param[in] state Bitts to set.
**/
void setstate(iostate state) {iostate_ |= state;}
private:
iostate iostate_;
};
#endif // ios_h

View file

@ -0,0 +1,153 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef iostream_h
#define iostream_h
/**
* \file
* \brief \ref iostream class
*/
#include <istream.h>
#include <ostream.h>
/** Skip white space
* \param[in] is the Stream
* \return The stream
*/
inline istream& ws(istream& is) {
is.skipWhite();
return is;
}
/** insert endline
* \param[in] os The Stream
* \return The stream
*/
inline ostream& endl(ostream& os) {
os.put('\n');
#if ENDL_CALLS_FLUSH
os.flush();
#endif // ENDL_CALLS_FLUSH
return os;
}
/** flush manipulator
* \param[in] os The stream
* \return The stream
*/
inline ostream& flush(ostream& os) {
os.flush();
return os;
}
/**
* \struct setfill
* \brief type for setfill manipulator
*/
struct setfill {
/** fill character */
char c;
/** constructor
*
* \param[in] arg new fill character
*/
explicit setfill(char arg) : c(arg) {}
};
/** setfill manipulator
* \param[in] os the stream
* \param[in] arg set setfill object
* \return the stream
*/
inline ostream &operator<< (ostream &os, const setfill &arg) {
os.fill(arg.c);
return os;
}
/** setfill manipulator
* \param[in] obj the stream
* \param[in] arg set setfill object
* \return the stream
*/
inline istream &operator>>(istream &obj, const setfill &arg) {
obj.fill(arg.c);
return obj;
}
//------------------------------------------------------------------------------
/** \struct setprecision
* \brief type for setprecision manipulator
*/
struct setprecision {
/** precision */
unsigned int p;
/** constructor
* \param[in] arg new precision
*/
explicit setprecision(unsigned int arg) : p(arg) {}
};
/** setprecision manipulator
* \param[in] os the stream
* \param[in] arg set setprecision object
* \return the stream
*/
inline ostream &operator<< (ostream &os, const setprecision &arg) {
os.precision(arg.p);
return os;
}
/** setprecision manipulator
* \param[in] is the stream
* \param[in] arg set setprecision object
* \return the stream
*/
inline istream &operator>>(istream &is, const setprecision &arg) {
is.precision(arg.p);
return is;
}
//------------------------------------------------------------------------------
/** \struct setw
* \brief type for setw manipulator
*/
struct setw {
/** width */
unsigned w;
/** constructor
* \param[in] arg new width
*/
explicit setw(unsigned arg) : w(arg) {}
};
/** setw manipulator
* \param[in] os the stream
* \param[in] arg set setw object
* \return the stream
*/
inline ostream &operator<< (ostream &os, const setw &arg) {
os.width(arg.w);
return os;
}
/** setw manipulator
* \param[in] is the stream
* \param[in] arg set setw object
* \return the stream
*/
inline istream &operator>>(istream &is, const setw &arg) {
is.width(arg.w);
return is;
}
//==============================================================================
/**
* \class iostream
* \brief Input/Output stream
*/
class iostream : public istream, public ostream {
};
#endif // iostream_h

View file

@ -0,0 +1,411 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#include <float.h>
#include <istream.h>
//------------------------------------------------------------------------------
/**
* Extract a character if one is available.
*
* \return The character or -1 if a failure occurs. A failure is indicated
* by the stream state.
*/
int istream::get() {
int c;
gcount_ = 0;
c = getch();
if (c < 0) {
setstate(failbit);
} else {
gcount_ = 1;
}
return c;
}
//------------------------------------------------------------------------------
/**
* Extract a character if one is available.
*
* \param[out] c location to receive the extracted character.
*
* \return always returns *this. A failure is indicated by the stream state.
*/
istream& istream::get(char& c) {
int tmp = get();
if (tmp >= 0) c = tmp;
return *this;
}
//------------------------------------------------------------------------------
/**
* Extract characters.
*
* \param[out] str Location to receive extracted characters.
* \param[in] n Size of str.
* \param[in] delim Delimiter
*
* Characters are extracted until extraction fails, n is less than 1,
* n-1 characters are extracted, or the next character equals
* \a delim (delim is not extracted). If no characters are extracted
* failbit is set. If end-of-file occurs the eofbit is set.
*
* \return always returns *this. A failure is indicated by the stream state.
*/
istream& istream::get(char *str, streamsize n, char delim) {
int c;
FatPos_t pos;
gcount_ = 0;
while ((gcount_ + 1) < n) {
c = getch(&pos);
if (c < 0) {
break;
}
if (c == delim) {
setpos(&pos);
break;
}
str[gcount_++] = c;
}
if (n > 0) str[gcount_] = '\0';
if (gcount_ == 0) setstate(failbit);
return *this;
}
//------------------------------------------------------------------------------
void istream::getBool(bool *b) {
if ((flags() & boolalpha) == 0) {
getNumber(b);
return;
}
PGM_P truePtr = PSTR("true");
PGM_P falsePtr = PSTR("false");
const uint8_t true_len = 4;
const uint8_t false_len = 5;
bool trueOk = true;
bool falseOk = true;
uint8_t i = 0;
int c = readSkip();
while (1) {
falseOk = falseOk && c == pgm_read_byte(falsePtr + i);
trueOk = trueOk && c == pgm_read_byte(truePtr + i);
if (trueOk == false && falseOk == false) break;
i++;
if (trueOk && i == true_len) {
*b = true;
return;
}
if (falseOk && i == false_len) {
*b = false;
return;
}
c = getch();
}
setstate(failbit);
}
//------------------------------------------------------------------------------
void istream::getChar(char* ch) {
int16_t c = readSkip();
if (c < 0) {
setstate(failbit);
} else {
*ch = c;
}
}
//------------------------------------------------------------------------------
//
// http://www.exploringbinary.com/category/numbers-in-computers/
//
int16_t const EXP_LIMIT = 100;
static const uint32_t uint32_max = (uint32_t)-1;
bool istream::getDouble(double* value) {
bool got_digit = false;
bool got_dot = false;
bool neg;
int16_t c;
bool expNeg = false;
int16_t exp = 0;
int16_t fracExp = 0;
uint32_t frac = 0;
FatPos_t endPos;
double pow10;
double v;
getpos(&endPos);
c = readSkip();
neg = c == '-';
if (c == '-' || c == '+') {
c = getch();
}
while (1) {
if (isdigit(c)) {
got_digit = true;
if (frac < uint32_max/10) {
frac = frac * 10 + (c - '0');
if (got_dot) fracExp--;
} else {
if (!got_dot) fracExp++;
}
} else if (!got_dot && c == '.') {
got_dot = true;
} else {
break;
}
if (fracExp < -EXP_LIMIT || fracExp > EXP_LIMIT) goto fail;
c = getch(&endPos);
}
if (!got_digit) goto fail;
if (c == 'e' || c == 'E') {
c = getch();
expNeg = c == '-';
if (c == '-' || c == '+') {
c = getch();
}
while (isdigit(c)) {
if (exp > EXP_LIMIT) goto fail;
exp = exp * 10 + (c - '0');
c = getch(&endPos);
}
}
v = static_cast<double>(frac);
exp = expNeg ? fracExp - exp : fracExp + exp;
expNeg = exp < 0;
if (expNeg) exp = -exp;
pow10 = 10.0;
while (exp) {
if (exp & 1) {
if (expNeg) {
// check for underflow
if (v < FLT_MIN * pow10 && frac != 0) goto fail;
v /= pow10;
} else {
// check for overflow
if (v > FLT_MAX / pow10) goto fail;
v *= pow10;
}
}
pow10 *= pow10;
exp >>= 1;
}
setpos(&endPos);
*value = neg ? -v : v;
return true;
fail:
// error restore position to last good place
setpos(&endPos);
setstate(failbit);
return false;
}
//------------------------------------------------------------------------------
/**
* Extract characters
*
* \param[out] str Location to receive extracted characters.
* \param[in] n Size of str.
* \param[in] delim Delimiter
*
* Characters are extracted until extraction fails,
* the next character equals \a delim (delim is extracted), or n-1
* characters are extracted.
*
* The failbit is set if no characters are extracted or n-1 characters
* are extracted. If end-of-file occurs the eofbit is set.
*
* \return always returns *this. A failure is indicated by the stream state.
*/
istream& istream::getline(char *str, streamsize n, char delim) {
FatPos_t pos;
int c;
gcount_ = 0;
if (n > 0) str[0] = '\0';
while (1) {
c = getch(&pos);
if (c < 0) {
break;
}
if (c == delim) {
gcount_++;
break;
}
if ((gcount_ + 1) >= n) {
setpos(&pos);
setstate(failbit);
break;
}
str[gcount_++] = c;
str[gcount_] = '\0';
}
if (gcount_ == 0) setstate(failbit);
return *this;
}
//------------------------------------------------------------------------------
bool istream::getNumber(uint32_t posMax, uint32_t negMax, uint32_t* num) {
int16_t c;
int8_t any = 0;
int8_t have_zero = 0;
uint8_t neg;
uint32_t val = 0;
uint32_t cutoff;
uint8_t cutlim;
FatPos_t endPos;
uint8_t f = flags() & basefield;
uint8_t base = f == oct ? 8 : f != hex ? 10 : 16;
getpos(&endPos);
c = readSkip();
neg = c == '-' ? 1 : 0;
if (c == '-' || c == '+') {
c = getch();
}
if (base == 16 && c == '0') { // TESTSUITE
c = getch(&endPos);
if (c == 'X' || c == 'x') {
c = getch();
// remember zero in case no hex digits follow x/X
have_zero = 1;
} else {
any = 1;
}
}
// set values for overflow test
cutoff = neg ? negMax : posMax;
cutlim = cutoff % base;
cutoff /= base;
while (1) {
if (isdigit(c)) {
c -= '0';
} else if (isalpha(c)) {
c -= isupper(c) ? 'A' - 10 : 'a' - 10;
} else {
break;
}
if (c >= base) {
break;
}
if (val > cutoff || (val == cutoff && c > cutlim)) {
// indicate overflow error
any = -1;
break;
}
val = val * base + c;
c = getch(&endPos);
any = 1;
}
setpos(&endPos);
if (any > 0 || (have_zero && any >= 0)) {
*num = neg ? -val : val;
return true;
}
setstate(failbit);
return false;
}
//------------------------------------------------------------------------------
/**
*
*/
void istream::getStr(char *str) {
FatPos_t pos;
uint16_t i = 0;
uint16_t m = width() ? width() - 1 : 0XFFFE;
if (m != 0) {
getpos(&pos);
int c = readSkip();
while (i < m) {
if (c < 0) {
break;
}
if (isspace(c)) {
setpos(&pos);
break;
}
str[i++] = c;
c = getch(&pos);
}
}
str[i] = '\0';
if (i == 0) setstate(failbit);
width(0);
}
//------------------------------------------------------------------------------
/**
* Extract characters and discard them.
*
* \param[in] n maximum number of characters to ignore.
* \param[in] delim Delimiter.
*
* Characters are extracted until extraction fails, \a n characters
* are extracted, or the next input character equals \a delim
* (the delimiter is extracted). If end-of-file occurs the eofbit is set.
*
* Failures are indicated by the state of the stream.
*
* \return *this
*
*/
istream& istream::ignore(streamsize n, int delim) {
int c;
gcount_ = 0;
while (gcount_ < n) {
c = getch();
if (c < 0) {
break;
}
gcount_++;
if (c == delim) break;
}
return *this;
}
//------------------------------------------------------------------------------
/**
* Return the next available character without consuming it.
*
* \return The character if the stream state is good else -1;
*
*/
int istream::peek() {
int16_t c;
FatPos_t pos;
gcount_ = 0;
getpos(&pos);
c = getch();
if (c < 0) {
if (!bad()) setstate(eofbit);
} else {
setpos(&pos);
}
return c;
}
//------------------------------------------------------------------------------
int16_t istream::readSkip() {
int16_t c;
do {
c = getch();
} while (isspace(c) && (flags() & skipws));
return c;
}
//------------------------------------------------------------------------------
/** used to implement ws() */
void istream::skipWhite() {
int c;
FatPos_t pos;
do {
c = getch(&pos);
} while (isspace(c));
setpos(&pos);
}

View file

@ -0,0 +1,306 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef istream_h
#define istream_h
/**
* \file
* \brief \ref istream class
*/
#include <ios.h>
/**
* \class istream
* \brief Input Stream
*/
class istream : public virtual ios {
public:
istream() {}
/** call manipulator
* \param[in] pf function to call
* \return the stream
*/
istream& operator>>(istream& (*pf)(istream& str)) {
return pf(*this);
}
/** call manipulator
* \param[in] pf function to call
* \return the stream
*/
istream& operator>>(ios_base& (*pf)(ios_base& str)) {
pf(*this);
return *this;
}
/** call manipulator
* \param[in] pf function to call
* \return the stream
*/
istream& operator>>(ios& (*pf)(ios& str)) {
pf(*this);
return *this;
}
/**
* Extract a character string
* \param[out] str location to store the string.
* \return Is always *this. Failure is indicated by the state of *this.
*/
istream& operator>>(char *str) {
getStr(str);
return *this;
}
/**
* Extract a character
* \param[out] ch location to store the character.
* \return Is always *this. Failure is indicated by the state of *this.
*/
istream& operator>>(char& ch) {
getChar(&ch);
return *this;
}
/**
* Extract a character string
* \param[out] str location to store the string.
* \return Is always *this. Failure is indicated by the state of *this.
*/
istream& operator>>(signed char *str) {
getStr(reinterpret_cast<char*>(str));
return *this;
}
/**
* Extract a character
* \param[out] ch location to store the character.
* \return Is always *this. Failure is indicated by the state of *this.
*/
istream& operator>>(signed char& ch) {
getChar(reinterpret_cast<char*>(&ch));
return *this;
}
/**
* Extract a character string
* \param[out] str location to store the string.
* \return Is always *this. Failure is indicated by the state of *this.
*/
istream& operator>>(unsigned char *str) {
getStr(reinterpret_cast<char*>(str));
return *this;
}
/**
* Extract a character
* \param[out] ch location to store the character.
* \return Is always *this. Failure is indicated by the state of *this.
*/
istream& operator>>(unsigned char& ch) {
getChar(reinterpret_cast<char*>(&ch));
return *this;
}
/**
* Extract a value of type bool.
* \param[out] arg location to store the value.
* \return Is always *this. Failure is indicated by the state of *this.
*/
istream& operator>>(bool& arg) {
getBool(&arg);
return *this;
}
/**
* Extract a value of type short.
* \param[out] arg location to store the value.
* \return Is always *this. Failure is indicated by the state of *this.
*/
istream &operator>>(short& arg) { // NOLINT
getNumber(&arg);
return *this;
}
/**
* Extract a value of type unsigned short.
* \param[out] arg location to store the value.
* \return Is always *this. Failure is indicated by the state of *this.
*/
istream &operator>>(unsigned short& arg) { // NOLINT
getNumber(&arg);
return *this;
}
/**
* Extract a value of type int.
* \param[out] arg location to store the value.
* \return Is always *this. Failure is indicated by the state of *this.
*/
istream &operator>>(int& arg) {
getNumber(&arg);
return *this;
}
/**
* Extract a value of type unsigned int.
* \param[out] arg location to store the value.
* \return Is always *this. Failure is indicated by the state of *this.
*/
istream &operator>>(unsigned int& arg) {
getNumber(&arg);
return *this;
}
/**
* Extract a value of type long.
* \param[out] arg location to store the value.
* \return Is always *this. Failure is indicated by the state of *this.
*/
istream &operator>>(long& arg) { // NOLINT
getNumber(&arg);
return *this;
}
/**
* Extract a value of type unsigned long.
* \param[out] arg location to store the value.
* \return Is always *this. Failure is indicated by the state of *this.
*/
istream &operator>>(unsigned long& arg) { // NOLINT
getNumber(&arg);
return *this;
}
/**
* Extract a value of type double.
* \param[out] arg location to store the value.
* \return Is always *this. Failure is indicated by the state of *this.
*/
istream &operator>> (double& arg) {
getDouble(&arg);
return *this;
}
/**
* Extract a value of type float.
* \param[out] arg location to store the value.
* \return Is always *this. Failure is indicated by the state of *this.
*/
istream &operator>> (float& arg) {
double v;
getDouble(&v);
arg = v;
return *this;
}
/**
* Extract a value of type void*.
* \param[out] arg location to store the value.
* \return Is always *this. Failure is indicated by the state of *this.
*/
istream& operator>> (void*& arg) {
uint32_t val;
getNumber(&val);
arg = reinterpret_cast<void*>(val);
return *this;
}
/**
* \return The number of characters extracted by the last unformatted
* input function.
*/
streamsize gcount() const {return gcount_;}
int get();
istream& get(char& ch);
istream& get(char *str, streamsize n, char delim = '\n');
istream& getline(char *str, streamsize count, char delim = '\n');
istream& ignore(streamsize n = 1, int delim= -1);
int peek();
// istream& read(char *str, streamsize count);
// streamsize readsome(char *str, streamsize count);
/**
* \return the stream position
*/
pos_type tellg() {return tellpos();}
/**
* Set the stream position
* \param[in] pos The absolute position in which to move the read pointer.
* \return Is always *this. Failure is indicated by the state of *this.
*/
istream& seekg(pos_type pos) {
if (!seekpos(pos)) setstate(failbit);
return *this;
}
/**
* Set the stream position.
*
* \param[in] off An offset to move the read pointer relative to way.
* \a off is a signed 32-bit int so the offset is limited to +- 2GB.
* \param[in] way One of ios::beg, ios::cur, or ios::end.
* \return Is always *this. Failure is indicated by the state of *this.
*/
istream& seekg(off_type off, seekdir way) {
if (!seekoff(off, way)) setstate(failbit);
return *this;
}
void skipWhite();
protected:
/// @cond SHOW_PROTECTED
/**
* Internal - do not use
* \return
*/
virtual int16_t getch() = 0;
/**
* Internal - do not use
* \param[out] pos
* \return
*/
int16_t getch(FatPos_t* pos) {
getpos(pos);
return getch();
}
/**
* Internal - do not use
* \param[out] pos
*/
virtual void getpos(FatPos_t* pos) = 0;
/**
* Internal - do not use
* \param[in] pos
*/
virtual bool seekoff(off_type off, seekdir way) = 0;
virtual bool seekpos(pos_type pos) = 0;
virtual void setpos(FatPos_t* pos) = 0;
virtual pos_type tellpos() = 0;
/// @endcond
private:
size_t gcount_;
void getBool(bool *b);
void getChar(char* ch);
bool getDouble(double* value);
template <typename T> void getNumber(T* value);
bool getNumber(uint32_t posMax, uint32_t negMax, uint32_t* num);
void getStr(char *str);
int16_t readSkip();
};
//------------------------------------------------------------------------------
template <typename T>
void istream::getNumber(T* value) {
uint32_t tmp;
if ((T)-1 < 0) {
// number is signed, max positive value
uint32_t const m = ((uint32_t)-1) >> (33 - sizeof(T) * 8);
// max absolute value of negative number is m + 1.
if (getNumber(m, m + 1, &tmp)) {
*value = (T)tmp;
}
} else {
// max unsigned value for T
uint32_t const m = (T)-1;
if (getNumber(m, m, &tmp)) {
*value = (T)tmp;
}
}
}
#endif // istream_h

View file

@ -0,0 +1,176 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#include <ostream.h>
#ifndef PSTR
#define PSTR(x) x
#endif
//------------------------------------------------------------------------------
void ostream::do_fill(unsigned len) {
for (; len < width(); len++) putch(fill());
width(0);
}
//------------------------------------------------------------------------------
void ostream::fill_not_left(unsigned len) {
if ((flags() & adjustfield) != left) {
do_fill(len);
}
}
//------------------------------------------------------------------------------
char* ostream::fmtNum(uint32_t n, char *ptr, uint8_t base) {
char a = flags() & uppercase ? 'A' - 10 : 'a' - 10;
do {
uint32_t m = n;
n /= base;
char c = m - base * n;
*--ptr = c < 10 ? c + '0' : c + a;
} while (n);
return ptr;
}
//------------------------------------------------------------------------------
void ostream::putBool(bool b) {
if (flags() & boolalpha) {
if (b) {
putPgm(PSTR("true"));
} else {
putPgm(PSTR("false"));
}
} else {
putChar(b ? '1' : '0');
}
}
//------------------------------------------------------------------------------
void ostream::putChar(char c) {
fill_not_left(1);
putch(c);
do_fill(1);
}
//------------------------------------------------------------------------------
void ostream::putDouble(double n) {
uint8_t nd = precision();
double round = 0.5;
char sign;
char buf[13]; // room for sign, 10 digits, '.', and zero byte
char *end = buf + sizeof(buf) - 1;
char *str = end;
// terminate string
*end = '\0';
// get sign and make nonnegative
if (n < 0.0) {
sign = '-';
n = -n;
} else {
sign = flags() & showpos ? '+' : '\0';
}
// check for larger than uint32_t
if (n > 4.0E9) {
putPgm(PSTR("BIG FLT"));
return;
}
// round up and separate in and fraction parts
for (uint8_t i = 0; i < nd; ++i) round *= 0.1;
n += round;
uint32_t intPart = n;
double fractionPart = n - intPart;
// format intPart and decimal point
if (nd || (flags() & showpoint)) *--str = '.';
str = fmtNum(intPart, str, 10);
// calculate length for fill
uint8_t len = sign ? 1 : 0;
len += nd + end - str;
// extract adjust field
fmtflags adj = flags() & adjustfield;
if (adj == internal) {
if (sign) putch(sign);
do_fill(len);
} else {
// do fill for internal or right
fill_not_left(len);
if (sign) *--str = sign;
}
putstr(str);
// output fraction
while (nd-- > 0) {
fractionPart *= 10.0;
int digit = static_cast<int>(fractionPart);
putch(digit + '0');
fractionPart -= digit;
}
// do fill if not done above
do_fill(len);
}
//------------------------------------------------------------------------------
void ostream::putNum(int32_t n) {
bool neg = n < 0 && flagsToBase() == 10;
if (neg) n = -n;
putNum(n, neg);
}
//------------------------------------------------------------------------------
void ostream::putNum(uint32_t n, bool neg) {
char buf[13];
char* end = buf + sizeof(buf) - 1;
char* num;
char* str;
uint8_t base = flagsToBase();
*end = '\0';
str = num = fmtNum(n, end, base);
if (base == 10) {
if (neg) {
*--str = '-';
} else if (flags() & showpos) {
*--str = '+';
}
} else if (flags() & showbase) {
if (flags() & hex) {
*--str = flags() & uppercase ? 'X' : 'x';
}
*--str = '0';
}
uint8_t len = end - str;
fmtflags adj = flags() & adjustfield;
if (adj == internal) {
while (str < num) putch(*str++);
}
if (adj != left) {
do_fill(len);
}
putstr(str);
do_fill(len);
}
//------------------------------------------------------------------------------
void ostream::putPgm(const char* str) {
int n;
for (n = 0; pgm_read_byte(&str[n]); n++) {}
fill_not_left(n);
for (uint8_t c; (c = pgm_read_byte(str)); str++) {
putch(c);
}
do_fill(n);
}
//------------------------------------------------------------------------------
void ostream::putStr(const char *str) {
unsigned n = strlen(str);
fill_not_left(n);
putstr(str);
do_fill(n);
}

View file

@ -0,0 +1,287 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef ostream_h
#define ostream_h
/**
* \file
* \brief \ref ostream class
*/
#include <ios.h>
//------------------------------------------------------------------------------
/** macro for flash inserter */
#define pstr(str) pgm(PSTR(str))
/** \struct pgm
* \brief type for string in flash
*/
struct pgm {
/** Pointer to flash string */
char *ptr;
/** constructor
* \param[in] str initializer for pointer.
*/
explicit pgm(char* str) : ptr(str) {}
/** constructor
* \param[in] str initializer for pointer.
*/
explicit pgm(const char *str) : ptr(const_cast<char*>(str)) {}
};
//==============================================================================
/**
* \class ostream
* \brief Output Stream
*/
class ostream : public virtual ios {
public:
ostream() {}
/** call manipulator
* \param[in] pf function to call
* \return the stream
*/
ostream& operator<< (ostream& (*pf)(ostream& str)) {
return pf(*this);
}
/** call manipulator
* \param[in] pf function to call
* \return the stream
*/
ostream& operator<< (ios_base& (*pf)(ios_base& str)) {
pf(*this);
return *this;
}
/** Output bool
* \param[in] arg value to output
* \return the stream
*/
ostream &operator<< (bool arg) {
putBool(arg);
return *this;
}
/** Output string
* \param[in] arg string to output
* \return the stream
*/
ostream &operator<< (const char *arg) {
putStr(arg);
return *this;
}
/** Output string
* \param[in] arg string to output
* \return the stream
*/
ostream &operator<< (const signed char *arg) {
putStr((const char*)arg);
return *this;
}
/** Output string
* \param[in] arg string to output
* \return the stream
*/
ostream &operator<< (const unsigned char *arg) {
putStr((const char*)arg);
return *this;
}
/** Output character
* \param[in] arg character to output
* \return the stream
*/
ostream &operator<< (char arg) {
putChar(arg);
return *this;
}
/** Output character
* \param[in] arg character to output
* \return the stream
*/
ostream &operator<< (signed char arg) {
putChar(static_cast<char>(arg));
return *this;
}
/** Output character
* \param[in] arg character to output
* \return the stream
*/
ostream &operator<< (unsigned char arg) {
putChar(static_cast<char>(arg));
return *this;
}
/** Output double
* \param[in] arg value to output
* \return the stream
*/
ostream &operator<< (double arg) {
putDouble(arg);
return *this;
}
/** Output float
* \param[in] arg value to output
* \return the stream
*/
ostream &operator<< (float arg) {
putDouble(arg);
return *this;
}
/** Output signed short
* \param[in] arg value to output
* \return the stream
*/
ostream &operator<< (short arg) { // NOLINT
putNum((int32_t)arg);
return *this;
}
/** Output unsigned short
* \param[in] arg value to output
* \return the stream
*/
ostream &operator<< (unsigned short arg) { // NOLINT
putNum((uint32_t)arg);
return *this;
}
/** Output signed int
* \param[in] arg value to output
* \return the stream
*/
ostream &operator<< (int arg) {
putNum((int32_t)arg);
return *this;
}
/** Output unsigned int
* \param[in] arg value to output
* \return the stream
*/
ostream &operator<< (unsigned int arg) {
putNum((uint32_t)arg);
return *this;
}
/** Output signed long
* \param[in] arg value to output
* \return the stream
*/
ostream &operator<< (long arg) { // NOLINT
putNum(arg);
return *this;
}
/** Output unsigned long
* \param[in] arg value to output
* \return the stream
*/
ostream &operator<< (unsigned long arg) { // NOLINT
putNum(arg);
return *this;
}
/** Output pointer
* \param[in] arg value to output
* \return the stream
*/
ostream& operator<< (const void* arg) {
putNum(reinterpret_cast<uint32_t>(arg));
return *this;
}
/** Output a string from flash using the pstr() macro
* \param[in] arg pgm struct pointing to string
* \return the stream
*/
ostream &operator<< (pgm arg) {
putPgm(arg.ptr);
return *this;
}
/** Output a string from flash using the Arduino F() macro.
* \param[in] arg pointing to flash string
* \return the stream
*/
ostream &operator<< (const __FlashStringHelper *arg) {
putPgm(reinterpret_cast<const char*>(arg));
return *this;
}
/**
* Puts a character in a stream.
*
* The unformatted output function inserts the element \a ch.
* It returns *this.
*
* \param[in] ch The character
* \return A reference to the ostream object.
*/
ostream& put(char ch) {
putch(ch);
return *this;
}
// ostream& write(char *str, streamsize count);
/**
* Flushes the buffer associated with this stream. The flush function
* calls the sync function of the associated file.
* \return A reference to the ostream object.
*/
ostream& flush() {
if (!sync()) setstate(badbit);
return *this;
}
/**
* \return the stream position
*/
pos_type tellp() {return tellpos();}
/**
* Set the stream position
* \param[in] pos The absolute position in which to move the write pointer.
* \return Is always *this. Failure is indicated by the state of *this.
*/
ostream& seekp(pos_type pos) {
if (!seekpos(pos)) setstate(failbit);
return *this;
}
/**
* Set the stream position.
*
* \param[in] off An offset to move the write pointer relative to way.
* \a off is a signed 32-bit int so the offset is limited to +- 2GB.
* \param[in] way One of ios::beg, ios::cur, or ios::end.
* \return Is always *this. Failure is indicated by the state of *this.
*/
ostream& seekp(off_type off, seekdir way) {
if (!seekoff(off, way)) setstate(failbit);
return *this;
}
protected:
/// @cond SHOW_PROTECTED
/** Put character with binary/text conversion
* \param[in] ch character to write
*/
virtual void putch(char ch) = 0;
virtual void putstr(const char *str) = 0;
virtual bool seekoff(off_type pos, seekdir way) = 0;
virtual bool seekpos(pos_type pos) = 0;
virtual bool sync() = 0;
virtual pos_type tellpos() = 0;
/// @endcond
private:
void do_fill(unsigned len);
void fill_not_left(unsigned len);
char* fmtNum(uint32_t n, char *ptr, uint8_t base);
void putBool(bool b);
void putChar(char c);
void putDouble(double n);
void putNum(uint32_t n, bool neg = false);
void putNum(int32_t n);
void putPgm(const char* str);
void putStr(const char* str);
};
#endif // ostream_h

View file

@ -0,0 +1,503 @@
/* Arduino DigitalPin Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino DigitalPin Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino DigitalPin Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
/**
* \file
* \brief DigitalPin class
*/
#ifndef DigitalPin_h
#define DigitalPin_h
#include <avr/io.h>
#include <util/atomic.h>
//------------------------------------------------------------------------------
/** DigitalPin version YYYYMMDD */
#define DIGITAL_PIN_VERSION 20120719
//------------------------------------------------------------------------------
/**
* \class pin_map_t
* \brief struct for mapping digital pins
*/
struct pin_map_t {
volatile uint8_t* ddr; /**< address of DDR for this pin */
volatile uint8_t* pin; /**< address of PIN for this pin */
volatile uint8_t* port; /**< address of PORT for this pin */
uint8_t bit; /**< bit number for this pin */
};
//------------------------------------------------------------------------------
#if defined(__AVR_ATmega168__)\
||defined(__AVR_ATmega168P__)\
||defined(__AVR_ATmega328P__)
// 168 and 328 Arduinos
const static pin_map_t pinMap[] = {
{&DDRD, &PIND, &PORTD, 0}, // D0 0
{&DDRD, &PIND, &PORTD, 1}, // D1 1
{&DDRD, &PIND, &PORTD, 2}, // D2 2
{&DDRD, &PIND, &PORTD, 3}, // D3 3
{&DDRD, &PIND, &PORTD, 4}, // D4 4
{&DDRD, &PIND, &PORTD, 5}, // D5 5
{&DDRD, &PIND, &PORTD, 6}, // D6 6
{&DDRD, &PIND, &PORTD, 7}, // D7 7
{&DDRB, &PINB, &PORTB, 0}, // B0 8
{&DDRB, &PINB, &PORTB, 1}, // B1 9
{&DDRB, &PINB, &PORTB, 2}, // B2 10
{&DDRB, &PINB, &PORTB, 3}, // B3 11
{&DDRB, &PINB, &PORTB, 4}, // B4 12
{&DDRB, &PINB, &PORTB, 5}, // B5 13
{&DDRC, &PINC, &PORTC, 0}, // C0 14
{&DDRC, &PINC, &PORTC, 1}, // C1 15
{&DDRC, &PINC, &PORTC, 2}, // C2 16
{&DDRC, &PINC, &PORTC, 3}, // C3 17
{&DDRC, &PINC, &PORTC, 4}, // C4 18
{&DDRC, &PINC, &PORTC, 5} // C5 19
};
//------------------------------------------------------------------------------
#elif defined(__AVR_ATmega1280__)\
|| defined(__AVR_ATmega2560__)
// Mega
static const pin_map_t pinMap[] = {
{&DDRE, &PINE, &PORTE, 0}, // E0 0
{&DDRE, &PINE, &PORTE, 1}, // E1 1
{&DDRE, &PINE, &PORTE, 4}, // E4 2
{&DDRE, &PINE, &PORTE, 5}, // E5 3
{&DDRG, &PING, &PORTG, 5}, // G5 4
{&DDRE, &PINE, &PORTE, 3}, // E3 5
{&DDRH, &PINH, &PORTH, 3}, // H3 6
{&DDRH, &PINH, &PORTH, 4}, // H4 7
{&DDRH, &PINH, &PORTH, 5}, // H5 8
{&DDRH, &PINH, &PORTH, 6}, // H6 9
{&DDRB, &PINB, &PORTB, 4}, // B4 10
{&DDRB, &PINB, &PORTB, 5}, // B5 11
{&DDRB, &PINB, &PORTB, 6}, // B6 12
{&DDRB, &PINB, &PORTB, 7}, // B7 13
{&DDRJ, &PINJ, &PORTJ, 1}, // J1 14
{&DDRJ, &PINJ, &PORTJ, 0}, // J0 15
{&DDRH, &PINH, &PORTH, 1}, // H1 16
{&DDRH, &PINH, &PORTH, 0}, // H0 17
{&DDRD, &PIND, &PORTD, 3}, // D3 18
{&DDRD, &PIND, &PORTD, 2}, // D2 19
{&DDRD, &PIND, &PORTD, 1}, // D1 20
{&DDRD, &PIND, &PORTD, 0}, // D0 21
{&DDRA, &PINA, &PORTA, 0}, // A0 22
{&DDRA, &PINA, &PORTA, 1}, // A1 23
{&DDRA, &PINA, &PORTA, 2}, // A2 24
{&DDRA, &PINA, &PORTA, 3}, // A3 25
{&DDRA, &PINA, &PORTA, 4}, // A4 26
{&DDRA, &PINA, &PORTA, 5}, // A5 27
{&DDRA, &PINA, &PORTA, 6}, // A6 28
{&DDRA, &PINA, &PORTA, 7}, // A7 29
{&DDRC, &PINC, &PORTC, 7}, // C7 30
{&DDRC, &PINC, &PORTC, 6}, // C6 31
{&DDRC, &PINC, &PORTC, 5}, // C5 32
{&DDRC, &PINC, &PORTC, 4}, // C4 33
{&DDRC, &PINC, &PORTC, 3}, // C3 34
{&DDRC, &PINC, &PORTC, 2}, // C2 35
{&DDRC, &PINC, &PORTC, 1}, // C1 36
{&DDRC, &PINC, &PORTC, 0}, // C0 37
{&DDRD, &PIND, &PORTD, 7}, // D7 38
{&DDRG, &PING, &PORTG, 2}, // G2 39
{&DDRG, &PING, &PORTG, 1}, // G1 40
{&DDRG, &PING, &PORTG, 0}, // G0 41
{&DDRL, &PINL, &PORTL, 7}, // L7 42
{&DDRL, &PINL, &PORTL, 6}, // L6 43
{&DDRL, &PINL, &PORTL, 5}, // L5 44
{&DDRL, &PINL, &PORTL, 4}, // L4 45
{&DDRL, &PINL, &PORTL, 3}, // L3 46
{&DDRL, &PINL, &PORTL, 2}, // L2 47
{&DDRL, &PINL, &PORTL, 1}, // L1 48
{&DDRL, &PINL, &PORTL, 0}, // L0 49
{&DDRB, &PINB, &PORTB, 3}, // B3 50
{&DDRB, &PINB, &PORTB, 2}, // B2 51
{&DDRB, &PINB, &PORTB, 1}, // B1 52
{&DDRB, &PINB, &PORTB, 0}, // B0 53
{&DDRF, &PINF, &PORTF, 0}, // F0 54
{&DDRF, &PINF, &PORTF, 1}, // F1 55
{&DDRF, &PINF, &PORTF, 2}, // F2 56
{&DDRF, &PINF, &PORTF, 3}, // F3 57
{&DDRF, &PINF, &PORTF, 4}, // F4 58
{&DDRF, &PINF, &PORTF, 5}, // F5 59
{&DDRF, &PINF, &PORTF, 6}, // F6 60
{&DDRF, &PINF, &PORTF, 7}, // F7 61
{&DDRK, &PINK, &PORTK, 0}, // K0 62
{&DDRK, &PINK, &PORTK, 1}, // K1 63
{&DDRK, &PINK, &PORTK, 2}, // K2 64
{&DDRK, &PINK, &PORTK, 3}, // K3 65
{&DDRK, &PINK, &PORTK, 4}, // K4 66
{&DDRK, &PINK, &PORTK, 5}, // K5 67
{&DDRK, &PINK, &PORTK, 6}, // K6 68
{&DDRK, &PINK, &PORTK, 7} // K7 69
};
//------------------------------------------------------------------------------
#elif defined(__AVR_ATmega644P__)\
|| defined(__AVR_ATmega644__)\
|| defined(__AVR_ATmega1284P__)
// Sanguino
static const pin_map_t pinMap[] = {
{&DDRB, &PINB, &PORTB, 0}, // B0 0
{&DDRB, &PINB, &PORTB, 1}, // B1 1
{&DDRB, &PINB, &PORTB, 2}, // B2 2
{&DDRB, &PINB, &PORTB, 3}, // B3 3
{&DDRB, &PINB, &PORTB, 4}, // B4 4
{&DDRB, &PINB, &PORTB, 5}, // B5 5
{&DDRB, &PINB, &PORTB, 6}, // B6 6
{&DDRB, &PINB, &PORTB, 7}, // B7 7
{&DDRD, &PIND, &PORTD, 0}, // D0 8
{&DDRD, &PIND, &PORTD, 1}, // D1 9
{&DDRD, &PIND, &PORTD, 2}, // D2 10
{&DDRD, &PIND, &PORTD, 3}, // D3 11
{&DDRD, &PIND, &PORTD, 4}, // D4 12
{&DDRD, &PIND, &PORTD, 5}, // D5 13
{&DDRD, &PIND, &PORTD, 6}, // D6 14
{&DDRD, &PIND, &PORTD, 7}, // D7 15
{&DDRC, &PINC, &PORTC, 0}, // C0 16
{&DDRC, &PINC, &PORTC, 1}, // C1 17
{&DDRC, &PINC, &PORTC, 2}, // C2 18
{&DDRC, &PINC, &PORTC, 3}, // C3 19
{&DDRC, &PINC, &PORTC, 4}, // C4 20
{&DDRC, &PINC, &PORTC, 5}, // C5 21
{&DDRC, &PINC, &PORTC, 6}, // C6 22
{&DDRC, &PINC, &PORTC, 7}, // C7 23
{&DDRA, &PINA, &PORTA, 7}, // A7 24
{&DDRA, &PINA, &PORTA, 6}, // A6 25
{&DDRA, &PINA, &PORTA, 5}, // A5 26
{&DDRA, &PINA, &PORTA, 4}, // A4 27
{&DDRA, &PINA, &PORTA, 3}, // A3 28
{&DDRA, &PINA, &PORTA, 2}, // A2 29
{&DDRA, &PINA, &PORTA, 1}, // A1 30
{&DDRA, &PINA, &PORTA, 0} // A0 31
};
//------------------------------------------------------------------------------
#elif defined(__AVR_ATmega32U4__)
#ifdef CORE_TEENSY
// Teensy 2.0
static const pin_map_t pinMap[] = {
{&DDRB, &PINB, &PORTB, 0}, // B0 0
{&DDRB, &PINB, &PORTB, 1}, // B1 1
{&DDRB, &PINB, &PORTB, 2}, // B2 2
{&DDRB, &PINB, &PORTB, 3}, // B3 3
{&DDRB, &PINB, &PORTB, 7}, // B7 4
{&DDRD, &PIND, &PORTD, 0}, // D0 5
{&DDRD, &PIND, &PORTD, 1}, // D1 6
{&DDRD, &PIND, &PORTD, 2}, // D2 7
{&DDRD, &PIND, &PORTD, 3}, // D3 8
{&DDRC, &PINC, &PORTC, 6}, // C6 9
{&DDRC, &PINC, &PORTC, 7}, // C7 10
{&DDRD, &PIND, &PORTD, 6}, // D6 11
{&DDRD, &PIND, &PORTD, 7}, // D7 12
{&DDRB, &PINB, &PORTB, 4}, // B4 13
{&DDRB, &PINB, &PORTB, 5}, // B5 14
{&DDRB, &PINB, &PORTB, 6}, // B6 15
{&DDRF, &PINF, &PORTF, 7}, // F7 16
{&DDRF, &PINF, &PORTF, 6}, // F6 17
{&DDRF, &PINF, &PORTF, 5}, // F5 18
{&DDRF, &PINF, &PORTF, 4}, // F4 19
{&DDRF, &PINF, &PORTF, 1}, // F1 20
{&DDRF, &PINF, &PORTF, 0}, // F0 21
{&DDRD, &PIND, &PORTD, 4}, // D4 22
{&DDRD, &PIND, &PORTD, 5}, // D5 23
{&DDRE, &PINE, &PORTE, 6} // E6 24
};
//------------------------------------------------------------------------------
#else // CORE_TEENSY
// Leonardo
static const pin_map_t pinMap[] = {
{&DDRD, &PIND, &PORTD, 2}, // D2 0
{&DDRD, &PIND, &PORTD, 3}, // D3 1
{&DDRD, &PIND, &PORTD, 1}, // D1 2
{&DDRD, &PIND, &PORTD, 0}, // D0 3
{&DDRD, &PIND, &PORTD, 4}, // D4 4
{&DDRC, &PINC, &PORTC, 6}, // C6 5
{&DDRD, &PIND, &PORTD, 7}, // D7 6
{&DDRE, &PINE, &PORTE, 6}, // E6 7
{&DDRB, &PINB, &PORTB, 4}, // B4 8
{&DDRB, &PINB, &PORTB, 5}, // B5 9
{&DDRB, &PINB, &PORTB, 6}, // B6 10
{&DDRB, &PINB, &PORTB, 7}, // B7 11
{&DDRD, &PIND, &PORTD, 6}, // D6 12
{&DDRC, &PINC, &PORTC, 7}, // C7 13
{&DDRB, &PINB, &PORTB, 3}, // B3 14
{&DDRB, &PINB, &PORTB, 1}, // B1 15
{&DDRB, &PINB, &PORTB, 2}, // B2 16
{&DDRB, &PINB, &PORTB, 0}, // B0 17
{&DDRF, &PINF, &PORTF, 7}, // F7 18
{&DDRF, &PINF, &PORTF, 6}, // F6 19
{&DDRF, &PINF, &PORTF, 5}, // F5 20
{&DDRF, &PINF, &PORTF, 4}, // F4 21
{&DDRF, &PINF, &PORTF, 1}, // F1 22
{&DDRF, &PINF, &PORTF, 0}, // F0 23
{&DDRD, &PIND, &PORTD, 4}, // D4 24
{&DDRD, &PIND, &PORTD, 7}, // D7 25
{&DDRB, &PINB, &PORTB, 4}, // B4 26
{&DDRB, &PINB, &PORTB, 5}, // B5 27
{&DDRB, &PINB, &PORTB, 6}, // B6 28
{&DDRD, &PIND, &PORTD, 6} // D6 29
};
#endif // CORE_TEENSY
//------------------------------------------------------------------------------
#elif defined(__AVR_AT90USB646__)\
|| defined(__AVR_AT90USB1286__)
// Teensy++ 1.0 & 2.0
static const pin_map_t pinMap[] = {
{&DDRD, &PIND, &PORTD, 0}, // D0 0
{&DDRD, &PIND, &PORTD, 1}, // D1 1
{&DDRD, &PIND, &PORTD, 2}, // D2 2
{&DDRD, &PIND, &PORTD, 3}, // D3 3
{&DDRD, &PIND, &PORTD, 4}, // D4 4
{&DDRD, &PIND, &PORTD, 5}, // D5 5
{&DDRD, &PIND, &PORTD, 6}, // D6 6
{&DDRD, &PIND, &PORTD, 7}, // D7 7
{&DDRE, &PINE, &PORTE, 0}, // E0 8
{&DDRE, &PINE, &PORTE, 1}, // E1 9
{&DDRC, &PINC, &PORTC, 0}, // C0 10
{&DDRC, &PINC, &PORTC, 1}, // C1 11
{&DDRC, &PINC, &PORTC, 2}, // C2 12
{&DDRC, &PINC, &PORTC, 3}, // C3 13
{&DDRC, &PINC, &PORTC, 4}, // C4 14
{&DDRC, &PINC, &PORTC, 5}, // C5 15
{&DDRC, &PINC, &PORTC, 6}, // C6 16
{&DDRC, &PINC, &PORTC, 7}, // C7 17
{&DDRE, &PINE, &PORTE, 6}, // E6 18
{&DDRE, &PINE, &PORTE, 7}, // E7 19
{&DDRB, &PINB, &PORTB, 0}, // B0 20
{&DDRB, &PINB, &PORTB, 1}, // B1 21
{&DDRB, &PINB, &PORTB, 2}, // B2 22
{&DDRB, &PINB, &PORTB, 3}, // B3 23
{&DDRB, &PINB, &PORTB, 4}, // B4 24
{&DDRB, &PINB, &PORTB, 5}, // B5 25
{&DDRB, &PINB, &PORTB, 6}, // B6 26
{&DDRB, &PINB, &PORTB, 7}, // B7 27
{&DDRA, &PINA, &PORTA, 0}, // A0 28
{&DDRA, &PINA, &PORTA, 1}, // A1 29
{&DDRA, &PINA, &PORTA, 2}, // A2 30
{&DDRA, &PINA, &PORTA, 3}, // A3 31
{&DDRA, &PINA, &PORTA, 4}, // A4 32
{&DDRA, &PINA, &PORTA, 5}, // A5 33
{&DDRA, &PINA, &PORTA, 6}, // A6 34
{&DDRA, &PINA, &PORTA, 7}, // A7 35
{&DDRE, &PINE, &PORTE, 4}, // E4 36
{&DDRE, &PINE, &PORTE, 5}, // E5 37
{&DDRF, &PINF, &PORTF, 0}, // F0 38
{&DDRF, &PINF, &PORTF, 1}, // F1 39
{&DDRF, &PINF, &PORTF, 2}, // F2 40
{&DDRF, &PINF, &PORTF, 3}, // F3 41
{&DDRF, &PINF, &PORTF, 4}, // F4 42
{&DDRF, &PINF, &PORTF, 5}, // F5 43
{&DDRF, &PINF, &PORTF, 6}, // F6 44
{&DDRF, &PINF, &PORTF, 7} // F7 45
};
//------------------------------------------------------------------------------
#else // CPU type
#error unknown CPU type
#endif // CPU type
/** count of pins */
static const uint8_t digitalPinCount = sizeof(pinMap)/sizeof(pin_map_t);
//==============================================================================
/** generate bad pin number error
* \return Never called so never returns
*/
uint8_t badPinNumber(void)
__attribute__((error("Pin number is too large or not a constant")));
//------------------------------------------------------------------------------
/** fast write helper
* \param[in] address I/O register address
* \param[in] bit bit number to write
* \param[in] level value for bit
*/
static inline __attribute__((always_inline))
void fastBitWrite(volatile uint8_t* address, uint8_t bit, bool level) {
if (level) {
*address |= 1 << bit;
} else {
*address &= ~(1 << bit);
}
}
//------------------------------------------------------------------------------
/** fast write helper
* \param[in] address I/O register address
* \param[in] bit bit number to write
* \param[in] level value for bit
*/
static inline __attribute__((always_inline))
void fastBitWriteSafe(volatile uint8_t* address, uint8_t bit, bool level) {
uint8_t oldSREG;
if (address > (uint8_t*)0X5F) {
oldSREG = SREG;
cli();
}
fastBitWrite(address, bit, level);
if (address > (uint8_t*)0X5F) {
SREG = oldSREG;
}
}
//------------------------------------------------------------------------------
/** set pin mode
* \param[in] pin Arduino pin number
* \param[in] mode if true set write mode else read mode
*/
static inline __attribute__((always_inline))
void fastPinMode(uint8_t pin, bool mode) {
if (__builtin_constant_p(pin) && pin < digitalPinCount) {
fastBitWriteSafe(pinMap[pin].ddr,
pinMap[pin].bit, mode);
} else {
badPinNumber();
}
}
//------------------------------------------------------------------------------
/** read pin value
* \param[in] pin Arduino pin number
* \return value read
*/
static inline __attribute__((always_inline))
bool fastDigitalRead(uint8_t pin) {
if (__builtin_constant_p(pin) && pin < digitalPinCount) {
return (*pinMap[pin].pin >> pinMap[pin].bit) & 1;
} else {
return badPinNumber();
}
}
//------------------------------------------------------------------------------
/** Set pin value
* \param[in] pin Arduino pin number
* \param[in] level value to write
*/
static inline __attribute__((always_inline))
void fastDigitalWrite(uint8_t pin, bool level) {
if (__builtin_constant_p(pin) && pin < digitalPinCount) {
fastBitWriteSafe(pinMap[pin].port, pinMap[pin].bit, level);
} else {
badPinNumber();
}
}
//------------------------------------------------------------------------------
/** Set pin value in ISR
* \param[in] pin Arduino pin number
* \param[in] level value to write
*/
static inline __attribute__((always_inline))
void fastDigitalWriteISR(uint8_t pin, bool level) {
if (__builtin_constant_p(pin) && pin < digitalPinCount) {
fastBitWrite(pinMap[pin].port, pinMap[pin].bit, level);
} else {
badPinNumber();
}
}
//==============================================================================
/**
* \class DigitalPin
* \brief digital avr port I/O
*/
template<uint8_t PinNumber>
class DigitalPin {
public:
//----------------------------------------------------------------------------
/**
* Set pin level high if output mode or enable 20K pullup if input mode.
*/
void high() {write(true);}
//----------------------------------------------------------------------------
/** Set the pin mode to input. */
void inputMode() {
if ((uint16_t)pinMap[PinNumber].ddr > 0X5F) {
ATOMIC_BLOCK(ATOMIC_RESTORESTATE) {
isrInputMode();
}
} else {
isrInputMode();
}
}
//----------------------------------------------------------------------------
/** Set the pin mode to input.
* \param[in] pullup If true enable the pin's pullup else disable the pullup.
*/
void inputMode(bool pullup) {
if ((uint16_t)pinMap[PinNumber].ddr > 0X5F) {
ATOMIC_BLOCK(ATOMIC_RESTORESTATE) {
isrInputMode(pullup);
}
} else {
isrInputMode(pullup);
}
}
//----------------------------------------------------------------------------
/**
* Set pin level low if output mode or disable 20K pullup if input mode.
*/
void low() {write(false);}
//----------------------------------------------------------------------------
/** Set the pin's mode to output */
void outputMode() {
if ((uint16_t)pinMap[PinNumber].ddr > 0X5F) {
ATOMIC_BLOCK(ATOMIC_RESTORESTATE) {
isrOutputMode();
}
} else {
isrOutputMode();
}
}
//----------------------------------------------------------------------------
/** \return Pin's level */
bool read() {
return *pinMap[PinNumber].pin & (1 << pinMap[PinNumber].bit);
}
//----------------------------------------------------------------------------
/** Write the pin's level.
* \param[in] value If true set the pin's level high else set the
* pin's level low.
*/
void write(bool value) {
if ((uint16_t)pinMap[PinNumber].port > 0X5F) {
ATOMIC_BLOCK(ATOMIC_RESTORESTATE) {
isrWrite(value);
}
} else {
isrWrite(value);
}
}
private:
//----------------------------------------------------------------------------
void isrHigh() {
*pinMap[PinNumber].port |= 1 << pinMap[PinNumber].bit;
}
//----------------------------------------------------------------------------
void isrInputMode() {
*pinMap[PinNumber].ddr &= ~(1 << pinMap[PinNumber].bit);
}
//----------------------------------------------------------------------------
void isrInputMode(bool pullup) {
isrInputMode();
isrWrite(pullup);
}
//----------------------------------------------------------------------------
void isrLow() {
*pinMap[PinNumber].port &= ~(1 << pinMap[PinNumber].bit);
}
//----------------------------------------------------------------------------
void isrOutputMode() {
*pinMap[PinNumber].ddr |= 1 << pinMap[PinNumber].bit;
}
//----------------------------------------------------------------------------
void isrWrite(bool value) {
if (value) {
isrHigh();
} else {
isrLow();
}
}
};
#endif // DigitalPin_h

View file

@ -0,0 +1,120 @@
#ifndef SoftSPI_h
#define SoftSPI_h
#include <DigitalPin.h>
/** nop for timing */
#define nop asm volatile ("nop\n\t")
//------------------------------------------------------------------------------
/**
* \class SoftSPI
* \brief fast bit-bang SPI
*/
template<uint8_t MisoPin, uint8_t MosiPin, uint8_t SckPin, uint8_t Mode = 0>
class SoftSPI {
public:
//-----------------------------------------------------------------------------
/** initialize SoftSpi */
void begin() {
fastPinMode(MisoPin, false);
fastPinMode(MosiPin, true);
fastPinMode(SckPin, true);
fastDigitalWrite(SckPin, MODE_CPOL(Mode));
}
//----------------------------------------------------------------------------
/** Soft SPI receive byte
* \return byte received
*/
uint8_t receive() {
uint8_t data = 0;
receiveBit(7, &data);
receiveBit(6, &data);
receiveBit(5, &data);
receiveBit(4, &data);
receiveBit(3, &data);
receiveBit(2, &data);
receiveBit(1, &data);
receiveBit(0, &data);
return data;
}
//----------------------------------------------------------------------------
/** Soft SPI send byte
* \param[in] data byte to send
*/
void send(uint8_t data) {
sendBit(7, data);
sendBit(6, data);
sendBit(5, data);
sendBit(4, data);
sendBit(3, data);
sendBit(2, data);
sendBit(1, data);
sendBit(0, data);
}
//----------------------------------------------------------------------------
/** Soft SPI transfer byte
* \param[in] txData byte to send
* \return byte received
*/
inline __attribute__((always_inline))
uint8_t transfer(uint8_t txData) {
uint8_t rxData = 0;
transferBit(7, &rxData, txData);
transferBit(6, &rxData, txData);
transferBit(5, &rxData, txData);
transferBit(4, &rxData, txData);
transferBit(3, &rxData, txData);
transferBit(2, &rxData, txData);
transferBit(1, &rxData, txData);
transferBit(0, &rxData, txData);
return rxData;
}
private:
//----------------------------------------------------------------------------
inline __attribute__((always_inline))
bool MODE_CPHA(uint8_t mode) {return (mode & 1) != 0;}
inline __attribute__((always_inline))
bool MODE_CPOL(uint8_t mode) {return (mode & 2) != 0;}
inline __attribute__((always_inline))
void receiveBit(uint8_t bit, uint8_t* data) {
if (MODE_CPHA(Mode)) {
fastDigitalWrite(SckPin, !MODE_CPOL(Mode));
}
nop;nop;
fastDigitalWrite(SckPin,
MODE_CPHA(Mode) ? MODE_CPOL(Mode) : !MODE_CPOL(Mode));
if (fastDigitalRead(MisoPin)) *data |= 1 << bit;
if (!MODE_CPHA(Mode)) {
fastDigitalWrite(SckPin, MODE_CPOL(Mode));
}
}
//----------------------------------------------------------------------------
inline __attribute__((always_inline))
void sendBit(uint8_t bit, uint8_t data) {
if (MODE_CPHA(Mode)) {
fastDigitalWrite(SckPin, !MODE_CPOL(Mode));
}
fastDigitalWrite(MosiPin, data & (1 << bit));
fastDigitalWrite(SckPin,
MODE_CPHA(Mode) ? MODE_CPOL(Mode) : !MODE_CPOL(Mode));
nop;nop;
if (!MODE_CPHA(Mode)) {
fastDigitalWrite(SckPin, MODE_CPOL(Mode));
}
}
//----------------------------------------------------------------------------
inline __attribute__((always_inline))
void transferBit(uint8_t bit, uint8_t* rxData, uint8_t txData) {
if (MODE_CPHA(Mode)) {
fastDigitalWrite(SckPin, !MODE_CPOL(Mode));
}
fastDigitalWrite(MosiPin, txData & (1 << bit));
fastDigitalWrite(SckPin,
MODE_CPHA(Mode) ? MODE_CPOL(Mode) : !MODE_CPOL(Mode));
if (fastDigitalRead(MisoPin)) *rxData |= 1 << bit;
if (!MODE_CPHA(Mode)) {
fastDigitalWrite(SckPin, MODE_CPOL(Mode));
}
}
//----------------------------------------------------------------------------
};
#endif // SoftSPI_h

View file

@ -0,0 +1,440 @@
/* Arduino SoftRTClib Library
* Copyright (C) 2011 by William Greiman
*
* This file is part of the Arduino SoftRTClib Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SoftRTClib Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#include <avr/pgmspace.h>
#include <SoftRTClib.h>
#define EPOCH_YEAR DateTime::FIRST_YEAR
#include <utility/InlineDateAlgorithms.h>
//------------------------------------------------------------------------------
inline uint8_t bcd2bin (uint8_t val) {return val - 6 * (val >> 4);}
//------------------------------------------------------------------------------
inline uint8_t bin2bcd (uint8_t val) {return val + 6 * (val / 10);}
//------------------------------------------------------------------------------
// parse two digit field
static uint8_t c2b(const char *s) {
uint8_t b = '0' <= s[0] && s[0] <= '9' ? s[0] - '0' : 0;
return 10*b + s[1] - '0';
}
//------------------------------------------------------------------------------
// used by c2m and printMmm
static char Mmm[] PROGMEM = "JanFebMarAprMayJunJulAugSepOctNovDec";
//------------------------------------------------------------------------------
// convert Mmm string to [0,12]
static uint8_t c2m(const char* s) {
uint8_t m;
for (m = 0; m < 12; m ++) {
if (!strncmp_P(s, &Mmm[3*m], 3)) return m + 1;
}
return 0;
}
//------------------------------------------------------------------------------
// print two digit field with zero fill
static void print2d(Print* pr, uint8_t n) {
if (n < 10) pr->write('0');
pr->print(n, DEC);
}
//==============================================================================
// DateTime member functions
//------------------------------------------------------------------------------
/** \return Day of Week (Sunday == 0) */
int DateTime::dayOfWeek() const {
uint16_t eday = daysSinceEpoch(year_, month_, day_);
return epochDayToDayOfWeek(eday);
}
//------------------------------------------------------------------------------
/** \return Day of Year [0, 365] */
int DateTime::dayOfYear() const {
return daysBeforeMonth(year_, month_) + day_ - 1;
}
//------------------------------------------------------------------------------
/** Print day with zero fill
* \param[in] pr Print stream.
*/
void DateTime::printDD(Print* pr) const {
print2d(pr, day());
}
//------------------------------------------------------------------------------
/** Print date in DD Mmm YYYY format
* \param[in] pr Print stream.
*/
void DateTime::printDate(Print* pr) const {
print2d(pr, day());
pr->write(' ');
printMmm(pr);
pr->write(' ');
pr->print(year());
}
//------------------------------------------------------------------------------
/** Print date in DD Mmm YYYY format
* \param[in] pr Print stream.
*/
void DateTime::printDateTime(Print* pr) const {
printDate(pr);
pr->write(' ');
printIsoTime(pr);
}
//------------------------------------------------------------------------------
/** Print three character day of week
* \param[in] pr Print stream.
*/
void DateTime::printDdd(Print* pr) const {
static char Ddd[] PROGMEM = "SunMonTueWedThuFriSat";
char buf[4];
uint8_t w = dayOfWeek();
strncpy_P(buf, &Ddd[3*w], 3);
buf[3] = 0;
pr->write(buf);
}
//------------------------------------------------------------------------------
/** Print date in ISO YYY-MM-DD format.
* \param[in] pr Print stream.
*/
void DateTime::printIsoDate(Print* pr) const {
pr->print(year());
pr->write('-');
print2d(pr, month());
pr->write('-');
print2d(pr, day());
}
//------------------------------------------------------------------------------
/** Print date/time in ISO YYY-MM-DD hh:mm:ss format.
* \param[in] pr Print stream.
*/
void DateTime::printIsoDateTime(Print* pr) const {
printIsoDate(pr);
pr->write(' ');
printIsoTime(pr);
}
//------------------------------------------------------------------------------
/** Print time in ISO hh:mm:ss format.
* \param[in] pr Print stream.
*/
void DateTime::printIsoTime(Print* pr)const {
print2d(pr, hour());
pr->write(':');
print2d(pr, minute());
pr->write(':');
print2d(pr, second());
}
//------------------------------------------------------------------------------
/** Print month with zero fill
* \param[in] pr Print stream.
*/
void DateTime::printMM(Print* pr) const {
print2d(pr, month());
}
//------------------------------------------------------------------------------
/** Print three character month
* \param[in] pr Print stream.
*/
void DateTime::printMmm(Print* pr) const {
char buf[4];
strncpy_P(buf, &Mmm[3*month() - 3], 3);
buf[3] = 0;
pr->write(buf);
}
//------------------------------------------------------------------------------
/** Print date in USA MM/DD/YYYY format
* \param[in] pr Print stream .
*/
void DateTime::printUsaDate(Print* pr) const {
print2d(pr, month());
pr->write('/');
print2d(pr, day());
pr->write('/');
pr->print(year());
}
//------------------------------------------------------------------------------
/** Print date/time in USA MM/DD/YYYY hh:mm:ss format
* \param[in] pr Print stream .
*/
void DateTime::printUsaDateTime(Print* pr) const{
printUsaDate(pr);
pr->write(' ');
printIsoTime(pr);
}
//------------------------------------------------------------------------------
/** set time to epoch, 1/1/1970 00:00:00 */
void DateTime::settime() {
year_ = FIRST_YEAR;
month_ = 1;
day_ = 1;
hour_ = 0;
minute_ = 0;
second_ = 0;
}
//------------------------------------------------------------------------------
/** Convert posix seconds to broken-down time.
* \param[in] t Posix time in seconds since epoch.
* \return true for success else false
*/
bool DateTime::settime(time_t t) {
if (t < 0) return false;
int32_t tmp = t;
t /= 60L;
second_ = tmp - 60L * t;
tmp = t;
t /= 60L;
minute_ = tmp - 60L * t;
uint16_t days = t / 24L;
hour_ = t - 24L * days;
year_ = epochDayToYear(days);
days -= daysBeforeYear(year_);
month_ = dayOfYearToMonth(year_, days);
day_ = 1 + days - daysBeforeMonth(year_, month_);
return true;
}
//------------------------------------------------------------------------------
/** Set date time
* \param[in] year 1970 <= year <= 2037.
* \param[in] month 1 <= month <= 12.
* \param[in] day 1 <= day <= (days in month).
* \param[in] hour 0 <= hour <= 23.
* \param[in] minute 0 <= minute <= 59.
* \param[in] second 0 <= second <= 59.
* \return true for success or false for failure. Fails if invalid time/date.
*/
bool DateTime::settime(uint16_t year, uint8_t month, uint8_t day,
uint8_t hour, uint8_t minute, uint8_t second) {
if (hour > 23 || minute > 59 || second > 59
|| year < FIRST_YEAR || year > LAST_YEAR
|| month < 1 || month > 12
|| day < 1 || day > daysInMonth(year, month)) {
return false;
}
year_ = year;
month_ = month;
day_ = day;
hour_ = hour;
minute_ = minute;
second_ = second;
return true;
}
//------------------------------------------------------------------------------
/** Set date time using __DATE__ and __TIME__ strings
*
* \param[in] date string in __DATE__ format.
* \param[in] time string in __TIME__ format.
* \return true for success or false for failure. Fails if invalid time/date.
*/
bool DateTime::settime(const char* date, const char* time) {
return settime(2000 + c2b(date + 9), c2m(date), c2b(date + 4),
c2b(time), c2b(time + 3), c2b(time + 6));
}
//------------------------------------------------------------------------------
/** \return Posix time in seconds since 1 Jan 1970 00:00:00 */
time_t DateTime::time() const {
uint16_t days = daysSinceEpoch(year_, month_, day_);
return second_ + 60L * (minute_ + 60L * (hour_ + 24L * days));
}
//==============================================================================
/** read date time
*
* \param[out] dt destination for date time
*
* \return true if read is successful else false
*/
bool RTC_DS1307::getTime(DateTime* dt) {
uint8_t r[7];
if (!readTime(r)) return false;
dt->year_ = 2000 + r[6];
dt->month_ = r[5];
dt->day_ = r[4];
dt->hour_ = r[2];
dt->minute_ = r[1];
dt->second_ = r[0];
return true;
}
//------------------------------------------------------------------------------
/** \return true if no I/O error and DS1307 is running */
bool RTC_DS1307::isrunning(void) {
uint8_t r;
if (!read(0, &r, 1)) return false;
return !(r & 0x80);
}
//------------------------------------------------------------------------------
/** \return current DS1307 date and time */
DateTime RTC_DS1307::now() {
uint8_t r[7];
readTime(r);
return DateTime(2000 + r[6], r[5], r[4], r[2], r[1], r[0]);
}
//------------------------------------------------------------------------------
/**
* Read RTC time registers
* \param[out] r Location for return of seven RTC time registers.
* Values are converted from BCD to binary.
* \return true for success or false for failure.
*/
bool RTC_DS1307::readTime(uint8_t *r) {
if (!read(0, r, 7)) return false;
r[0] &= 0X7F;
for (uint8_t i = 0; i < 7; i++) r[i] = bcd2bin(r[i]);
return true;
}
//------------------------------------------------------------------------------
/** set mode for SQW/OUT pin
*
* \param[in] sqwMode DS1307_SQW_LOW, DS1307_SQW_HIGH, DS1307_SQW_1_HZ,
* DS1307_SQW_4096_HZ, DS1307_SQW_8192_HZ, or DS1307_SQW_32768_HZ
* \return true for success or false for failure.
*/
bool RTC_DS1307::setSQW(uint8_t sqwMode) {
return write(DS1307_CONTROL_ADDRESS, &sqwMode, 1);
}
//------------------------------------------------------------------------------
/** set date and time
* \param[in] dt date and time to be used.
* \return true for success or false for failure.
*/
bool RTC_DS1307::setTime(const DateTime* dt) {
uint8_t r[7];
r[0] = dt->second();
r[1] = dt->minute();
r[2] = dt->hour();
#if SET_RTC_DAY_OF_WEEK
r[3] = dt->isoDayOfWeek();
#else // SET_RTC_DAY_OF_WEEK
r[3] = 0;
#endif
r[4] = dt->day();
r[5] = dt->month();
r[6] = dt->year() % 100;
for (uint8_t i = 0; i < 7; i++) {
r[i] = bin2bcd(r[i]);
}
return write(0, r, 7);
}
//==============================================================================
#if DS_RTC_USE_WIRE
//------------------------------------------------------------------------------
/**
* Read data from the RTC.
*
* \param[in] address starting address.
* \param[out] buf Location for data.
* \param[in] count Number of bytes to write.
* \return The value true, 1, for success or false, 0, for failure.
*/
bool RTC_DS1307::read(uint8_t address, uint8_t *buf, uint8_t count) {
Wire.beginTransmission(DS_RTC_I2C_ADD/2);
#if ARDUINO < 100
Wire.send(0);
#else // ARDUINO < 100
Wire.write(0);
#endif // ARDUINO < 100
if (Wire.endTransmission()) return false;
Wire.requestFrom((uint8_t)(DS_RTC_I2C_ADD/2), count);
if (Wire.available() != count) return false;
for (uint8_t i = 0; i < count; i++) {
#if ARDUINO < 100
buf[i] = Wire.receive();
#else // ARDUINO < 100
buf[i] = Wire.read();
#endif // ARDUINO < 100
}
return true;
}
//------------------------------------------------------------------------------
/**
* Write data to the RTC.
*
* \param[in] address Starting address.
* \param[in] buf Location of data.
* \param[in] count Number of bytes to write.
* \return The value true, 1, for success or false, 0, for failure.
*/
bool RTC_DS1307::write(uint8_t address, uint8_t *buf, uint8_t count) {
Wire.beginTransmission(DS_RTC_I2C_ADD/2);
#if ARDUINO < 100
Wire.send(0);
Wire.send(buf, count);
#else // ARDUINO < 100
Wire.write(0);
Wire.write(buf, count);
#endif // ARDUINO < 100
return Wire.endTransmission() ? false : true;
}
#else // DS_RTC_USE_WIRE
//------------------------------------------------------------------------------
/**
* Read data from the RTC.
*
* \param[in] address starting address.
* \param[out] buf Location for data.
* \param[in] count Number of bytes to write.
* \return The value true, 1, for success or false, 0, for failure.
*/
bool RTC_DS1307::read(uint8_t address, uint8_t *buf, uint8_t count) {
// issue a start condition, send device address and write direction bit
if (!i2cBus_->start(DS_RTC_I2C_ADD | I2C_WRITE)) goto fail;
// send address
if (!i2cBus_->write(address)) goto fail;
// issue a repeated start condition, send device address and direction bit
if (!i2cBus_->restart(DS_RTC_I2C_ADD | I2C_READ)) goto fail;
// read data
for (uint8_t i = 0; i < count; i++) {
// send Ack until last byte then send Nak
buf[i] = i2cBus_->read(i == (count - 1));
}
// issue a stop condition
i2cBus_->stop();
return true;
fail:
i2cBus_->stop();
return false;
}
//------------------------------------------------------------------------------
/**
* Write data to the RTC.
*
* \param[in] address Starting address.
* \param[in] buf Location of data.
* \param[in] count Number of bytes to write.
* \return The value true, 1, for success or false, 0, for failure.
*/
bool RTC_DS1307::write(uint8_t address, uint8_t *buf, uint8_t count) {
// issue a start condition, send device address and write direction bit
if (!i2cBus_->start(DS_RTC_I2C_ADD | I2C_WRITE)) goto fail;
// send the address
if (!i2cBus_->write(address)) goto fail;
// send data
for (uint8_t i = 0; i < count; i++) {
if (!i2cBus_->write(buf[i])) goto fail;
}
// issue a stop condition
i2cBus_->stop();
return true;
fail:
i2cBus_->stop();
return false;
}
#endif // DS_RTC_USE_WIRE

View file

@ -0,0 +1,210 @@
/* Arduino SoftRTClib Library
* Copyright (C) 2011 by William Greiman
*
* This file is part of the Arduino SoftRTClib Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SoftRTClib Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
/*
* The API for this library was designed for easy use with programs
* that use the JeeLabs RTClib.
* http://news.jeelabs.org/code/
*/
/**
* \file
* \brief SoftRTClib header
*/
#ifndef SoftRTClib_h
#define SoftRTClib_h
// set nonzero to use Wire library
#define DS_RTC_USE_WIRE 0
#if DS_RTC_USE_WIRE
#include <Wire.h>
#else // DS_RTC_USE_WIRE
#include <I2cMaster.h>
#endif // DS_RTC_USE_WIRE
//------------------------------------------------------------------------------
/**
* Set nonzero to set RTC internal day-of-week register
*/
#define SET_RTC_DAY_OF_WEEK 1
//------------------------------------------------------------------------------
#include <Print.h>
/** i2c 8-bit address for RTC. low bit is read/write */
uint8_t const DS_RTC_I2C_ADD = 0XD0;
/*
The DS1307 control register is used to control the operation of the SQW/OUT pin.
The SQW/OUT pin is open drain and requires an external pullup resistor. SQW/OUT
operates with either VCC or VBAT applied. The pullup voltage can be up to 5.5V
regardless of the voltage on VCC. If not used, this pin can be left floating.
07h DS1307 Control
+---+---+---+----+---+---+---+---+
|OUT| 0 | 0 |SQWE| 0 | 0 |RS1|RS2|
| 0 | 0 | 0 | 0 | 0 | 0 | 1 | 1 |
+---+---+---+----+---+---+---+---+
OUT SQWE RS1 RS2 SQW Pin
x 1 0 0 1 Hz
x 1 0 1 4096 Hz
x 1 1 0 8196 Hz
x 1 1 1 32768 Hz
1 0 x x high
0 0 x x low
*/
/** DS1307 control register address. */
uint8_t const DS1307_CONTROL_ADDRESS = 0X07;
/** DS1307 control register value for SQW pin low. */
uint8_t const DS1307_SQW_LOW = 0X00;
/** DS1307 control register value for SQW pin high. */
uint8_t const DS1307_SQW_HIGH = 0X80;
/** DS1307 control register value for 1 Hz square-wave on SQW pin. */
uint8_t const DS1307_SQW_1_HZ = 0X10;
/** DS1307 control register value for 4096 Hz square-wave on SQW pin. */
uint8_t const DS1307_SQW_4096_HZ = 0X11;
/** DS1307 control register value for 8192 Hz square-wave on SQW pin. */
uint8_t const DS1307_SQW_8192_HZ = 0X12;
/** DS1307 control register value for 32768 Hz square-wave on SQW pin. */
uint8_t const DS1307_SQW_32768_HZ = 0X13;
//------------------------------------------------------------------------------
/** typedef for seconds since epoch */
typedef int32_t time_t;
//------------------------------------------------------------------------------
/**
* \class DateTime
* \brief Class for date/time objects
*/
class DateTime {
public:
/** Year of posix epoch */
static const uint16_t FIRST_YEAR = 1970;
/** last year representable by int32_t */
static const uint16_t LAST_YEAR = FIRST_YEAR + 67;
//----------------------------------------------------------------------------
/** constructor */
DateTime() {settime();}
/** constructor
*
* \param[in] t Posix time in seconds since epoch.
*/
explicit DateTime(time_t t) {if (!settime(t)) settime();}
/** constructor
*
* \param[in] year [1970, 2037]
* \param[in] month [1, 12]
* \param[in] day [1, last day in month]
* \param[in] hour [0, 23]
* \param[in] minute [0, 59]
* \param[in] second [0, 59]
*/
DateTime(uint16_t year, uint8_t month, uint8_t day,
uint8_t hour, uint8_t minute, uint8_t second) {
if (!settime(year, month, day, hour, minute, second)) settime();
}
/** constructor
*
* \param[in] date string in __DATE__ format.
* \param[in] time string in __TIME__ format.
*/
DateTime(const char* date, const char* time) {
if (!settime(date, time)) settime();
}
//----------------------------------------------------------------------------
// inline functions
/** \return year */
int year() const {return year_;}
/** \return month [1, 12] */
int month() const {return month_;}
/** \return day [1, 31] */
int day() const {return day_;}
/** \return hour [0, 23] */
int hour() const {return hour_;}
/** \return hour 12-hour clock [1, 12] */
int hour12() const {return (hour_ + 11) % 12 + 1;}
/** \return ISO day of week [1, 7] Sunday = 1 */
int isoDayOfWeek() const {return (dayOfWeek() + 6) % 7 + 1;}
/** \return ISO day of year [1, 366]; first day of year is 001. */
int isoDayOfYear() const {return dayOfYear() + 1;}
/** \return minute [0, 59] */
int minute() const {return minute_;}
/** \return second [0, 59]*/
int second() const {return second_;}
/** \return posix seconds since 1/1/1970 00:00:00 */
time_t unixtime() const {return time();}
//----------------------------------------------------------------------------
int dayOfWeek() const;
int dayOfYear() const;
void printDate(Print* pr) const;
void printDateTime(Print* pr) const;
void printDD(Print* pr) const;
void printDdd(Print* pr) const;
void printIsoDate(Print* pr) const;
void printIsoDateTime(Print* pr) const;
void printIsoTime(Print* pr)const ;
void printUsaDate(Print* pr) const;
void printMM(Print* pr) const;
void printMmm(Print* pr) const;
void printUsaDateTime(Print* pr) const;
void settime();
bool settime(time_t t);
bool settime(uint16_t year, uint8_t month, uint8_t day,
uint8_t hour, uint8_t minute, uint8_t second);
bool settime(const char* date, const char* time);
time_t time() const;
private:
friend class RTC_DS1307;
uint16_t year_;
uint8_t month_;
uint8_t day_;
uint8_t hour_;
uint8_t minute_;
uint8_t second_;
};
//------------------------------------------------------------------------------
/**
* \class RTC_DS1307
* \brief Class for DS1307 access
*/
class RTC_DS1307 {
public:
/** \return true for RTClib compatibility */
uint8_t begin() {return 1;};
/** set time
* \param[in] dt new date and time
*/
void adjust(const DateTime& dt) {setTime(&dt);}
bool getTime(DateTime* dt);
bool isrunning();
DateTime now();
bool read(uint8_t address, uint8_t *buf, uint8_t count);
bool readTime(uint8_t *r);
bool setSQW(uint8_t sqwMode);
bool setTime(const DateTime* dt);
bool write(uint8_t address, uint8_t *buf, uint8_t count);
#if DS_RTC_USE_WIRE
/** Constructor */
RTC_DS1307() {}
#else // DS_RTC_USE_WIRE
/** Constructor
* \param[in] i2cBus I2C bus for this RTC.
*/
explicit RTC_DS1307(I2cMasterBase* i2cBus) : i2cBus_(i2cBus) {}
private:
RTC_DS1307() {}
I2cMasterBase *i2cBus_;
#endif // DS_RTC_USE_WIRE
};
#endif // SoftRTClib_h

View file

@ -0,0 +1,456 @@
// Utility sketch to set RTC time, date, and control registers.
//
// This sketch can be used with many Maxim I2C RTC chips.
// See your chip's data sheet.
//------------------------------------------------------------------------------
#include <avr/pgmspace.h>
#include <I2cMaster.h>
#include <SoftRTClib.h>
// use software I2C if USE_SOFT_I2C is nonzero
#define USE_SOFT_I2C 1
#if USE_SOFT_I2C
// use analog pins 4, 5 for software I2C
#if defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
// Is Mega
const uint8_t RTC_SCL_PIN = 59;
const uint8_t RTC_SDA_PIN = 58;
#else
// Not Mega
const uint8_t RTC_SCL_PIN = 19;
const uint8_t RTC_SDA_PIN = 18;
#endif // defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)
SoftI2cMaster i2c(RTC_SDA_PIN, RTC_SCL_PIN);
#else // USE_SOFT_I2C
// enable pull-ups on SDA/SCL
TwiMaster i2c(true);
#endif // USE_SOFT_I2C
// constants for SQW test
uint8_t const SQW_DELAY = 10;
uint8_t const SQW_INTERRUPT = 0;
uint8_t const SQW_PIN = 2;
uint8_t const GPS_PIN = 3;
uint8_t const GPS_INTERRUPT = 1;
RTC_DS1307 rtc(&i2c);
uint32_t sqwCount;
int32_t gpsCount;
int32_t gpsSqwCount;
void gpsInterrupt();
bool hexReadEcho(uint8_t*);
void hexPrint(uint8_t);
void sqwInterrupt();
//------------------------------------------------------------------------------
#define printPSTR(s) print_P(PSTR(s))
//------------------------------------------------------------------------------
void print_P(PGM_P str) {
uint8_t c;
while ((c = pgm_read_byte(str++))) Serial.write(c);
}
//------------------------------------------------------------------------------
bool readUint8(uint8_t base, uint8_t *v) {
uint16_t n = 0;
while (!Serial.available()) {}
while (Serial.available()) {
uint8_t c = Serial.read();
if ('0' <= c && c <= '9') {
c -= '0';
} else if ('a' <= c && c <= 'z') {
c -= 'a' - 10;
} else if ('A' <= c && c <= 'Z') {
c -= 'A' - 10;
} else {
c = base;
}
n = base * n + c;
if (c >= base || n >= 256) return false;
delay(10);
}
*v = n;
return true;
}
//------------------------------------------------------------------------------
bool decReadEcho(uint8_t min, uint8_t max, uint8_t* n) {
uint8_t d;
if (!readUint8(10, &d) || d < min || d > max) {
printPSTR("Invalid\r\n");
return false;
}
Serial.println(d, DEC);
*n = d;
return true;
}
//------------------------------------------------------------------------------
void displayTime(void) {
DateTime dt;
if (!rtc.getTime(&dt)) {
printPSTR("DS1307 time error\r\n");
return;
}
dt.printDdd(&Serial);
printPSTR(", ");
dt.printDateTime(&Serial);
Serial.println();
}
//------------------------------------------------------------------------------
void helpDS1307Crtl() {
printPSTR(
"07h DS1307 Control\r\n"
"+---+---+---+----+---+---+---+---+\r\n"
"|OUT| 0 | 0 |SQWE| 0 | 0 |RS1|RS2|\r\n"
"| 0 | 0 | 0 | 0 | 0 | 0 | 1 | 1 |\r\n"
"+---+---+---+----+---+---+---+---+\r\n"
"OUT SQWE RS1 RS2 SQW Pin\r\n"
" x 1 0 0 1 Hz\r\n"
" x 1 0 1 4096 Hz\r\n"
" x 1 1 0 8196 Hz\r\n"
" x 1 1 1 32768 Hz\r\n"
" 1 0 x x high\r\n"
" 0 0 x x low\r\n");
}
//------------------------------------------------------------------------------
void helpDS3231Ctrl() {
printPSTR(
"0Eh DS3231 Control\r\n"
"+-----+-----+----+---+---+-----+----+----+\r\n"
"|!EOSC|BBSQW|CONV|RS2|RS1|INTCN|A2IE|A1IE|\r\n"
"| 0 | 0 | 0 | 1 | 1 | 1 | 0 | 0 |\r\n"
"+-----+-----+----+---+---+-----+----+----+\r\n"
"!EOSC - set to stop osc under battery\r\n"
"BBSQW - set to enable SQW under battery\r\n"
"CONV - set to start temp conversion\r\n"
"RS2 RS1 SQW Pin\r\n"
" 0 0 1 Hz\r\n"
" 0 1 1024 Hz\r\n"
" 1 0 4096 Hz\r\n"
" 1 1 8196 Hz\r\n"
"INTCN - clear to enable SQW, set for alarm\r\n"
"A2IE - set to enable alarm 2 interrupt\r\n"
"A1IE - set to enable alarm 1 interrupt\r\n");
}
//------------------------------------------------------------------------------
void helpDS3231CrtlStatus() {
printPSTR(
"0Fh DS3231 Control/Status\r\n"
"+---+---+---+---+-------+---+---+---+\r\n"
"|OSF| 0 | 0 | 0 |EN32kHz|BSY|A2F|A1F|\r\n"
"| 1 | 0 | 0 | 0 | 1 | x | x | x |\r\n"
"+---+---+---+---+-------+---+---+---+\r\n"
"OSF - osc was stopped flag\r\n"
"EN32kHz - set to enable 32 kHz\r\n"
"BSY - busy executing TCXO functions\r\n"
"A2F - alarm 2 flag\r\n"
"A1F - alarm 1 flag\r\n");
}
//------------------------------------------------------------------------------
void DS3231Temperature() {
uint8_t r[2];
const uint8_t DS3231_TEMP_ADD = 0X11;
if (!rtc.read(DS3231_TEMP_ADD, r, 2)) {
printPSTR("Read temp failed\r\n");
return;
}
float T = ((r[0] << 8) | r[1]) / 256.0;
Serial.print(T);
printPSTR(" C\r\n");
}
//------------------------------------------------------------------------------
void dumpRegisters(void) {
uint8_t a = 0;
uint8_t h;
do {
if ((a % 8) == 0) {
if (a) Serial.println();
hexPrint(a);
Serial.write(' ');
}
Serial.write(' ');
if (!rtc.read(a, &h, 1)) break;
hexPrint(h);
} while(a++ != 0X3F);
Serial.println();
}
//------------------------------------------------------------------------------
bool enableSQW() {
uint8_t sqwEnable;
printPSTR("Connect RTC signal to pin ");
Serial.println(SQW_PIN, DEC);
while (Serial.read() >= 0) {}
printPSTR(
"Type 1 to enable 32 kHz SQW on a DS1307\r\n"
"Type 0 to skip SQW enable for chips like a DS3231\r\n"
"Enter (0 or 1): ");
if (!decReadEcho(0, 1, &sqwEnable)) return false;
if (sqwEnable) {
if (!rtc.setSQW(DS1307_SQW_32768_HZ)) {
printPSTR("SQW enable failed\r\n");
return false;
}
}
return true;
}
//------------------------------------------------------------------------------
void gpsCal(void) {
printPSTR("Connect GPS pps to pin ");
Serial.println(GPS_PIN, DEC);
if (!enableSQW()) return;
printPSTR("\r\nType any character to stop\r\n\r\n");
while (Serial.read() >= 0);
pinMode(GPS_PIN, INPUT);
pinMode(SQW_PIN, INPUT);
// enable pullup
digitalWrite(SQW_PIN, HIGH);
digitalWrite(GPS_PIN, HIGH);
// attach interrupts
attachInterrupt(SQW_INTERRUPT, sqwInterrupt, FALLING);
attachInterrupt(GPS_INTERRUPT, gpsInterrupt, FALLING);
sqwCount = 0;
delay(100);
if (sqwCount == 0) {
printPSTR("No RTC signal on pin ");
Serial.println(SQW_PIN, DEC);
return;
}
gpsCount = -1;
while (Serial.available() == 0) {
cli();
int32_t s = gpsSqwCount;
int32_t g = gpsCount;
sei();
if (g < 1) {
printPSTR("Waiting for GPS pps on pin ");
Serial.println(GPS_PIN, DEC);
delay(1000);
} else {
float e = (float)(s - 32768 * g) / (32768 * g);
Serial.print(g);
if (e == 0.0) {
printPSTR(" RTC == GPS \r\n");
} else {
if (e > 0) {
printPSTR(" fast ");
} else if (e < 0) {
printPSTR(" slow ");
}
Serial.print(e * 24 * 3600, 3);
printPSTR(" sec/day ");
Serial.print(1000000 * e);
printPSTR(" +-");
Serial.print(0.02 + 2000000.0 / s);
printPSTR(" ppm\r\n");
}
uint32_t m = millis();
while (g == gpsCount) {
if ((millis() -m) > 2000) gpsCount = -1;
}
}
}
detachInterrupt(GPS_INTERRUPT);
detachInterrupt(SQW_INTERRUPT);
}
//------------------------------------------------------------------------------
void gpsInterrupt(void) {
if (gpsCount < 0) {
sqwCount = 0;
gpsCount = 0;
return;
}
gpsCount++;
gpsSqwCount = sqwCount;
}
//------------------------------------------------------------------------------
void help() {
printPSTR(
"Options are:\r\n"
"(0) Display date and time\r\n"
"(1) Set date and time\r\n"
"(2) Dump registers\r\n"
"(3) Set register\r\n"
"(4) DS3231 temperature\r\n"
"(5) SQW/32kHz pin test\r\n"
"(6) Calibrate with GPS pps\r\n"
"(7) DS1307 control help\r\n"
"(8) DS3231 control help\r\n"
"(9) DS3231 control/status help\r\n");
}
//------------------------------------------------------------------------------
void hexPrint(uint8_t v) {
Serial.print(v >> 4, HEX);
Serial.print(v & 0XF, HEX);
}
//------------------------------------------------------------------------------
void hexPrintln(uint8_t v) {
hexPrint(v);
Serial.println();
}
//------------------------------------------------------------------------------
bool hexReadEcho(uint8_t* v) {
uint8_t h;
if (!readUint8(16, &h)) {
printPSTR("Invalid\r\n");
return false;
}
hexPrintln(h);
*v = h;
return true;
}
//------------------------------------------------------------------------------
void setDateTime(void) {
DateTime dt;
uint8_t Y, M, D, h, m, s;
uint8_t v;
printPSTR("Enter year [1,99]: ");
if (!decReadEcho(0, 99, &Y)) return;
printPSTR("Enter month [1,12]: ");
if (!decReadEcho(1, 12, &M)) return;
printPSTR("Enter day [1,31]: ");
if (!decReadEcho(1, 31, &D)) return;
printPSTR("Enter hour [0,23]: ");
if (!decReadEcho(0, 23, &h)) return;
printPSTR("Enter minute [0,59]: ");
if (!decReadEcho(0, 59, &m)) return;
printPSTR("Enter second [0,59]: ");
if (!decReadEcho(0, 59, &s)) return;
if (!dt.settime(2000 + Y, M, D, h, m, s)) {
printPSTR("Invalid date/time\r\n");
return;
}
if (!rtc.setTime(&dt)) {
printPSTR("setTime failed\r\n");
return;
}
displayTime();
}
//------------------------------------------------------------------------------
void setRegister(void) {
uint8_t a;
uint8_t r;
printPSTR(
"Address/Register\n\r"
"7 DS1307 Control\n\r"
"E DS3231 Control\n\r"
"F DS3231 Control/Status\n\r"
"10 DS3231 Aging Offset\n\r"
"\n\r"
"Enter address [0,FF]: ");
if (!hexReadEcho(&a)) return;
if (!rtc.read(a, &r, 1)) {
printPSTR("read failed");
return;
}
printPSTR("Current value: ");
hexPrintln(r);
printPSTR("q to quit or new value [0,FF]: ");
while (!Serial.available());
if (Serial.peek() == 'q') {
Serial.println('q');
return;
}
if (!hexReadEcho(&r)) return;
if (!rtc.write(a, &r, 1)) {
printPSTR("write failed");
}
}
//------------------------------------------------------------------------------
void sqwInterrupt(void) {
sqwCount++;
}
//------------------------------------------------------------------------------
void sqwTest(void) {
if (!enableSQW()) return;
// enable pullup
digitalWrite(SQW_PIN, HIGH);
printPSTR("Please wait ");
Serial.print(SQW_DELAY, DEC);
printPSTR(" seconds.\r\n");
attachInterrupt(SQW_INTERRUPT, sqwInterrupt, FALLING);
sqwCount = 0;
delay(SQW_DELAY * 1000UL);
detachInterrupt(SQW_INTERRUPT);
Serial.print(sqwCount);
printPSTR(" interrupts in ");
Serial.print(SQW_DELAY, DEC);
printPSTR(" seconds.\r\n");
if (sqwCount == 0) {
printPSTR("Is SQWE/EN32kHz set in the control register?\r\n");
printPSTR("Is the RTC connected to pin ");
Serial.print(SQW_PIN, DEC);
Serial.println('?');
}
}
//------------------------------------------------------------------------------
void setup(void) {
Serial.begin(9600);
Serial.println();
displayTime();
}
//------------------------------------------------------------------------------
void loop(void) {
uint8_t n;
while (Serial.read() >= 0);
printPSTR("\r\nEnter option number or h for help: ");
while (!Serial.available());
n = Serial.read();
Serial.write(n);
Serial.println();
Serial.println();
switch (n) {
case 'h':
case 'H':
help();
break;
case '0':
displayTime();
break;
case '1':
setDateTime();
break;
case '2':
dumpRegisters();
break;
case '3':
setRegister();
break;
case '4':
DS3231Temperature();
break;
case '5':
sqwTest();
break;
case '6':
gpsCal();
break;
case '7':
helpDS1307Crtl();
break;
case '8':
helpDS3231Ctrl();
break;
case '9':
helpDS3231CrtlStatus();
break;
default:
printPSTR("Invalid option");
break;
}
}

View file

@ -0,0 +1,54 @@
// Date and time functions using a DS1307 RTC connected via I2C and SoftI2cMaster
#include <I2cMaster.h>
#include <SoftRTClib.h>
#if defined(__AVR_ATmega1280__)\
|| defined(__AVR_ATmega2560__)
// Mega analog pins 4 and 5
// pins for DS1307 with software i2c on Mega
#define SDA_PIN 58
#define SCL_PIN 59
#elif defined(__AVR_ATmega168__)\
||defined(__AVR_ATmega168P__)\
||defined(__AVR_ATmega328P__)
// 168 and 328 Arduinos analog pin 4 and 5
#define SDA_PIN 18
#define SCL_PIN 19
#else // CPU type
#error unknown CPU
#endif // CPU type
// An instance of class for software master
SoftI2cMaster i2c(SDA_PIN, SCL_PIN);
RTC_DS1307 RTC(&i2c);
void setup () {
Serial.begin(9600);
}
void loop () {
DateTime now = RTC.now();
now.printIsoDateTime(&Serial);
Serial.println();
Serial.print(" since midnight 1/1/1970 = ");
Serial.print(now.unixtime());
Serial.print("s = ");
Serial.print(now.unixtime() / 86400L);
Serial.println("d");
// calculate a date which is 7 days and 30 seconds into the future
DateTime future (now.unixtime() + 7 * 86400L + 30);
Serial.print(" now + 7d + 30s: ");
future.printIsoDateTime(&Serial);
Serial.println();
Serial.println();
delay(3000);
}

View file

@ -0,0 +1,78 @@
// demo of DS1307 SQW pin output
#include <I2cMaster.h>
#include <SoftRTClib.h>
// constants for SQW test
uint8_t const SQW_DELAY = 10;
uint8_t const SQW_INTERRUPT = 0;
uint8_t const SQW_PIN = 2;
#if defined(__AVR_ATmega1280__)\
|| defined(__AVR_ATmega2560__)
// Mega analog pins 4 and 5
// pins for DS1307 with software i2c on Mega
#define SDA_PIN 58
#define SCL_PIN 59
#elif defined(__AVR_ATmega168__)\
||defined(__AVR_ATmega168P__)\
||defined(__AVR_ATmega328P__)
// 168 and 328 Arduinos analog pin 4 and 5
#define SDA_PIN 18
#define SCL_PIN 19
#else // CPU type
#error unknown CPU
#endif // CPU type
// An instance of class for software master
SoftI2cMaster i2c(SDA_PIN, SCL_PIN);
RTC_DS1307 rtc(&i2c);
uint32_t sqwCount;
//------------------------------------------------------------------------------
void sqwInterrupt(void) {
sqwCount++;
}
//------------------------------------------------------------------------------
void sqwTest(void) {
pinMode(SQW_PIN, INPUT);
// enable pullup
digitalWrite(SQW_PIN, HIGH);
Serial.print("Please wait ");
Serial.print(SQW_DELAY, DEC);
Serial.println(" seconds.");
attachInterrupt(SQW_INTERRUPT, sqwInterrupt, FALLING);
sqwCount = 0;
delay(SQW_DELAY * 1000UL);
detachInterrupt(SQW_INTERRUPT);
Serial.print(sqwCount);
Serial.print(" interrupts in ");
Serial.print(SQW_DELAY, DEC);
Serial.println(" seconds.");
if (sqwCount == 0) {
Serial.println("Is SQWE set in the control register?");
Serial.print("Is SQW connected to pin ");
Serial.print(SQW_PIN, DEC);
Serial.println('?');
}
}
//------------------------------------------------------------------------------
void setup () {
Serial.begin(9600);
Serial.print("Connect the DS1307 SQW pin to Arduino pin ");
Serial.println(SQW_PIN, DEC);
Serial.println("Type any character to count SQW interrupts");
while (!Serial.available()) {}
if (!rtc.setSQW(DS1307_SQW_32768_HZ)) {
Serial.println("setSqw failed");
return;
}
sqwTest();
// disable SQW
rtc.setSQW(DS1307_SQW_LOW);
}
//------------------------------------------------------------------------------
void loop() {}

View file

@ -0,0 +1,34 @@
// Date and time functions using a DS1307 RTC connected via I2C and TwiMaster
#include <I2cMaster.h>
#include <SoftRTClib.h>
TwiMaster i2c(true);
RTC_DS1307 RTC(&i2c);
void setup () {
Serial.begin(9600);
}
void loop () {
DateTime now = RTC.now();
now.printIsoDateTime(&Serial);
Serial.println();
Serial.print(" since midnight 1/1/1970 = ");
Serial.print(now.unixtime());
Serial.print("s = ");
Serial.print(now.unixtime() / 86400L);
Serial.println("d");
// calculate a date which is 7 days and 30 seconds into the future
DateTime future (now.unixtime() + 7 * 86400L + 30);
Serial.print(" now + 7d + 30s: ");
future.printIsoDateTime(&Serial);
Serial.println();
Serial.println();
delay(3000);
}

View file

@ -0,0 +1,38 @@
// Warning: set DS_RTC_USE_WIRE nonzero in SoftRTClib.h
// Date and time functions using a DS1307 RTC connected via I2C and Wire lib
#include <Wire.h>
#include <SoftRTClib.h>
#if !DS_RTC_USE_WIRE
#error set DS_RTC_USE_WIRE nonzero in SoftRTClib.h
#endif // DS_RTC_USE_WIRE
RTC_DS1307 RTC;
void setup () {
Serial.begin(9600);
Wire.begin();
}
void loop () {
DateTime now = RTC.now();
now.printIsoDateTime(&Serial);
Serial.println();
Serial.print(" since midnight 1/1/1970 = ");
Serial.print(now.unixtime());
Serial.print("s = ");
Serial.print(now.unixtime() / 86400L);
Serial.println("d");
// calculate a date which is 7 days and 30 seconds into the future
DateTime future (now.unixtime() + 7 * 86400L + 30);
Serial.print(" now + 7d + 30s: ");
future.printIsoDateTime(&Serial);
Serial.println();
Serial.println();
delay(3000);
}

View file

@ -0,0 +1,101 @@
/* InlineDateAlgorithms
* Copyright (C) 2012 by William Greiman
*
* This file is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with InlineDateAlgorithms. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef InlineDateAlgorithms_h
#define InlineDateAlgorithms_h
//------------------------------------------------------------------------------
#ifndef EPOCH_YEAR
/** default Epoch is January 1 00:00:00 of EPOCH_YEAR */
#define EPOCH_YEAR 1970
#endif // EPOCH_YEAR
//------------------------------------------------------------------------------
/** is leap year
* \param[in] y year, 1900 < y < 2100
* \return one if leap year else zero
*/
inline bool leap(uint16_t y) {return (y & 3) == 0;}
//------------------------------------------------------------------------------
/** Day of year to month
* \param[in] y year 1900 < y < 2100
* \param[in] yday day of year 0 <= yday <= 365
* \return month [1,12]
*/
inline uint8_t dayOfYearToMonth(uint16_t y, uint16_t yday) {
return yday < 31 ? 1 : (456 + 5 * (yday - 58 - leap(y))) / 153;
}
//------------------------------------------------------------------------------
/** Number of days in the year before the current month
* \param[in] y year 1900 < y < 2100
* \param[in] m month 0 < m < 13
* \return days in year before current month [0,335]
*/
inline uint16_t daysBeforeMonth(uint16_t y, uint8_t m) {
return m < 3 ? 31 *(m - 1) : leap(y) + (153 * m - 2) / 5 - 32;
}
//------------------------------------------------------------------------------
/** Count of days since epoch in previous years.
* \param[in] y year (EPOCH_YEAR <= y <= MAX_YEAR)
* \return count of days in previous years
*/
inline uint16_t daysBeforeYear(uint16_t y) {
return 365 * (y - EPOCH_YEAR) + (y - 1) / 4 - (EPOCH_YEAR - 1) / 4;
}
//------------------------------------------------------------------------------
/** Number of days in month
* \param[in] y year 1900 < y < 2100
* \param[in] m month 0 < m < 13
* \return Count of days in month [1, 31]
*/
inline uint8_t daysInMonth(uint16_t y, uint8_t m) {
return m == 2 ? 28 + leap(y) : m < 8 ? 30 + (m & 1) : 31 - (m & 1);
}
//------------------------------------------------------------------------------
/** Count of days since Epoch.
* 1900 < EPOCH_YEAR, MAX_YEAR < 2100, (MAX_YEAR - EPOCH_YEAR) < 178.
* \param[in] y year (EPOCH_YEAR <= y <= MAX_YEAR)
* \param[in] m month 1 <= m <= 12
* \param[in] d day 1 <= d <= 31
* \return Count of days since epoch
*
* Derived from Zeller's congruence
*/
inline uint16_t daysSinceEpoch(uint16_t y, uint8_t m, uint8_t d) {
if (m < 3) {
m += 12;
y--;
}
return 365 * (y + 1 - EPOCH_YEAR) + y / 4 - (EPOCH_YEAR - 1) / 4
+ (153 * m - 2) / 5 + d - 398;
}
//------------------------------------------------------------------------------
/** epoch day to day of week (Sunday == 0)
* \param[in] eday count of days since epoch.
* \return day of week (Sunday == 0)
**/
inline uint8_t epochDayToDayOfWeek(uint16_t eday) {
return (eday + EPOCH_YEAR - 1 + (EPOCH_YEAR - 1) / 4) % 7;
}
//------------------------------------------------------------------------------
/** Day of epoch to year
* \param[in] eday count of days since epoch
* \return year for count of days since epoch
*/
inline uint16_t epochDayToYear(uint16_t eday) {
return EPOCH_YEAR
+ (eday - (eday + 365 * (1 + (EPOCH_YEAR - 1) % 4)) / 1461) / 365;
}
#endif // InlineDateAlgorithms_h

View file

@ -0,0 +1,9 @@
AdafruitLogger.ino will run on a Leonardo, Mega, or 328 Arduino with an Adafruit
Data Logging shield with no jumper wires.
It will timestamp files.
I have included the libraries I used with the sketch.
The version of SdFat is 20121219 with LEONARDO_SOFT_SPI and MEGA_SOFT_SPI
set to one in SdFatConfig.h

View file

@ -0,0 +1,62 @@
Support has been added for the Arduino Due.
You must connect your SD socket to the 6-pin "ISP connector". You must have short
wires or a custom shield to run at full speed, 42 MHz.
If you have problems use a lower SPI speed. You can also check for SPI
errors by editing SdFatCobfig.h to enable CRC checking.
You should be be able to use any digital pin for SD chip select. The default
pin is SS which is pin 10 for Due.
The default SPI rate is 42 MHz. You can set SD chip select and the SPI rate
by calling:
bool SdFat::begin(uint8_t chipSelectPin, uint8_t spiRateID);
The second argument, spiRateID, sets the SCK rate and can be these symbols:
SPI_FULL_SPEED - 42 MHz
SPI_DIV3_SPEED - 28 MHz
SPI_HALF_SPEED - 21 MHz
SPI_DIV6_SPEED - 14 MHz
SPI_QUARTER_SPEED 10.5 MHz
SPI_EIGHTH_SPEED 5.25 MHz
Large reads and writes use fast multi-block SD read/write commands. For optimal
speed, use records that are a multiple of 512 bytes.
Run the bench.ino example to explore large read/write speed.
Replace this line:
#define BUF_SIZE 100
With a large size like this:
#define BUF_SIZE 8192
For best results the record size should be a power of two (512, 1024, 2048,
4096, 8192). In this case records will be aligned with FAT cluster boundaries.
Since Due is fast, increase the test file size by editing this line:
#define FILE_SIZE_MB 5
Run the PrintBenchmark.ino example to compare text formatting speed of Due
with AVR boards.
A number of options are available to configure SPI for the Due board.
You can use the standard SPI.h library by editing SdFatConfig.h and set
USE_ARDUINO_SPI_LIBRARY nonzero. You must include SPI.h in your sketch.
Several options can be set in Sd2Card.cpp in the USE_NATIVE_SAM3X_SPI
section. These include USE_SAM3X_DMAC to control use of DMA and
USE_SAM3X_BUS_MATRIX_FIX to change Bus Matrix operation. Most people
will not need to change these.

View file

@ -0,0 +1,36 @@
SD cards have very complex controllers and they are evolving in a manner that
make them difficult to use with the Arduino.
Higher end cards often perform poorly on the Arduino. Here is a bit of
background.
First, SPI mode is not used in most devices so the SPI controller is not
very good.
The flash erase groups in SD cards are very large, 128 KB is common. This
means that rewriting file structures can result in a huge amount of data
being moved.
This is what is happening when you see long clock activity. The card
indicates busy by holding data out low. The spec allow a card to go busy
for up to 250 ms.
Cards have two write modes, single block random mode and multiple block
sequential mode. For file writes I must use single block mode. This is
always slow but often extremely slow in high end cards. microSD cards also
have poor support for this mode.
I have several applications that use multiple block mode and they run much
faster. The binaryLogger.pde example can log 40,000 16-bit samples per
second without dropping data on a good SanDisk video card.
Looks like I should develop a Serial logger using this method. It requires
allocating a huge contiguous file and writing it using the multiple block
sequential mode. This makes the app more complex and not so easy to
understand.
The write time for a 512 byte block in sequential mode is about 850
microseconds with occasional busy times of 2 - 3 ms on a SanDisk Extreme
30 MB/sec card. In random mode this card is often slower than five year
old class 2 cards.

View file

@ -0,0 +1,14 @@
Features have been added to support an unmodified Adafruit GPS Shield
or Datalogging Shield on an Arduino Mega.
Define MEGA_SOFT_SPI to be non-zero in SdFatConfig.h to use software SPI
on Mega Arduinos. Pins used are SS 10, MOSI 11, MISO 12, and SCK 13.
Defining MEGA_SOFT_SPI allows an unmodified Adafruit GPS Shield to be
used on Mega Arduinos. Software SPI works well with GPS Shield V1.1
but many SD cards will fail with GPS Shield V1.0.
Software SPI should work with all Datalogging Shields.
The examples SdFatGPS_CSVSensorLogger.pde and SdFatGPSLogger_v3.pde
should work on on the Mega when MEGA_SOFT_SPI is defined.

View file

@ -0,0 +1,13 @@
SdFat has support for multiple SD cards. This requires multiple instances
of SdFat objects.
You must edit SdFatConfig.h to enable multiple instances of SdFat. Set
USE_MULTIPLE_CARDS nonzero like this:
#define USE_MULTIPLE_CARDS 1
Look at TwoCards.pde in the SdFat/examples folder. This example demonstrates
use of two SD cards.
Read WorkingDirectory.txt for more information on volume working
directories and the current working directory.

View file

@ -0,0 +1,21 @@
For those who don't like too much documentation.
To use this library place the SdFat folder into the libraries
subfolder in your main sketches folder. You may need to
create the libraries folder. Restart the Arduino IDE if
it was open.
Run the QuickStart.pde sketch from the
libraries/SdFat/examples/QuickStart folder. Click the
IDE up-arrow icon then -> libraries -> SdFat -> QuickStart.
You can also click File -> Examples -> SdFat -> QuickStart.
If problems occur try reading more documentation and use these
forums for help:
http://forums.adafruit.com/
http://arduino.cc/forum/
If QuickStart.pde runs successfully try more examples.

View file

@ -0,0 +1,10 @@
<html>
<head>
<title>A web page that points a browser to a different page</title>
<meta http-equiv="refresh" content="0; URL=html/index.html">
<meta name="keywords" content="automatic redirection">
</head>
<body>
Your browser didn't automatically redirect. Open html/index.html manually.
</body>
</html>

View file

@ -0,0 +1,119 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef ArduinoStream_h
#define ArduinoStream_h
/**
* \file
* \brief ArduinoInStream and ArduinoOutStream classes
*/
#include <bufstream.h>
//==============================================================================
/**
* \class ArduinoInStream
* \brief Input stream for Arduino Stream objects
*/
class ArduinoInStream : public ibufstream {
public:
/**
* Constructor
* \param[in] hws hardware stream
* \param[in] buf buffer for input line
* \param[in] size size of input buffer
*/
ArduinoInStream(Stream &hws, char* buf, size_t size) {
hw_ = &hws;
line_ = buf;
size_ = size;
}
/** read a line. */
void readline() {
size_t i = 0;
uint32_t t;
line_[0] = '\0';
while (!hw_->available());
while (1) {
t = millis();
while (!hw_->available()) {
if ((millis() - t) > 10) goto done;
}
if (i >= (size_ - 1)) {
setstate(failbit);
return;
}
line_[i++] = hw_->read();
line_[i] = '\0';
}
done:
init(line_);
}
protected:
/** Internal - do not use.
* \param[in] off
* \param[in] way
* \return true/false.
*/
bool seekoff(off_type off, seekdir way) {return false;}
/** Internal - do not use.
* \param[in] pos
* \return true/false.
*/
bool seekpos(pos_type pos) {return false;}
private:
char *line_;
size_t size_;
Stream* hw_;
};
//==============================================================================
/**
* \class ArduinoOutStream
* \brief Output stream for Arduino Print objects
*/
class ArduinoOutStream : public ostream {
public:
/** constructor
*
* \param[in] pr Print object for this ArduinoOutStream.
*/
explicit ArduinoOutStream(Print& pr) : pr_(&pr) {}
protected:
/// @cond SHOW_PROTECTED
/**
* Internal do not use
* \param[in] c
*/
void putch(char c) {
if (c == '\n') pr_->write('\r');
pr_->write(c);
}
void putstr(const char* str) {pr_->write(str);}
bool seekoff(off_type off, seekdir way) {return false;}
bool seekpos(pos_type pos) {return false;}
bool sync() {return true;}
pos_type tellpos() {return 0;}
/// @endcond
private:
ArduinoOutStream() {}
Print* pr_;
};
#endif // ArduinoStream_h

View file

@ -0,0 +1,71 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#include <Arduino.h>
#if defined(UDR0) || defined(DOXYGEN)
#include <MinimumSerial.h>
//------------------------------------------------------------------------------
/**
* Set baud rate for serial port zero and enable in non interrupt mode.
* Do not call this function if you use another serial library.
* \param[in] baud rate
*/
void MinimumSerial::begin(unsigned long baud) {
uint16_t baud_setting;
// don't worry, the compiler will squeeze out F_CPU != 16000000UL
if (F_CPU != 16000000UL || baud != 57600) {
// Double the USART Transmission Speed
UCSR0A = 1 << U2X0;
baud_setting = (F_CPU / 4 / baud - 1) / 2;
} else {
// hardcoded exception for compatibility with the bootloader shipped
// with the Duemilanove and previous boards and the firmware on the 8U2
// on the Uno and Mega 2560.
UCSR0A = 0;
baud_setting = (F_CPU / 8 / baud - 1) / 2;
}
// assign the baud_setting
UBRR0H = baud_setting >> 8;
UBRR0L = baud_setting;
// enable transmit and receive
UCSR0B |= (1 << TXEN0) | (1 << RXEN0) ;
}
//------------------------------------------------------------------------------
/**
* Unbuffered read
* \return -1 if no character is available or an available character.
*/
int MinimumSerial::read() {
if (UCSR0A & (1 << RXC0)) return UDR0;
return -1;
}
//------------------------------------------------------------------------------
/**
* Unbuffered write
*
* \param[in] b byte to write.
* \return 1
*/
size_t MinimumSerial::write(uint8_t b) {
while (((1 << UDRIE0) & UCSR0B) || !(UCSR0A & (1 << UDRE0))) {}
UDR0 = b;
return 1;
}
MinimumSerial MiniSerial;
#endif // defined(UDR0) || defined(DOXYGEN)

View file

@ -0,0 +1,36 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef MinimumSerial_h
#define MinimumSerial_h
/**
* \class MinimumSerial
* \brief mini serial class for the %SdFat library.
*/
class MinimumSerial : public Print {
public:
void begin(unsigned long);
int read();
size_t write(uint8_t b);
using Print::write;
};
#ifdef UDR0
extern MinimumSerial MiniSerial;
#endif // UDR0
#endif // MinimumSerial_h

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,233 @@
/* Arduino Sd2Card Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino Sd2Card Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino Sd2Card Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef Sd2Card_h
#define Sd2Card_h
/**
* \file
* \brief Sd2Card class for V2 SD/SDHC cards
*/
#include <Arduino.h>
#include <SdFatConfig.h>
#include <SdInfo.h>
//------------------------------------------------------------------------------
// SPI speed is F_CPU/2^(1 + index), 0 <= index <= 6
/** Set SCK to max rate of F_CPU/2. See Sd2Card::setSckRate(). */
uint8_t const SPI_FULL_SPEED = 0;
/** Set SCK rate to F_CPU/3 for Due */
uint8_t const SPI_DIV3_SPEED = 1;
/** Set SCK rate to F_CPU/4. See Sd2Card::setSckRate(). */
uint8_t const SPI_HALF_SPEED = 2;
/** Set SCK rate to F_CPU/6 for Due */
uint8_t const SPI_DIV6_SPEED = 3;
/** Set SCK rate to F_CPU/8. See Sd2Card::setSckRate(). */
uint8_t const SPI_QUARTER_SPEED = 4;
/** Set SCK rate to F_CPU/16. See Sd2Card::setSckRate(). */
uint8_t const SPI_EIGHTH_SPEED = 6;
/** Set SCK rate to F_CPU/32. See Sd2Card::setSckRate(). */
uint8_t const SPI_SIXTEENTH_SPEED = 8;
/** MAX rate test - see spiInit for a given chip for details */
const uint8_t MAX_SCK_RATE_ID = 14;
//------------------------------------------------------------------------------
/** init timeout ms */
uint16_t const SD_INIT_TIMEOUT = 2000;
/** erase timeout ms */
uint16_t const SD_ERASE_TIMEOUT = 10000;
/** read timeout ms */
uint16_t const SD_READ_TIMEOUT = 300;
/** write time out ms */
uint16_t const SD_WRITE_TIMEOUT = 600;
//------------------------------------------------------------------------------
// SD card errors
/** timeout error for command CMD0 (initialize card in SPI mode) */
uint8_t const SD_CARD_ERROR_CMD0 = 0X1;
/** CMD8 was not accepted - not a valid SD card*/
uint8_t const SD_CARD_ERROR_CMD8 = 0X2;
/** card returned an error response for CMD12 (write stop) */
uint8_t const SD_CARD_ERROR_CMD12 = 0X3;
/** card returned an error response for CMD17 (read block) */
uint8_t const SD_CARD_ERROR_CMD17 = 0X4;
/** card returned an error response for CMD18 (read multiple block) */
uint8_t const SD_CARD_ERROR_CMD18 = 0X5;
/** card returned an error response for CMD24 (write block) */
uint8_t const SD_CARD_ERROR_CMD24 = 0X6;
/** WRITE_MULTIPLE_BLOCKS command failed */
uint8_t const SD_CARD_ERROR_CMD25 = 0X7;
/** card returned an error response for CMD58 (read OCR) */
uint8_t const SD_CARD_ERROR_CMD58 = 0X8;
/** SET_WR_BLK_ERASE_COUNT failed */
uint8_t const SD_CARD_ERROR_ACMD23 = 0X9;
/** ACMD41 initialization process timeout */
uint8_t const SD_CARD_ERROR_ACMD41 = 0XA;
/** card returned a bad CSR version field */
uint8_t const SD_CARD_ERROR_BAD_CSD = 0XB;
/** erase block group command failed */
uint8_t const SD_CARD_ERROR_ERASE = 0XC;
/** card not capable of single block erase */
uint8_t const SD_CARD_ERROR_ERASE_SINGLE_BLOCK = 0XD;
/** Erase sequence timed out */
uint8_t const SD_CARD_ERROR_ERASE_TIMEOUT = 0XE;
/** card returned an error token instead of read data */
uint8_t const SD_CARD_ERROR_READ = 0XF;
/** read CID or CSD failed */
uint8_t const SD_CARD_ERROR_READ_REG = 0X10;
/** timeout while waiting for start of read data */
uint8_t const SD_CARD_ERROR_READ_TIMEOUT = 0X11;
/** card did not accept STOP_TRAN_TOKEN */
uint8_t const SD_CARD_ERROR_STOP_TRAN = 0X12;
/** card returned an error token as a response to a write operation */
uint8_t const SD_CARD_ERROR_WRITE = 0X13;
/** attempt to write protected block zero */
uint8_t const SD_CARD_ERROR_WRITE_BLOCK_ZERO = 0X14; // REMOVE - not used
/** card did not go ready for a multiple block write */
uint8_t const SD_CARD_ERROR_WRITE_MULTIPLE = 0X15;
/** card returned an error to a CMD13 status check after a write */
uint8_t const SD_CARD_ERROR_WRITE_PROGRAMMING = 0X16;
/** timeout occurred during write programming */
uint8_t const SD_CARD_ERROR_WRITE_TIMEOUT = 0X17;
/** incorrect rate selected */
uint8_t const SD_CARD_ERROR_SCK_RATE = 0X18;
/** init() not called */
uint8_t const SD_CARD_ERROR_INIT_NOT_CALLED = 0X19;
/** card returned an error for CMD59 (CRC_ON_OFF) */
uint8_t const SD_CARD_ERROR_CMD59 = 0X1A;
/** invalid read CRC */
uint8_t const SD_CARD_ERROR_READ_CRC = 0X1B;
/** SPI DMA error */
uint8_t const SD_CARD_ERROR_SPI_DMA = 0X1C;
//------------------------------------------------------------------------------
// card types
/** Standard capacity V1 SD card */
uint8_t const SD_CARD_TYPE_SD1 = 1;
/** Standard capacity V2 SD card */
uint8_t const SD_CARD_TYPE_SD2 = 2;
/** High Capacity SD card */
uint8_t const SD_CARD_TYPE_SDHC = 3;
/**
* define SOFTWARE_SPI to use bit-bang SPI
*/
//------------------------------------------------------------------------------
#if LEONARDO_SOFT_SPI && defined(__AVR_ATmega32U4__) && !defined(CORE_TEENSY)
#define SOFTWARE_SPI
#elif MEGA_SOFT_SPI&&(defined(__AVR_ATmega1280__)||defined(__AVR_ATmega2560__))
#define SOFTWARE_SPI
#elif USE_SOFTWARE_SPI
#define SOFTWARE_SPI
#endif // LEONARDO_SOFT_SPI
//------------------------------------------------------------------------------
// define default chip select pin
//
#ifndef SOFTWARE_SPI
// hardware pin defs
/** The default chip select pin for the SD card is SS. */
uint8_t const SD_CHIP_SELECT_PIN = SS;
#else // SOFTWARE_SPI
/** SPI chip select pin */
uint8_t const SD_CHIP_SELECT_PIN = SOFT_SPI_CS_PIN;
#endif // SOFTWARE_SPI
//------------------------------------------------------------------------------
/**
* \class Sd2Card
* \brief Raw access to SD and SDHC flash memory cards.
*/
class Sd2Card {
public:
/** Construct an instance of Sd2Card. */
Sd2Card() : errorCode_(SD_CARD_ERROR_INIT_NOT_CALLED), type_(0) {}
uint32_t cardSize();
bool erase(uint32_t firstBlock, uint32_t lastBlock);
bool eraseSingleBlockEnable();
/**
* Set SD error code.
* \param[in] code value for error code.
*/
void error(uint8_t code) {errorCode_ = code;}
/**
* \return error code for last error. See Sd2Card.h for a list of error codes.
*/
int errorCode() const {return errorCode_;}
/** \return error data for last error. */
int errorData() const {return status_;}
/**
* Initialize an SD flash memory card with default clock rate and chip
* select pin. See sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin).
*
* \return true for success or false for failure.
*/
bool init(uint8_t sckRateID = SPI_FULL_SPEED,
uint8_t chipSelectPin = SD_CHIP_SELECT_PIN);
bool readBlock(uint32_t block, uint8_t* dst);
/**
* Read a card's CID register. The CID contains card identification
* information such as Manufacturer ID, Product name, Product serial
* number and Manufacturing date.
*
* \param[out] cid pointer to area for returned data.
*
* \return true for success or false for failure.
*/
bool readCID(cid_t* cid) {
return readRegister(CMD10, cid);
}
/**
* Read a card's CSD register. The CSD contains Card-Specific Data that
* provides information regarding access to the card's contents.
*
* \param[out] csd pointer to area for returned data.
*
* \return true for success or false for failure.
*/
bool readCSD(csd_t* csd) {
return readRegister(CMD9, csd);
}
bool readData(uint8_t *dst);
bool readStart(uint32_t blockNumber);
bool readStop();
bool setSckRate(uint8_t sckRateID);
/** Return the card type: SD V1, SD V2 or SDHC
* \return 0 - SD V1, 1 - SD V2, or 3 - SDHC.
*/
int type() const {return type_;}
bool writeBlock(uint32_t blockNumber, const uint8_t* src);
bool writeData(const uint8_t* src);
bool writeStart(uint32_t blockNumber, uint32_t eraseCount);
bool writeStop();
private:
//----------------------------------------------------------------------------
uint8_t chipSelectPin_;
uint8_t errorCode_;
uint8_t spiRate_;
uint8_t status_;
uint8_t type_;
// private functions
uint8_t cardAcmd(uint8_t cmd, uint32_t arg) {
cardCommand(CMD55, 0);
return cardCommand(cmd, arg);
}
uint8_t cardCommand(uint8_t cmd, uint32_t arg);
bool readData(uint8_t* dst, size_t count);
bool readRegister(uint8_t cmd, void* buf);
void chipSelectHigh();
void chipSelectLow();
void type(uint8_t value) {type_ = value;}
bool waitNotBusy(uint16_t timeoutMillis);
bool writeData(uint8_t token, const uint8_t* src);
};
#endif // Sd2Card_h

File diff suppressed because it is too large Load diff

View file

@ -0,0 +1,564 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef SdBaseFile_h
#define SdBaseFile_h
/**
* \file
* \brief SdBaseFile class
*/
#ifdef __AVR__
#include <avr/pgmspace.h>
#else // __AVR__
#ifndef PGM_P
/** pointer to flash for ARM */
#define PGM_P const char*
#endif // PGM_P
#ifndef PSTR
/** store literal string in flash for ARM */
#define PSTR(x) (x)
#endif // PSTR
#ifndef pgm_read_byte
/** read 8-bits from flash for ARM */
#define pgm_read_byte(addr) (*(const unsigned char*)(addr))
#endif // pgm_read_byte
#ifndef pgm_read_word
/** read 16-bits from flash for ARM */
#define pgm_read_word(addr) (*(const uint16_t*)(addr))
#endif // pgm_read_word
#ifndef PROGMEM
/** store in flash for ARM */
#define PROGMEM const
#endif // PROGMEM
#endif // __AVR__
#include <Arduino.h>
#include <SdFatConfig.h>
#include <SdVolume.h>
//------------------------------------------------------------------------------
/**
* \struct FatPos_t
* \brief internal type for istream
* do not use in user apps
*/
struct FatPos_t {
/** stream position */
uint32_t position;
/** cluster for position */
uint32_t cluster;
FatPos_t() : position(0), cluster(0) {}
};
// use the gnu style oflag in open()
/** open() oflag for reading */
uint8_t const O_READ = 0X01;
/** open() oflag - same as O_IN */
uint8_t const O_RDONLY = O_READ;
/** open() oflag for write */
uint8_t const O_WRITE = 0X02;
/** open() oflag - same as O_WRITE */
uint8_t const O_WRONLY = O_WRITE;
/** open() oflag for reading and writing */
uint8_t const O_RDWR = (O_READ | O_WRITE);
/** open() oflag mask for access modes */
uint8_t const O_ACCMODE = (O_READ | O_WRITE);
/** The file offset shall be set to the end of the file prior to each write. */
uint8_t const O_APPEND = 0X04;
/** synchronous writes - call sync() after each write */
uint8_t const O_SYNC = 0X08;
/** truncate the file to zero length */
uint8_t const O_TRUNC = 0X10;
/** set the initial position at the end of the file */
uint8_t const O_AT_END = 0X20;
/** create the file if nonexistent */
uint8_t const O_CREAT = 0X40;
/** If O_CREAT and O_EXCL are set, open() shall fail if the file exists */
uint8_t const O_EXCL = 0X80;
// SdBaseFile class static and const definitions
// flags for ls()
/** ls() flag to print modify date */
uint8_t const LS_DATE = 1;
/** ls() flag to print file size */
uint8_t const LS_SIZE = 2;
/** ls() flag for recursive list of subdirectories */
uint8_t const LS_R = 4;
// flags for timestamp
/** set the file's last access date */
uint8_t const T_ACCESS = 1;
/** set the file's creation date and time */
uint8_t const T_CREATE = 2;
/** Set the file's write date and time */
uint8_t const T_WRITE = 4;
// values for type_
/** This file has not been opened. */
uint8_t const FAT_FILE_TYPE_CLOSED = 0;
/** A normal file */
uint8_t const FAT_FILE_TYPE_NORMAL = 1;
/** A FAT12 or FAT16 root directory */
uint8_t const FAT_FILE_TYPE_ROOT_FIXED = 2;
/** A FAT32 root directory */
uint8_t const FAT_FILE_TYPE_ROOT32 = 3;
/** A subdirectory file*/
uint8_t const FAT_FILE_TYPE_SUBDIR = 4;
/** Test value for directory type */
uint8_t const FAT_FILE_TYPE_MIN_DIR = FAT_FILE_TYPE_ROOT_FIXED;
/** date field for FAT directory entry
* \param[in] year [1980,2107]
* \param[in] month [1,12]
* \param[in] day [1,31]
*
* \return Packed date for dir_t entry.
*/
static inline uint16_t FAT_DATE(uint16_t year, uint8_t month, uint8_t day) {
return (year - 1980) << 9 | month << 5 | day;
}
/** year part of FAT directory date field
* \param[in] fatDate Date in packed dir format.
*
* \return Extracted year [1980,2107]
*/
static inline uint16_t FAT_YEAR(uint16_t fatDate) {
return 1980 + (fatDate >> 9);
}
/** month part of FAT directory date field
* \param[in] fatDate Date in packed dir format.
*
* \return Extracted month [1,12]
*/
static inline uint8_t FAT_MONTH(uint16_t fatDate) {
return (fatDate >> 5) & 0XF;
}
/** day part of FAT directory date field
* \param[in] fatDate Date in packed dir format.
*
* \return Extracted day [1,31]
*/
static inline uint8_t FAT_DAY(uint16_t fatDate) {
return fatDate & 0X1F;
}
/** time field for FAT directory entry
* \param[in] hour [0,23]
* \param[in] minute [0,59]
* \param[in] second [0,59]
*
* \return Packed time for dir_t entry.
*/
static inline uint16_t FAT_TIME(uint8_t hour, uint8_t minute, uint8_t second) {
return hour << 11 | minute << 5 | second >> 1;
}
/** hour part of FAT directory time field
* \param[in] fatTime Time in packed dir format.
*
* \return Extracted hour [0,23]
*/
static inline uint8_t FAT_HOUR(uint16_t fatTime) {
return fatTime >> 11;
}
/** minute part of FAT directory time field
* \param[in] fatTime Time in packed dir format.
*
* \return Extracted minute [0,59]
*/
static inline uint8_t FAT_MINUTE(uint16_t fatTime) {
return(fatTime >> 5) & 0X3F;
}
/** second part of FAT directory time field
* Note second/2 is stored in packed time.
*
* \param[in] fatTime Time in packed dir format.
*
* \return Extracted second [0,58]
*/
static inline uint8_t FAT_SECOND(uint16_t fatTime) {
return 2*(fatTime & 0X1F);
}
/** Default date for file timestamps is 1 Jan 2000 */
uint16_t const FAT_DEFAULT_DATE = ((2000 - 1980) << 9) | (1 << 5) | 1;
/** Default time for file timestamp is 1 am */
uint16_t const FAT_DEFAULT_TIME = (1 << 11);
//------------------------------------------------------------------------------
/**
* \class SdBaseFile
* \brief Base class for SdFile with Print and C++ streams.
*/
class SdBaseFile {
public:
/** Create an instance. */
SdBaseFile() : writeError(false), type_(FAT_FILE_TYPE_CLOSED) {}
SdBaseFile(const char* path, uint8_t oflag);
#if DESTRUCTOR_CLOSES_FILE
~SdBaseFile() {if(isOpen()) close();}
#endif // DESTRUCTOR_CLOSES_FILE
/**
* writeError is set to true if an error occurs during a write().
* Set writeError to false before calling print() and/or write() and check
* for true after calls to print() and/or write().
*/
bool writeError;
/** \return value of writeError */
bool getWriteError() {return writeError;}
/** Set writeError to zero */
void clearWriteError() {writeError = 0;}
//----------------------------------------------------------------------------
// helpers for stream classes
/** get position for streams
* \param[out] pos struct to receive position
*/
void getpos(FatPos_t* pos);
/** set position for streams
* \param[out] pos struct with value for new position
*/
void setpos(FatPos_t* pos);
//----------------------------------------------------------------------------
/** \return number of bytes available from yhe current position to EOF */
uint32_t available() {return fileSize() - curPosition();}
bool close();
bool contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock);
bool createContiguous(SdBaseFile* dirFile,
const char* path, uint32_t size);
/** \return The current cluster number for a file or directory. */
uint32_t curCluster() const {return curCluster_;}
/** \return The current position for a file or directory. */
uint32_t curPosition() const {return curPosition_;}
/** \return Current working directory */
static SdBaseFile* cwd() {return cwd_;}
/** Set the date/time callback function
*
* \param[in] dateTime The user's call back function. The callback
* function is of the form:
*
* \code
* void dateTime(uint16_t* date, uint16_t* time) {
* uint16_t year;
* uint8_t month, day, hour, minute, second;
*
* // User gets date and time from GPS or real-time clock here
*
* // return date using FAT_DATE macro to format fields
* *date = FAT_DATE(year, month, day);
*
* // return time using FAT_TIME macro to format fields
* *time = FAT_TIME(hour, minute, second);
* }
* \endcode
*
* Sets the function that is called when a file is created or when
* a file's directory entry is modified by sync(). All timestamps,
* access, creation, and modify, are set when a file is created.
* sync() maintains the last access date and last modify date/time.
*
* See the timestamp() function.
*/
static void dateTimeCallback(
void (*dateTime)(uint16_t* date, uint16_t* time)) {
dateTime_ = dateTime;
}
/** Cancel the date/time callback function. */
static void dateTimeCallbackCancel() {dateTime_ = 0;}
bool dirEntry(dir_t* dir);
static void dirName(const dir_t& dir, char* name);
bool exists(const char* name);
int16_t fgets(char* str, int16_t num, char* delim = 0);
/** \return The total number of bytes in a file or directory. */
uint32_t fileSize() const {return fileSize_;}
/** \return The first cluster number for a file or directory. */
uint32_t firstCluster() const {return firstCluster_;}
bool getFilename(char* name);
/** \return True if this is a directory else false. */
bool isDir() const {return type_ >= FAT_FILE_TYPE_MIN_DIR;}
/** \return True if this is a normal file else false. */
bool isFile() const {return type_ == FAT_FILE_TYPE_NORMAL;}
/** \return True if this is an open file/directory else false. */
bool isOpen() const {return type_ != FAT_FILE_TYPE_CLOSED;}
/** \return True if this is a subdirectory else false. */
bool isSubDir() const {return type_ == FAT_FILE_TYPE_SUBDIR;}
/** \return True if this is the root directory. */
bool isRoot() const {
return type_ == FAT_FILE_TYPE_ROOT_FIXED || type_ == FAT_FILE_TYPE_ROOT32;
}
void ls(Print* pr, uint8_t flags = 0, uint8_t indent = 0);
void ls(uint8_t flags = 0);
bool mkdir(SdBaseFile* dir, const char* path, bool pFlag = true);
// alias for backward compactability
bool makeDir(SdBaseFile* dir, const char* path) {
return mkdir(dir, path, false);
}
bool open(SdBaseFile* dirFile, uint16_t index, uint8_t oflag);
bool open(SdBaseFile* dirFile, const char* path, uint8_t oflag);
bool open(const char* path, uint8_t oflag = O_READ);
bool openNext(SdBaseFile* dirFile, uint8_t oflag);
bool openRoot(SdVolume* vol);
int peek();
bool printCreateDateTime(Print* pr);
static void printFatDate(uint16_t fatDate);
static void printFatDate(Print* pr, uint16_t fatDate);
static void printFatTime(uint16_t fatTime);
static void printFatTime(Print* pr, uint16_t fatTime);
int printField(int16_t value, char term);
int printField(uint16_t value, char term);
int printField(int32_t value, char term);
int printField(uint32_t value, char term);
bool printModifyDateTime(Print* pr);
bool printName();
bool printName(Print* pr);
int16_t read();
int read(void* buf, size_t nbyte);
int8_t readDir(dir_t* dir);
static bool remove(SdBaseFile* dirFile, const char* path);
bool remove();
/** Set the file's current position to zero. */
void rewind() {seekSet(0);}
bool rename(SdBaseFile* dirFile, const char* newPath);
bool rmdir();
// for backward compatibility
bool rmDir() {return rmdir();}
bool rmRfStar();
/** Set the files position to current position + \a pos. See seekSet().
* \param[in] offset The new position in bytes from the current position.
* \return true for success or false for failure.
*/
bool seekCur(int32_t offset) {
return seekSet(curPosition_ + offset);
}
/** Set the files position to end-of-file + \a offset. See seekSet().
* \param[in] offset The new position in bytes from end-of-file.
* \return true for success or false for failure.
*/
bool seekEnd(int32_t offset = 0) {return seekSet(fileSize_ + offset);}
bool seekSet(uint32_t pos);
bool sync();
bool timestamp(SdBaseFile* file);
bool timestamp(uint8_t flag, uint16_t year, uint8_t month, uint8_t day,
uint8_t hour, uint8_t minute, uint8_t second);
/** Type of file. You should use isFile() or isDir() instead of type()
* if possible.
*
* \return The file or directory type.
*/
uint8_t type() const {return type_;}
bool truncate(uint32_t size);
/** \return SdVolume that contains this file. */
SdVolume* volume() const {return vol_;}
int write(const void* buf, size_t nbyte);
//------------------------------------------------------------------------------
private:
// allow SdFat to set cwd_
friend class SdFat;
// global pointer to cwd dir
static SdBaseFile* cwd_;
// data time callback function
static void (*dateTime_)(uint16_t* date, uint16_t* time);
// bits defined in flags_
// should be 0X0F
static uint8_t const F_OFLAG = (O_ACCMODE | O_APPEND | O_SYNC);
// sync of directory entry required
static uint8_t const F_FILE_DIR_DIRTY = 0X80;
// private data
uint8_t flags_; // See above for definition of flags_ bits
uint8_t fstate_; // error and eof indicator
uint8_t type_; // type of file see above for values
uint8_t dirIndex_; // index of directory entry in dirBlock
SdVolume* vol_; // volume where file is located
uint32_t curCluster_; // cluster for current file position
uint32_t curPosition_; // current file position in bytes from beginning
uint32_t dirBlock_; // block for this files directory entry
uint32_t fileSize_; // file size in bytes
uint32_t firstCluster_; // first cluster of file
/** experimental don't use */
bool openParent(SdBaseFile* dir);
// private functions
bool addCluster();
cache_t* addDirCluster();
dir_t* cacheDirEntry(uint8_t action);
int8_t lsPrintNext(Print *pr, uint8_t flags, uint8_t indent);
static bool make83Name(const char* str, uint8_t* name, const char** ptr);
bool mkdir(SdBaseFile* parent, const uint8_t dname[11]);
bool open(SdBaseFile* dirFile, const uint8_t dname[11], uint8_t oflag);
bool openCachedEntry(uint8_t cacheIndex, uint8_t oflags);
dir_t* readDirCache();
bool setDirSize();
//------------------------------------------------------------------------------
// to be deleted
static void printDirName(const dir_t& dir,
uint8_t width, bool printSlash);
static void printDirName(Print* pr, const dir_t& dir,
uint8_t width, bool printSlash);
//------------------------------------------------------------------------------
// Deprecated functions - suppress cpplint warnings with NOLINT comment
#if ALLOW_DEPRECATED_FUNCTIONS && !defined(DOXYGEN)
public:
/** \deprecated Use:
* bool contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock);
* \param[out] bgnBlock the first block address for the file.
* \param[out] endBlock the last block address for the file.
* \return true for success or false for failure.
*/
bool contiguousRange(uint32_t& bgnBlock, uint32_t& endBlock) { // NOLINT
return contiguousRange(&bgnBlock, &endBlock);
}
/** \deprecated Use:
* bool createContiguous(SdBaseFile* dirFile,
* const char* path, uint32_t size)
* \param[in] dirFile The directory where the file will be created.
* \param[in] path A path with a valid DOS 8.3 file name.
* \param[in] size The desired file size.
* \return true for success or false for failure.
*/
bool createContiguous(SdBaseFile& dirFile, // NOLINT
const char* path, uint32_t size) {
return createContiguous(&dirFile, path, size);
}
/** \deprecated Use:
* static void dateTimeCallback(
* void (*dateTime)(uint16_t* date, uint16_t* time));
* \param[in] dateTime The user's call back function.
*/
static void dateTimeCallback(
void (*dateTime)(uint16_t& date, uint16_t& time)) { // NOLINT
oldDateTime_ = dateTime;
dateTime_ = dateTime ? oldToNew : 0;
}
/** \deprecated Use: bool dirEntry(dir_t* dir);
* \param[out] dir Location for return of the file's directory entry.
* \return true for success or false for failure.
*/
bool dirEntry(dir_t& dir) {return dirEntry(&dir);} // NOLINT
/** \deprecated Use:
* bool mkdir(SdBaseFile* dir, const char* path);
* \param[in] dir An open SdFat instance for the directory that will contain
* the new directory.
* \param[in] path A path with a valid 8.3 DOS name for the new directory.
* \return true for success or false for failure.
*/
bool mkdir(SdBaseFile& dir, const char* path) { // NOLINT
return mkdir(&dir, path);
}
/** \deprecated Use:
* bool open(SdBaseFile* dirFile, const char* path, uint8_t oflag);
* \param[in] dirFile An open SdFat instance for the directory containing the
* file to be opened.
* \param[in] path A path with a valid 8.3 DOS name for the file.
* \param[in] oflag Values for \a oflag are constructed by a bitwise-inclusive
* OR of flags O_READ, O_WRITE, O_TRUNC, and O_SYNC.
* \return true for success or false for failure.
*/
bool open(SdBaseFile& dirFile, // NOLINT
const char* path, uint8_t oflag) {
return open(&dirFile, path, oflag);
}
/** \deprecated Do not use in new apps
* \param[in] dirFile An open SdFat instance for the directory containing the
* file to be opened.
* \param[in] path A path with a valid 8.3 DOS name for a file to be opened.
* \return true for success or false for failure.
*/
bool open(SdBaseFile& dirFile, const char* path) { // NOLINT
return open(dirFile, path, O_RDWR);
}
/** \deprecated Use:
* bool open(SdBaseFile* dirFile, uint16_t index, uint8_t oflag);
* \param[in] dirFile An open SdFat instance for the directory.
* \param[in] index The \a index of the directory entry for the file to be
* opened. The value for \a index is (directory file position)/32.
* \param[in] oflag Values for \a oflag are constructed by a bitwise-inclusive
* OR of flags O_READ, O_WRITE, O_TRUNC, and O_SYNC.
* \return true for success or false for failure.
*/
bool open(SdBaseFile& dirFile, uint16_t index, uint8_t oflag) { // NOLINT
return open(&dirFile, index, oflag);
}
/** \deprecated Use: bool openRoot(SdVolume* vol);
* \param[in] vol The FAT volume containing the root directory to be opened.
* \return true for success or false for failure.
*/
bool openRoot(SdVolume& vol) {return openRoot(&vol);} // NOLINT
/** \deprecated Use: int8_t readDir(dir_t* dir);
* \param[out] dir The dir_t struct that will receive the data.
* \return bytes read for success zero for eof or -1 for failure.
*/
int8_t readDir(dir_t& dir) {return readDir(&dir);} // NOLINT
/** \deprecated Use:
* static uint8_t remove(SdBaseFile* dirFile, const char* path);
* \param[in] dirFile The directory that contains the file.
* \param[in] path The name of the file to be removed.
* \return true for success or false for failure.
*/
static bool remove(SdBaseFile& dirFile, const char* path) { // NOLINT
return remove(&dirFile, path);
}
//------------------------------------------------------------------------------
// rest are private
private:
static void (*oldDateTime_)(uint16_t& date, uint16_t& time); // NOLINT
static void oldToNew(uint16_t* date, uint16_t* time) {
uint16_t d;
uint16_t t;
oldDateTime_(d, t);
*date = d;
*time = t;
}
#elif !defined(DOXYGEN) // ALLOW_DEPRECATED_FUNCTIONS
public:
bool contiguousRange(uint32_t& bgnBlock, uint32_t& endBlock) // NOLINT
__attribute__((error("use contiguousRange(&bgnBlock, &endBlock)")));
bool createContiguous(SdBaseFile& dirFile, // NOLINT
const char* path, uint32_t size)
__attribute__((error("use createContiguous(&bgnBlock, &endBlock)")));
static void dateTimeCallback( // NOLINT
void (*dateTime)(uint16_t& date, uint16_t& time)) // NOLINT
__attribute__((error("use void dateTimeCallback("
"void (*dateTime)(uint16_t* date, uint16_t* time))")));
bool dirEntry(dir_t& dir) // NOLINT
__attribute__((error("use dirEntry(&dir)")));
bool mkdir(SdBaseFile& dir, const char* path) // NOLINT
__attribute__((error("use mkdir(&dir, path)")));
bool open(SdBaseFile& dirFile, // NOLINT
const char* path, uint8_t oflag)
__attribute__((error("use open(&dirFile, path, oflag)")));
bool open(SdBaseFile& dirFile, const char* path) // NOLINT
__attribute__((error("use open(&dirFile, path, O_RDWR)")));
bool open(SdBaseFile& dirFile, uint16_t index, uint8_t oflag) // NOLINT
__attribute__((error("use open(&dirFile, index, oflag)")));
bool openRoot(SdVolume& vol) // NOLINT
__attribute__((error("use openRoot(&vol)")));
int8_t readDir(dir_t& dir) // NOLINT
__attribute__((error("use readDir(&dir)")));
static bool remove(SdBaseFile& dirFile, const char* path) // NOLINT
__attribute__((error("use remove(&dirFile, path)")));
#endif // ALLOW_DEPRECATED_FUNCTIONS
};
#endif // SdBaseFile_h

View file

@ -0,0 +1,350 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#include <SdFat.h>
#ifndef PSTR
#define PSTR(x) x
#define PGM_P const char*
#endif
//------------------------------------------------------------------------------
#if USE_SERIAL_FOR_STD_OUT || !defined(UDR0)
Print* SdFat::stdOut_ = &Serial;
#else // USE_SERIAL_FOR_STD_OUT
#include <MinimumSerial.h>
Print* SdFat::stdOut_ = &MiniSerial;
#endif // USE_SERIAL_FOR_STD_OUT
//------------------------------------------------------------------------------
static void pstrPrint(PGM_P str) {
for (uint8_t c; (c = pgm_read_byte(str)); str++) SdFat::stdOut()->write(c);
}
//------------------------------------------------------------------------------
static void pstrPrintln(PGM_P str) {
pstrPrint(str);
SdFat::stdOut()->println();
}
//------------------------------------------------------------------------------
/**
* Initialize an SdFat object.
*
* Initializes the SD card, SD volume, and root directory.
*
* \param[in] chipSelectPin SD chip select pin. See Sd2Card::init().
* \param[in] sckRateID value for SPI SCK rate. See Sd2Card::init().
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure.
*/
bool SdFat::begin(uint8_t chipSelectPin, uint8_t sckRateID) {
return card_.init(sckRateID, chipSelectPin) && vol_.init(&card_) && chdir(1);
}
//------------------------------------------------------------------------------
/** Change a volume's working directory to root
*
* Changes the volume's working directory to the SD's root directory.
* Optionally set the current working directory to the volume's
* working directory.
*
* \param[in] set_cwd Set the current working directory to this volume's
* working directory if true.
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure.
*/
bool SdFat::chdir(bool set_cwd) {
if (set_cwd) SdBaseFile::cwd_ = &vwd_;
if (vwd_.isOpen()) vwd_.close();
return vwd_.openRoot(&vol_);
}
//------------------------------------------------------------------------------
/** Change a volume's working directory
*
* Changes the volume working directory to the \a path subdirectory.
* Optionally set the current working directory to the volume's
* working directory.
*
* Example: If the volume's working directory is "/DIR", chdir("SUB")
* will change the volume's working directory from "/DIR" to "/DIR/SUB".
*
* If path is "/", the volume's working directory will be changed to the
* root directory
*
* \param[in] path The name of the subdirectory.
*
* \param[in] set_cwd Set the current working directory to this volume's
* working directory if true.
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure.
*/
bool SdFat::chdir(const char *path, bool set_cwd) {
SdBaseFile dir;
if (path[0] == '/' && path[1] == '\0') return chdir(set_cwd);
if (!dir.open(&vwd_, path, O_READ)) goto fail;
if (!dir.isDir()) goto fail;
vwd_ = dir;
if (set_cwd) SdBaseFile::cwd_ = &vwd_;
return true;
fail:
return false;
}
//------------------------------------------------------------------------------
/** Set the current working directory to a volume's working directory.
*
* This is useful with multiple SD cards.
*
* The current working directory is changed to this volume's working directory.
*
* This is like the Windows/DOS \<drive letter>: command.
*/
void SdFat::chvol() {
SdBaseFile::cwd_ = &vwd_;
}
//------------------------------------------------------------------------------
/** %Print any SD error code and halt. */
void SdFat::errorHalt() {
errorPrint();
while (1);
}
//------------------------------------------------------------------------------
/** %Print msg, any SD error code, and halt.
*
* \param[in] msg Message to print.
*/
void SdFat::errorHalt(char const* msg) {
errorPrint(msg);
while (1);
}
//------------------------------------------------------------------------------
/** %Print msg, any SD error code, and halt.
*
* \param[in] msg Message in program space (flash memory) to print.
*/
void SdFat::errorHalt_P(PGM_P msg) {
errorPrint_P(msg);
while (1);
}
//------------------------------------------------------------------------------
/** %Print any SD error code. */
void SdFat::errorPrint() {
if (!card_.errorCode()) return;
pstrPrint(PSTR("SD errorCode: 0X"));
stdOut_->print(card_.errorCode(), HEX);
pstrPrint(PSTR(",0X"));
stdOut_->println(card_.errorData(), HEX);
}
//------------------------------------------------------------------------------
/** %Print msg, any SD error code.
*
* \param[in] msg Message to print.
*/
void SdFat::errorPrint(char const* msg) {
pstrPrint(PSTR("error: "));
stdOut_->println(msg);
errorPrint();
}
//------------------------------------------------------------------------------
/** %Print msg, any SD error code.
*
* \param[in] msg Message in program space (flash memory) to print.
*/
void SdFat::errorPrint_P(PGM_P msg) {
pstrPrint(PSTR("error: "));
pstrPrintln(msg);
errorPrint();
}
//------------------------------------------------------------------------------
/**
* Test for the existence of a file.
*
* \param[in] name Name of the file to be tested for.
*
* \return true if the file exists else false.
*/
bool SdFat::exists(const char* name) {
return vwd_.exists(name);
}
//------------------------------------------------------------------------------
/** %Print error details and halt after SdFat::init() fails. */
void SdFat::initErrorHalt() {
initErrorPrint();
while (1);
}
//------------------------------------------------------------------------------
/**Print message, error details, and halt after SdFat::init() fails.
*
* \param[in] msg Message to print.
*/
void SdFat::initErrorHalt(char const *msg) {
stdOut_->println(msg);
initErrorHalt();
}
//------------------------------------------------------------------------------
/**Print message, error details, and halt after SdFat::init() fails.
*
* \param[in] msg Message in program space (flash memory) to print.
*/
void SdFat::initErrorHalt_P(PGM_P msg) {
pstrPrintln(msg);
initErrorHalt();
}
//------------------------------------------------------------------------------
/** Print error details after SdFat::init() fails. */
void SdFat::initErrorPrint() {
if (card_.errorCode()) {
pstrPrintln(PSTR("Can't access SD card. Do not reformat."));
if (card_.errorCode() == SD_CARD_ERROR_CMD0) {
pstrPrintln(PSTR("No card, wrong chip select pin, or SPI problem?"));
}
errorPrint();
} else if (vol_.fatType() == 0) {
pstrPrintln(PSTR("Invalid format, reformat SD."));
} else if (!vwd_.isOpen()) {
pstrPrintln(PSTR("Can't open root directory."));
} else {
pstrPrintln(PSTR("No error found."));
}
}
//------------------------------------------------------------------------------
/**Print message and error details and halt after SdFat::init() fails.
*
* \param[in] msg Message to print.
*/
void SdFat::initErrorPrint(char const *msg) {
stdOut_->println(msg);
initErrorPrint();
}
//------------------------------------------------------------------------------
/**Print message and error details after SdFat::init() fails.
*
* \param[in] msg Message in program space (flash memory) to print.
*/
void SdFat::initErrorPrint_P(PGM_P msg) {
pstrPrintln(msg);
initErrorHalt();
}
//------------------------------------------------------------------------------
/** List the directory contents of the volume working directory to stdOut.
*
* \param[in] flags The inclusive OR of
*
* LS_DATE - %Print file modification date
*
* LS_SIZE - %Print file size.
*
* LS_R - Recursive list of subdirectories.
*/
void SdFat::ls(uint8_t flags) {
vwd_.ls(stdOut_, flags);
}
//------------------------------------------------------------------------------
/** List the directory contents of the volume working directory.
*
* \param[in] pr Print stream for list.
*
* \param[in] flags The inclusive OR of
*
* LS_DATE - %Print file modification date
*
* LS_SIZE - %Print file size.
*
* LS_R - Recursive list of subdirectories.
*/
void SdFat::ls(Print* pr, uint8_t flags) {
vwd_.ls(pr, flags);
}
//------------------------------------------------------------------------------
/** Make a subdirectory in the volume working directory.
*
* \param[in] path A path with a valid 8.3 DOS name for the subdirectory.
*
* \param[in] pFlag Create missing parent directories if true.
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure.
*/
bool SdFat::mkdir(const char* path, bool pFlag) {
SdBaseFile sub;
return sub.mkdir(&vwd_, path, pFlag);
}
//------------------------------------------------------------------------------
/** Remove a file from the volume working directory.
*
* \param[in] path A path with a valid 8.3 DOS name for the file.
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure.
*/
bool SdFat::remove(const char* path) {
return SdBaseFile::remove(&vwd_, path);
}
//------------------------------------------------------------------------------
/** Rename a file or subdirectory.
*
* \param[in] oldPath Path name to the file or subdirectory to be renamed.
*
* \param[in] newPath New path name of the file or subdirectory.
*
* The \a newPath object must not exist before the rename call.
*
* The file to be renamed must not be open. The directory entry may be
* moved and file system corruption could occur if the file is accessed by
* a file object that was opened before the rename() call.
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure.
*/
bool SdFat::rename(const char *oldPath, const char *newPath) {
SdBaseFile file;
if (!file.open(oldPath, O_READ)) return false;
return file.rename(&vwd_, newPath);
}
//------------------------------------------------------------------------------
/** Remove a subdirectory from the volume's working directory.
*
* \param[in] path A path with a valid 8.3 DOS name for the subdirectory.
*
* The subdirectory file will be removed only if it is empty.
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure.
*/
bool SdFat::rmdir(const char* path) {
SdBaseFile sub;
if (!sub.open(path, O_READ)) return false;
return sub.rmdir();
}
//------------------------------------------------------------------------------
/** Truncate a file to a specified length. The current file position
* will be maintained if it is less than or equal to \a length otherwise
* it will be set to end of file.
*
* \param[in] path A path with a valid 8.3 DOS name for the file.
* \param[in] length The desired length for the file.
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure.
* Reasons for failure include file is read only, file is a directory,
* \a length is greater than the current file size or an I/O error occurs.
*/
bool SdFat::truncate(const char* path, uint32_t length) {
SdBaseFile file;
if (!file.open(path, O_WRITE)) return false;
return file.truncate(length);
}

View file

@ -0,0 +1,119 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef SdFat_h
#define SdFat_h
/**
* \file
* \brief SdFat class
*/
//------------------------------------------------------------------------------
/** SdFat version YYYYMMDD */
#define SD_FAT_VERSION 20130207
//------------------------------------------------------------------------------
/** error if old IDE */
#if !defined(ARDUINO) || ARDUINO < 100
#error Arduino IDE must be 1.0 or greater
#endif // ARDUINO < 100
//------------------------------------------------------------------------------
#include <SdFile.h>
#include <SdStream.h>
#include <ArduinoStream.h>
#include <MinimumSerial.h>
//------------------------------------------------------------------------------
/**
* \class SdFat
* \brief Integration class for the %SdFat library.
*/
class SdFat {
public:
SdFat() {}
#if ALLOW_DEPRECATED_FUNCTIONS && !defined(DOXYGEN)
/**
* Initialize an SdFat object.
*
* Initializes the SD card, SD volume, and root directory.
*
* \param[in] sckRateID value for SPI SCK rate. See Sd2Card::init().
* \param[in] chipSelectPin SD chip select pin. See Sd2Card::init().
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure.
*/
bool init(uint8_t sckRateID = SPI_FULL_SPEED,
uint8_t chipSelectPin = SD_CHIP_SELECT_PIN) {
return begin(chipSelectPin, sckRateID);
}
#elif !defined(DOXYGEN) // ALLOW_DEPRECATED_FUNCTIONS
bool init() __attribute__((error("use sd.begin()")));
bool init(uint8_t sckRateID)
__attribute__((error("use sd.begin(chipSelect, sckRate)")));
bool init(uint8_t sckRateID, uint8_t chipSelectPin)
__attribute__((error("use sd.begin(chipSelect, sckRate)")));
#endif // ALLOW_DEPRECATED_FUNCTIONS
/** \return a pointer to the Sd2Card object. */
Sd2Card* card() {return &card_;}
bool chdir(bool set_cwd = false);
bool chdir(const char* path, bool set_cwd = false);
void chvol();
void errorHalt();
void errorHalt(char const *msg);
void errorPrint();
void errorPrint(char const *msg);
bool exists(const char* name);
bool begin(uint8_t chipSelectPin = SD_CHIP_SELECT_PIN,
uint8_t sckRateID = SPI_FULL_SPEED);
void initErrorHalt();
void initErrorHalt(char const *msg);
void initErrorPrint();
void initErrorPrint(char const *msg);
void ls(uint8_t flags = 0);
void ls(Print* pr, uint8_t flags = 0);
bool mkdir(const char* path, bool pFlag = true);
bool remove(const char* path);
bool rename(const char *oldPath, const char *newPath);
bool rmdir(const char* path);
bool truncate(const char* path, uint32_t length);
/** \return a pointer to the SdVolume object. */
SdVolume* vol() {return &vol_;}
/** \return a pointer to the volume working directory. */
SdBaseFile* vwd() {return &vwd_;}
//----------------------------------------------------------------------------
void errorHalt_P(PGM_P msg);
void errorPrint_P(PGM_P msg);
void initErrorHalt_P(PGM_P msg);
void initErrorPrint_P(PGM_P msg);
//----------------------------------------------------------------------------
/**
* Set stdOut Print stream for messages.
* \param[in] stream The new Print stream.
*/
static void setStdOut(Print* stream) {stdOut_ = stream;}
/** \return Print stream for messages. */
static Print* stdOut() {return stdOut_;}
private:
Sd2Card card_;
SdVolume vol_;
SdBaseFile vwd_;
static Print* stdOut_;
};
#endif // SdFat_h

View file

@ -0,0 +1,183 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
/**
* \file
* \brief configuration definitions
*/
#ifndef SdFatConfig_h
#define SdFatConfig_h
#include <stdint.h>
//------------------------------------------------------------------------------
/**
* Set USE_SEPARATE_FAT_CACHE nonzero to use a second 512 byte cache
* for FAT table entries. Improves performance for large writes that
* are not a multiple of 512 bytes.
*/
#ifdef __arm__
#define USE_SEPARATE_FAT_CACHE 1
#else // __arm__
#define USE_SEPARATE_FAT_CACHE 0
#endif // __arm__
//------------------------------------------------------------------------------
/**
* Don't use mult-block read/write on small AVR boards
*/
#if defined(RAMEND) && RAMEND < 3000
#define USE_MULTI_BLOCK_SD_IO 0
#else
#define USE_MULTI_BLOCK_SD_IO 1
#endif
//------------------------------------------------------------------------------
/**
* Force use of Arduino Standard SPI library if USE_ARDUINO_SPI_LIBRARY
* is nonzero.
*/
#define USE_ARDUINO_SPI_LIBRARY 0
//------------------------------------------------------------------------------
/**
* Use native SPI on Teensy 3.0 if USE_NATIVE_MK20DX128-SPI is nonzero.
*/
#if defined(__arm__) && defined(CORE_TEENSY)
#define USE_NATIVE_MK20DX128_SPI 1
#else
#define USE_NATIVE_MK20DX128_SPI 0
#endif
//------------------------------------------------------------------------------
/**
* Use fast SAM3X SPI library if USE_NATIVE_SAM3X_SPI is nonzero.
*/
#if defined(__arm__) && !defined(CORE_TEENSY)
#define USE_NATIVE_SAM3X_SPI 1
#else
#define USE_NATIVE_SAM3X_SPI 0
#endif
//------------------------------------------------------------------------------
/**
* To enable SD card CRC checking set USE_SD_CRC nonzero.
*
* Set USE_SD_CRC to 1 to use a smaller slower CRC-CCITT function.
*
* Set USE_SD_CRC to 2 to used a larger faster table driven CRC-CCITT function.
*/
#define USE_SD_CRC 0
//------------------------------------------------------------------------------
/**
* To use multiple SD cards set USE_MULTIPLE_CARDS nonzero.
*
* Using multiple cards costs 400 - 500 bytes of flash.
*
* Each card requires about 550 bytes of SRAM so use of a Mega is recommended.
*/
#define USE_MULTIPLE_CARDS 0
//------------------------------------------------------------------------------
/**
* Set DESTRUCTOR_CLOSES_FILE nonzero to close a file in its destructor.
*
* Causes use of lots of heap in ARM.
*/
#define DESTRUCTOR_CLOSES_FILE 0
//------------------------------------------------------------------------------
/**
* For AVR
*
* Set nonzero to use Serial (the HardwareSerial class) for error messages
* and output from print functions like ls().
*
* If USE_SERIAL_FOR_STD_OUT is zero, a small non-interrupt driven class
* is used to output messages to serial port zero. This allows an alternate
* Serial library like SerialPort to be used with SdFat.
*
* You can redirect stdOut with SdFat::setStdOut(Print* stream) and
* get the current stream with SdFat::stdOut().
*/
#define USE_SERIAL_FOR_STD_OUT 0
//------------------------------------------------------------------------------
/**
* Call flush for endl if ENDL_CALLS_FLUSH is nonzero
*
* The standard for iostreams is to call flush. This is very costly for
* SdFat. Each call to flush causes 2048 bytes of I/O to the SD.
*
* SdFat has a single 512 byte buffer for SD I/O so it must write the current
* data block to the SD, read the directory block from the SD, update the
* directory entry, write the directory block to the SD and read the data
* block back into the buffer.
*
* The SD flash memory controller is not designed for this many rewrites
* so performance may be reduced by more than a factor of 100.
*
* If ENDL_CALLS_FLUSH is zero, you must call flush and/or close to force
* all data to be written to the SD.
*/
#define ENDL_CALLS_FLUSH 0
//------------------------------------------------------------------------------
/**
* Allow use of deprecated functions if ALLOW_DEPRECATED_FUNCTIONS is nonzero
*/
#define ALLOW_DEPRECATED_FUNCTIONS 0
//------------------------------------------------------------------------------
/**
* Allow FAT12 volumes if FAT12_SUPPORT is nonzero.
* FAT12 has not been well tested.
*/
#define FAT12_SUPPORT 0
//------------------------------------------------------------------------------
/**
* SPI init rate for SD initialization commands. Must be 10 (F_CPU/64)
* or greater
*/
#define SPI_SD_INIT_RATE 11
//------------------------------------------------------------------------------
/**
* Define MEGA_SOFT_SPI nonzero to use software SPI on Mega Arduinos.
* Default pins used are SS 10, MOSI 11, MISO 12, and SCK 13.
* Edit Software Spi pins to change pin numbers.
*
* MEGA_SOFT_SPI allows an unmodified Adafruit GPS Shield to be used
* on Mega Arduinos. Software SPI works well with GPS Shield V1.1
* but many SD cards will fail with GPS Shield V1.0.
*/
#define MEGA_SOFT_SPI 0
//------------------------------------------------------------------------------
/**
* Define LEONARDO_SOFT_SPI nonzero to use software SPI on Leonardo Arduinos.
* Default pins used are SS 10, MOSI 11, MISO 12, and SCK 13.
* Edit Software Spi pins to change pin numbers.
*
* LEONARDO_SOFT_SPI allows an unmodified Adafruit GPS Shield to be used
* on Leonardo Arduinos. Software SPI works well with GPS Shield V1.1
* but many SD cards will fail with GPS Shield V1.0.
*/
#define LEONARDO_SOFT_SPI 0
//------------------------------------------------------------------------------
/**
* Set USE_SOFTWARE_SPI nonzero to always use software SPI on AVR.
*/
#define USE_SOFTWARE_SPI 0
// define software SPI pins so Mega can use unmodified 168/328 shields
/** Default Software SPI chip select pin */
uint8_t const SOFT_SPI_CS_PIN = 10;
/** Software SPI Master Out Slave In pin */
uint8_t const SOFT_SPI_MOSI_PIN = 11;
/** Software SPI Master In Slave Out pin */
uint8_t const SOFT_SPI_MISO_PIN = 12;
/** Software SPI Clock pin */
uint8_t const SOFT_SPI_SCK_PIN = 13;
#endif // SdFatConfig_h

View file

@ -0,0 +1,604 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef SdFatStructs_h
#define SdFatStructs_h
/**
* \file
* \brief FAT file structures
*/
/*
* mostly from Microsoft document fatgen103.doc
* http://www.microsoft.com/whdc/system/platform/firmware/fatgen.mspx
*/
//------------------------------------------------------------------------------
/** Value for byte 510 of boot block or MBR */
uint8_t const BOOTSIG0 = 0X55;
/** Value for byte 511 of boot block or MBR */
uint8_t const BOOTSIG1 = 0XAA;
/** Value for bootSignature field int FAT/FAT32 boot sector */
uint8_t const EXTENDED_BOOT_SIG = 0X29;
//------------------------------------------------------------------------------
/**
* \struct partitionTable
* \brief MBR partition table entry
*
* A partition table entry for a MBR formatted storage device.
* The MBR partition table has four entries.
*/
struct partitionTable {
/**
* Boot Indicator . Indicates whether the volume is the active
* partition. Legal values include: 0X00. Do not use for booting.
* 0X80 Active partition.
*/
uint8_t boot;
/**
* Head part of Cylinder-head-sector address of the first block in
* the partition. Legal values are 0-255. Only used in old PC BIOS.
*/
uint8_t beginHead;
/**
* Sector part of Cylinder-head-sector address of the first block in
* the partition. Legal values are 1-63. Only used in old PC BIOS.
*/
unsigned beginSector : 6;
/** High bits cylinder for first block in partition. */
unsigned beginCylinderHigh : 2;
/**
* Combine beginCylinderLow with beginCylinderHigh. Legal values
* are 0-1023. Only used in old PC BIOS.
*/
uint8_t beginCylinderLow;
/**
* Partition type. See defines that begin with PART_TYPE_ for
* some Microsoft partition types.
*/
uint8_t type;
/**
* head part of cylinder-head-sector address of the last sector in the
* partition. Legal values are 0-255. Only used in old PC BIOS.
*/
uint8_t endHead;
/**
* Sector part of cylinder-head-sector address of the last sector in
* the partition. Legal values are 1-63. Only used in old PC BIOS.
*/
unsigned endSector : 6;
/** High bits of end cylinder */
unsigned endCylinderHigh : 2;
/**
* Combine endCylinderLow with endCylinderHigh. Legal values
* are 0-1023. Only used in old PC BIOS.
*/
uint8_t endCylinderLow;
/** Logical block address of the first block in the partition. */
uint32_t firstSector;
/** Length of the partition, in blocks. */
uint32_t totalSectors;
}__attribute__((packed));
/** Type name for partitionTable */
typedef struct partitionTable part_t;
//------------------------------------------------------------------------------
/**
* \struct masterBootRecord
*
* \brief Master Boot Record
*
* The first block of a storage device that is formatted with a MBR.
*/
struct masterBootRecord {
/** Code Area for master boot program. */
uint8_t codeArea[440];
/** Optional Windows NT disk signature. May contain boot code. */
uint32_t diskSignature;
/** Usually zero but may be more boot code. */
uint16_t usuallyZero;
/** Partition tables. */
part_t part[4];
/** First MBR signature byte. Must be 0X55 */
uint8_t mbrSig0;
/** Second MBR signature byte. Must be 0XAA */
uint8_t mbrSig1;
}__attribute__((packed));
/** Type name for masterBootRecord */
typedef struct masterBootRecord mbr_t;
//------------------------------------------------------------------------------
/**
* \struct fat_boot
*
* \brief Boot sector for a FAT12/FAT16 volume.
*
*/
struct fat_boot {
/**
* The first three bytes of the boot sector must be valid,
* executable x 86-based CPU instructions. This includes a
* jump instruction that skips the next nonexecutable bytes.
*/
uint8_t jump[3];
/**
* This is typically a string of characters that identifies
* the operating system that formatted the volume.
*/
char oemId[8];
/**
* The size of a hardware sector. Valid decimal values for this
* field are 512, 1024, 2048, and 4096. For most disks used in
* the United States, the value of this field is 512.
*/
uint16_t bytesPerSector;
/**
* Number of sectors per allocation unit. This value must be a
* power of 2 that is greater than 0. The legal values are
* 1, 2, 4, 8, 16, 32, 64, and 128. 128 should be avoided.
*/
uint8_t sectorsPerCluster;
/**
* The number of sectors preceding the start of the first FAT,
* including the boot sector. The value of this field is always 1.
*/
uint16_t reservedSectorCount;
/**
* The number of copies of the FAT on the volume.
* The value of this field is always 2.
*/
uint8_t fatCount;
/**
* For FAT12 and FAT16 volumes, this field contains the count of
* 32-byte directory entries in the root directory. For FAT32 volumes,
* this field must be set to 0. For FAT12 and FAT16 volumes, this
* value should always specify a count that when multiplied by 32
* results in a multiple of bytesPerSector. FAT16 volumes should
* use the value 512.
*/
uint16_t rootDirEntryCount;
/**
* This field is the old 16-bit total count of sectors on the volume.
* This count includes the count of all sectors in all four regions
* of the volume. This field can be 0; if it is 0, then totalSectors32
* must be nonzero. For FAT32 volumes, this field must be 0. For
* FAT12 and FAT16 volumes, this field contains the sector count, and
* totalSectors32 is 0 if the total sector count fits
* (is less than 0x10000).
*/
uint16_t totalSectors16;
/**
* This dates back to the old MS-DOS 1.x media determination and is
* no longer usually used for anything. 0xF8 is the standard value
* for fixed (nonremovable) media. For removable media, 0xF0 is
* frequently used. Legal values are 0xF0 or 0xF8-0xFF.
*/
uint8_t mediaType;
/**
* Count of sectors occupied by one FAT on FAT12/FAT16 volumes.
* On FAT32 volumes this field must be 0, and sectorsPerFat32
* contains the FAT size count.
*/
uint16_t sectorsPerFat16;
/** Sectors per track for interrupt 0x13. Not used otherwise. */
uint16_t sectorsPerTrack;
/** Number of heads for interrupt 0x13. Not used otherwise. */
uint16_t headCount;
/**
* Count of hidden sectors preceding the partition that contains this
* FAT volume. This field is generally only relevant for media
* visible on interrupt 0x13.
*/
uint32_t hidddenSectors;
/**
* This field is the new 32-bit total count of sectors on the volume.
* This count includes the count of all sectors in all four regions
* of the volume. This field can be 0; if it is 0, then
* totalSectors16 must be nonzero.
*/
uint32_t totalSectors32;
/**
* Related to the BIOS physical drive number. Floppy drives are
* identified as 0x00 and physical hard disks are identified as
* 0x80, regardless of the number of physical disk drives.
* Typically, this value is set prior to issuing an INT 13h BIOS
* call to specify the device to access. The value is only
* relevant if the device is a boot device.
*/
uint8_t driveNumber;
/** used by Windows NT - should be zero for FAT */
uint8_t reserved1;
/** 0X29 if next three fields are valid */
uint8_t bootSignature;
/**
* A random serial number created when formatting a disk,
* which helps to distinguish between disks.
* Usually generated by combining date and time.
*/
uint32_t volumeSerialNumber;
/**
* A field once used to store the volume label. The volume label
* is now stored as a special file in the root directory.
*/
char volumeLabel[11];
/**
* A field with a value of either FAT, FAT12 or FAT16,
* depending on the disk format.
*/
char fileSystemType[8];
/** X86 boot code */
uint8_t bootCode[448];
/** must be 0X55 */
uint8_t bootSectorSig0;
/** must be 0XAA */
uint8_t bootSectorSig1;
}__attribute__((packed));
/** Type name for FAT Boot Sector */
typedef struct fat_boot fat_boot_t;
//------------------------------------------------------------------------------
/**
* \struct fat32_boot
*
* \brief Boot sector for a FAT32 volume.
*
*/
struct fat32_boot {
/**
* The first three bytes of the boot sector must be valid,
* executable x 86-based CPU instructions. This includes a
* jump instruction that skips the next nonexecutable bytes.
*/
uint8_t jump[3];
/**
* This is typically a string of characters that identifies
* the operating system that formatted the volume.
*/
char oemId[8];
/**
* The size of a hardware sector. Valid decimal values for this
* field are 512, 1024, 2048, and 4096. For most disks used in
* the United States, the value of this field is 512.
*/
uint16_t bytesPerSector;
/**
* Number of sectors per allocation unit. This value must be a
* power of 2 that is greater than 0. The legal values are
* 1, 2, 4, 8, 16, 32, 64, and 128. 128 should be avoided.
*/
uint8_t sectorsPerCluster;
/**
* The number of sectors preceding the start of the first FAT,
* including the boot sector. Must not be zero
*/
uint16_t reservedSectorCount;
/**
* The number of copies of the FAT on the volume.
* The value of this field is always 2.
*/
uint8_t fatCount;
/**
* FAT12/FAT16 only. For FAT32 volumes, this field must be set to 0.
*/
uint16_t rootDirEntryCount;
/**
* For FAT32 volumes, this field must be 0.
*/
uint16_t totalSectors16;
/**
* This dates back to the old MS-DOS 1.x media determination and is
* no longer usually used for anything. 0xF8 is the standard value
* for fixed (nonremovable) media. For removable media, 0xF0 is
* frequently used. Legal values are 0xF0 or 0xF8-0xFF.
*/
uint8_t mediaType;
/**
* On FAT32 volumes this field must be 0, and sectorsPerFat32
* contains the FAT size count.
*/
uint16_t sectorsPerFat16;
/** Sectors per track for interrupt 0x13. Not used otherwise. */
uint16_t sectorsPerTrack;
/** Number of heads for interrupt 0x13. Not used otherwise. */
uint16_t headCount;
/**
* Count of hidden sectors preceding the partition that contains this
* FAT volume. This field is generally only relevant for media
* visible on interrupt 0x13.
*/
uint32_t hidddenSectors;
/**
* Contains the total number of sectors in the FAT32 volume.
*/
uint32_t totalSectors32;
/**
* Count of sectors occupied by one FAT on FAT32 volumes.
*/
uint32_t sectorsPerFat32;
/**
* This field is only defined for FAT32 media and does not exist on
* FAT12 and FAT16 media.
* Bits 0-3 -- Zero-based number of active FAT.
* Only valid if mirroring is disabled.
* Bits 4-6 -- Reserved.
* Bit 7 -- 0 means the FAT is mirrored at runtime into all FATs.
* -- 1 means only one FAT is active; it is the one referenced
* in bits 0-3.
* Bits 8-15 -- Reserved.
*/
uint16_t fat32Flags;
/**
* FAT32 version. High byte is major revision number.
* Low byte is minor revision number. Only 0.0 define.
*/
uint16_t fat32Version;
/**
* Cluster number of the first cluster of the root directory for FAT32.
* This usually 2 but not required to be 2.
*/
uint32_t fat32RootCluster;
/**
* Sector number of FSINFO structure in the reserved area of the
* FAT32 volume. Usually 1.
*/
uint16_t fat32FSInfo;
/**
* If nonzero, indicates the sector number in the reserved area
* of the volume of a copy of the boot record. Usually 6.
* No value other than 6 is recommended.
*/
uint16_t fat32BackBootBlock;
/**
* Reserved for future expansion. Code that formats FAT32 volumes
* should always set all of the bytes of this field to 0.
*/
uint8_t fat32Reserved[12];
/**
* Related to the BIOS physical drive number. Floppy drives are
* identified as 0x00 and physical hard disks are identified as
* 0x80, regardless of the number of physical disk drives.
* Typically, this value is set prior to issuing an INT 13h BIOS
* call to specify the device to access. The value is only
* relevant if the device is a boot device.
*/
uint8_t driveNumber;
/** used by Windows NT - should be zero for FAT */
uint8_t reserved1;
/** 0X29 if next three fields are valid */
uint8_t bootSignature;
/**
* A random serial number created when formatting a disk,
* which helps to distinguish between disks.
* Usually generated by combining date and time.
*/
uint32_t volumeSerialNumber;
/**
* A field once used to store the volume label. The volume label
* is now stored as a special file in the root directory.
*/
char volumeLabel[11];
/**
* A text field with a value of FAT32.
*/
char fileSystemType[8];
/** X86 boot code */
uint8_t bootCode[420];
/** must be 0X55 */
uint8_t bootSectorSig0;
/** must be 0XAA */
uint8_t bootSectorSig1;
}__attribute__((packed));
/** Type name for FAT32 Boot Sector */
typedef struct fat32_boot fat32_boot_t;
//------------------------------------------------------------------------------
/** Lead signature for a FSINFO sector */
uint32_t const FSINFO_LEAD_SIG = 0x41615252;
/** Struct signature for a FSINFO sector */
uint32_t const FSINFO_STRUCT_SIG = 0x61417272;
/**
* \struct fat32_fsinfo
*
* \brief FSINFO sector for a FAT32 volume.
*
*/
struct fat32_fsinfo {
/** must be 0X52, 0X52, 0X61, 0X41 */
uint32_t leadSignature;
/** must be zero */
uint8_t reserved1[480];
/** must be 0X72, 0X72, 0X41, 0X61 */
uint32_t structSignature;
/**
* Contains the last known free cluster count on the volume.
* If the value is 0xFFFFFFFF, then the free count is unknown
* and must be computed. Any other value can be used, but is
* not necessarily correct. It should be range checked at least
* to make sure it is <= volume cluster count.
*/
uint32_t freeCount;
/**
* This is a hint for the FAT driver. It indicates the cluster
* number at which the driver should start looking for free clusters.
* If the value is 0xFFFFFFFF, then there is no hint and the driver
* should start looking at cluster 2.
*/
uint32_t nextFree;
/** must be zero */
uint8_t reserved2[12];
/** must be 0X00, 0X00, 0X55, 0XAA */
uint8_t tailSignature[4];
}__attribute__((packed));
/** Type name for FAT32 FSINFO Sector */
typedef struct fat32_fsinfo fat32_fsinfo_t;
//------------------------------------------------------------------------------
// End Of Chain values for FAT entries
/** FAT12 end of chain value used by Microsoft. */
uint16_t const FAT12EOC = 0XFFF;
/** Minimum value for FAT12 EOC. Use to test for EOC. */
uint16_t const FAT12EOC_MIN = 0XFF8;
/** FAT16 end of chain value used by Microsoft. */
uint16_t const FAT16EOC = 0XFFFF;
/** Minimum value for FAT16 EOC. Use to test for EOC. */
uint16_t const FAT16EOC_MIN = 0XFFF8;
/** FAT32 end of chain value used by Microsoft. */
uint32_t const FAT32EOC = 0X0FFFFFFF;
/** Minimum value for FAT32 EOC. Use to test for EOC. */
uint32_t const FAT32EOC_MIN = 0X0FFFFFF8;
/** Mask a for FAT32 entry. Entries are 28 bits. */
uint32_t const FAT32MASK = 0X0FFFFFFF;
//------------------------------------------------------------------------------
/**
* \struct directoryEntry
* \brief FAT short directory entry
*
* Short means short 8.3 name, not the entry size.
*
* Date Format. A FAT directory entry date stamp is a 16-bit field that is
* basically a date relative to the MS-DOS epoch of 01/01/1980. Here is the
* format (bit 0 is the LSB of the 16-bit word, bit 15 is the MSB of the
* 16-bit word):
*
* Bits 9-15: Count of years from 1980, valid value range 0-127
* inclusive (1980-2107).
*
* Bits 5-8: Month of year, 1 = January, valid value range 1-12 inclusive.
*
* Bits 0-4: Day of month, valid value range 1-31 inclusive.
*
* Time Format. A FAT directory entry time stamp is a 16-bit field that has
* a granularity of 2 seconds. Here is the format (bit 0 is the LSB of the
* 16-bit word, bit 15 is the MSB of the 16-bit word).
*
* Bits 11-15: Hours, valid value range 0-23 inclusive.
*
* Bits 5-10: Minutes, valid value range 0-59 inclusive.
*
* Bits 0-4: 2-second count, valid value range 0-29 inclusive (0 - 58 seconds).
*
* The valid time range is from Midnight 00:00:00 to 23:59:58.
*/
struct directoryEntry {
/** Short 8.3 name.
*
* The first eight bytes contain the file name with blank fill.
* The last three bytes contain the file extension with blank fill.
*/
uint8_t name[11];
/** Entry attributes.
*
* The upper two bits of the attribute byte are reserved and should
* always be set to 0 when a file is created and never modified or
* looked at after that. See defines that begin with DIR_ATT_.
*/
uint8_t attributes;
/**
* Reserved for use by Windows NT. Set value to 0 when a file is
* created and never modify or look at it after that.
*/
uint8_t reservedNT;
/**
* The granularity of the seconds part of creationTime is 2 seconds
* so this field is a count of tenths of a second and its valid
* value range is 0-199 inclusive. (WHG note - seems to be hundredths)
*/
uint8_t creationTimeTenths;
/** Time file was created. */
uint16_t creationTime;
/** Date file was created. */
uint16_t creationDate;
/**
* Last access date. Note that there is no last access time, only
* a date. This is the date of last read or write. In the case of
* a write, this should be set to the same date as lastWriteDate.
*/
uint16_t lastAccessDate;
/**
* High word of this entry's first cluster number (always 0 for a
* FAT12 or FAT16 volume).
*/
uint16_t firstClusterHigh;
/** Time of last write. File creation is considered a write. */
uint16_t lastWriteTime;
/** Date of last write. File creation is considered a write. */
uint16_t lastWriteDate;
/** Low word of this entry's first cluster number. */
uint16_t firstClusterLow;
/** 32-bit unsigned holding this file's size in bytes. */
uint32_t fileSize;
}__attribute__((packed));
//------------------------------------------------------------------------------
// Definitions for directory entries
//
/** Type name for directoryEntry */
typedef struct directoryEntry dir_t;
/** escape for name[0] = 0XE5 */
uint8_t const DIR_NAME_0XE5 = 0X05;
/** name[0] value for entry that is free after being "deleted" */
uint8_t const DIR_NAME_DELETED = 0XE5;
/** name[0] value for entry that is free and no allocated entries follow */
uint8_t const DIR_NAME_FREE = 0X00;
/** file is read-only */
uint8_t const DIR_ATT_READ_ONLY = 0X01;
/** File should hidden in directory listings */
uint8_t const DIR_ATT_HIDDEN = 0X02;
/** Entry is for a system file */
uint8_t const DIR_ATT_SYSTEM = 0X04;
/** Directory entry contains the volume label */
uint8_t const DIR_ATT_VOLUME_ID = 0X08;
/** Entry is for a directory */
uint8_t const DIR_ATT_DIRECTORY = 0X10;
/** Old DOS archive bit for backup support */
uint8_t const DIR_ATT_ARCHIVE = 0X20;
/** Test value for long name entry. Test is
(d->attributes & DIR_ATT_LONG_NAME_MASK) == DIR_ATT_LONG_NAME. */
uint8_t const DIR_ATT_LONG_NAME = 0X0F;
/** Test mask for long name entry */
uint8_t const DIR_ATT_LONG_NAME_MASK = 0X3F;
/** defined attribute bits */
uint8_t const DIR_ATT_DEFINED_BITS = 0X3F;
/** Directory entry is part of a long name
* \param[in] dir Pointer to a directory entry.
*
* \return true if the entry is for part of a long name else false.
*/
static inline uint8_t DIR_IS_LONG_NAME(const dir_t* dir) {
return (dir->attributes & DIR_ATT_LONG_NAME_MASK) == DIR_ATT_LONG_NAME;
}
/** Mask for file/subdirectory tests */
uint8_t const DIR_ATT_FILE_TYPE_MASK = (DIR_ATT_VOLUME_ID | DIR_ATT_DIRECTORY);
/** Directory entry is for a file
* \param[in] dir Pointer to a directory entry.
*
* \return true if the entry is for a normal file else false.
*/
static inline uint8_t DIR_IS_FILE(const dir_t* dir) {
return (dir->attributes & DIR_ATT_FILE_TYPE_MASK) == 0;
}
/** Directory entry is for a subdirectory
* \param[in] dir Pointer to a directory entry.
*
* \return true if the entry is for a subdirectory else false.
*/
static inline uint8_t DIR_IS_SUBDIR(const dir_t* dir) {
return (dir->attributes & DIR_ATT_FILE_TYPE_MASK) == DIR_ATT_DIRECTORY;
}
/** Directory entry is for a file or subdirectory
* \param[in] dir Pointer to a directory entry.
*
* \return true if the entry is for a normal file or subdirectory else false.
*/
static inline uint8_t DIR_IS_FILE_OR_SUBDIR(const dir_t* dir) {
return (dir->attributes & DIR_ATT_VOLUME_ID) == 0;
}
#endif // SdFatStructs_h

View file

@ -0,0 +1,77 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#include <SdFat.h>
#include <SdFatUtil.h>
#ifdef __arm__
// should use uinstd.h to define sbrk but Due causes a conflict
extern "C" char* sbrk(int incr);
#endif // __arm__
//------------------------------------------------------------------------------
/** Amount of free RAM
* \return The number of free bytes.
*/
int SdFatUtil::FreeRam() {
char top;
#ifdef __arm__
return &top - reinterpret_cast<char*>(sbrk(0));
#elif defined(CORE_TEENSY) || (ARDUINO > 103 && ARDUINO != 151)
extern char *__brkval;
return &top - __brkval;
#else // __arm__
extern char *__brkval;
extern char *__malloc_heap_start;
return __brkval ? &top - __brkval : &top - __malloc_heap_start;
#endif // __arm__
}
//------------------------------------------------------------------------------
/** %Print a string in flash memory.
*
* \param[in] pr Print object for output.
* \param[in] str Pointer to string stored in flash memory.
*/
void SdFatUtil::print_P(Print* pr, PGM_P str) {
for (uint8_t c; (c = pgm_read_byte(str)); str++) pr->write(c);
}
//------------------------------------------------------------------------------
/** %Print a string in flash memory followed by a CR/LF.
*
* \param[in] pr Print object for output.
* \param[in] str Pointer to string stored in flash memory.
*/
void SdFatUtil::println_P(Print* pr, PGM_P str) {
print_P(pr, str);
pr->println();
}
//------------------------------------------------------------------------------
/** %Print a string in flash memory to Serial.
*
* \param[in] str Pointer to string stored in flash memory.
*/
void SdFatUtil::SerialPrint_P(PGM_P str) {
print_P(SdFat::stdOut(), str);
}
//------------------------------------------------------------------------------
/** %Print a string in flash memory to Serial followed by a CR/LF.
*
* \param[in] str Pointer to string stored in flash memory.
*/
void SdFatUtil::SerialPrintln_P(PGM_P str) {
println_P(SdFat::stdOut(), str);
}

View file

@ -0,0 +1,40 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef SdFatUtil_h
#define SdFatUtil_h
/**
* \file
* \brief Useful utility functions.
*/
#include <SdFat.h>
/** Store and print a string in flash memory.*/
#define PgmPrint(x) SerialPrint_P(PSTR(x))
/** Store and print a string in flash memory followed by a CR/LF.*/
#define PgmPrintln(x) SerialPrintln_P(PSTR(x))
namespace SdFatUtil {
int FreeRam();
void print_P(Print* pr, PGM_P str);
void println_P(Print* pr, PGM_P str);
void SerialPrint_P(PGM_P str);
void SerialPrintln_P(PGM_P str);
}
using namespace SdFatUtil; // NOLINT
#endif // #define SdFatUtil_h

View file

@ -0,0 +1,227 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
/**
\mainpage Arduino %SdFat Library
<CENTER>Copyright &copy; 2012 by William Greiman
</CENTER>
\section Intro Introduction
The Arduino %SdFat Library is a minimal implementation of FAT16 and FAT32
file systems on SD flash memory cards. Standard SD and high capacity SDHC
cards are supported.
Experimental support for FAT12 can be enabled by setting FAT12_SUPPORT
nonzero in SdFatConfig.h.
The %SdFat library only supports short 8.3 names.
The main classes in %SdFat are SdFat, SdFile, \ref fstream, \ref ifstream,
and \ref ofstream.
The SdFat class maintains a volume working directories, a current working
directory, and simplifies initialization of other classes.
The SdFile class provides binary file access functions such as open(), read(),
remove(), write(), close() and sync(). This class supports access to the root
directory and subdirectories.
The \ref fstream class implements C++ iostreams for both reading and writing
text files.
The \ref ifstream class implements the C++ iostreams for reading text files.
The \ref ofstream class implements the C++ iostreams for writing text files.
The classes \ref ibufstream and \ref obufstream format and parse character
strings in memory buffers.
the classes ArduinoInStream and ArduinoOutStream provide iostream functions
for Serial, LiquidCrystal, and other devices.
The SdVolume class supports FAT16 and FAT32 partitions. Most applications
will not need to call SdVolume member function.
The Sd2Card class supports access to standard SD cards and SDHC cards. Most
applications will not need to call Sd2Card functions. The Sd2Card class can
be used for raw access to the SD card.
A number of example are provided in the %SdFat/examples folder. These were
developed to test %SdFat and illustrate its use.
%SdFat was developed for high speed data recording. %SdFat was used to
implement an audio record/play class, WaveRP, for the Adafruit Wave Shield.
This application uses special Sd2Card calls to write to contiguous files in
raw mode. These functions reduce write latency so that audio can be
recorded with the small amount of RAM in the Arduino.
\section SDcard SD\SDHC Cards
Arduinos access SD cards using the cards SPI protocol. PCs, Macs, and
most consumer devices use the 4-bit parallel SD protocol. A card that
functions well on A PC or Mac may not work well on the Arduino.
Most cards have good SPI read performance but cards vary widely in SPI
write performance. Write performance is limited by how efficiently the
card manages internal erase/remapping operations. The Arduino cannot
optimize writes to reduce erase operations because of its limit RAM.
SanDisk cards generally have good write performance. They seem to have
more internal RAM buffering than other cards and therefore can limit
the number of flash erase operations that the Arduino forces due to its
limited RAM.
\section Hardware Hardware Configuration
%SdFat was developed using an
<A HREF = "http://www.adafruit.com/"> Adafruit Industries</A>
<A HREF = "http://www.ladyada.net/make/waveshield/"> Wave Shield</A>.
The hardware interface to the SD card should not use a resistor based level
shifter. %SdFat sets the SPI bus frequency to 8 MHz which results in signal
rise times that are too slow for the edge detectors in many newer SD card
controllers when resistor voltage dividers are used.
The 5 to 3.3 V level shifter for 5 V Arduinos should be IC based like the
74HC4050N based circuit shown in the file SdLevel.png. The Adafruit Wave Shield
uses a 74AHC125N. Gravitech sells SD and MicroSD Card Adapters based on the
74LCX245.
If you are using a resistor based level shifter and are having problems try
setting the SPI bus frequency to 4 MHz. This can be done by using
card.init(SPI_HALF_SPEED) to initialize the SD card.
\section comment Bugs and Comments
If you wish to report bugs or have comments, send email to fat16lib@sbcglobal.net.
\section SdFatClass SdFat Usage
%SdFat uses a slightly restricted form of short names.
Only printable ASCII characters are supported. No characters with code point
values greater than 127 are allowed. Space is not allowed even though space
was allowed in the API of early versions of DOS.
Short names are limited to 8 characters followed by an optional period (.)
and extension of up to 3 characters. The characters may be any combination
of letters and digits. The following special characters are also allowed:
$ % ' - _ @ ~ ` ! ( ) { } ^ # &
Short names are always converted to upper case and their original case
value is lost.
\note
The Arduino Print class uses character
at a time writes so it was necessary to use a \link SdFile::sync() sync() \endlink
function to control when data is written to the SD card.
\par
An application which writes to a file using print(), println() or
\link SdFile::write write() \endlink must call \link SdFile::sync() sync() \endlink
at the appropriate time to force data and directory information to be written
to the SD Card. Data and directory information are also written to the SD card
when \link SdFile::close() close() \endlink is called.
\par
Applications must use care calling \link SdFile::sync() sync() \endlink
since 2048 bytes of I/O is required to update file and
directory information. This includes writing the current data block, reading
the block that contains the directory entry for update, writing the directory
block back and reading back the current data block.
It is possible to open a file with two or more instances of SdFile. A file may
be corrupted if data is written to the file by more than one instance of SdFile.
\section HowTo How to format SD Cards as FAT Volumes
You should use a freshly formatted SD card for best performance. FAT
file systems become slower if many files have been created and deleted.
This is because the directory entry for a deleted file is marked as deleted,
but is not deleted. When a new file is created, these entries must be scanned
before creating the file, a flaw in the FAT design. Also files can become
fragmented which causes reads and writes to be slower.
A formatter sketch, SdFormatter.pde, is included in the
%SdFat/examples/SdFormatter directory. This sketch attempts to
emulate SD Association's SDFormatter.
The best way to restore an SD card's format on a PC is to use SDFormatter
which can be downloaded from:
http://www.sdcard.org/consumers/formatter/
SDFormatter aligns flash erase boundaries with file
system structures which reduces write latency and file system overhead.
SDFormatter does not have an option for FAT type so it may format
small cards as FAT12.
After the MBR is restored by SDFormatter you may need to reformat small
cards that have been formatted FAT12 to force the volume type to be FAT16.
If you reformat the SD card with an OS utility, choose a cluster size that
will result in:
4084 < CountOfClusters && CountOfClusters < 65525
The volume will then be FAT16.
If you are formatting an SD card on OS X or Linux, be sure to use the first
partition. Format this partition with a cluster count in above range for FAT16.
SDHC cards should be formatted FAT32 with a cluster size of 32 KB.
Microsoft operating systems support removable media formatted with a
Master Boot Record, MBR, or formatted as a super floppy with a FAT Boot Sector
in block zero.
Microsoft operating systems expect MBR formatted removable media
to have only one partition. The first partition should be used.
Microsoft operating systems do not support partitioning SD flash cards.
If you erase an SD card with a program like KillDisk, Most versions of
Windows will format the card as a super floppy.
\section References References
Adafruit Industries:
http://www.adafruit.com/
http://www.ladyada.net/make/waveshield/
The Arduino site:
http://www.arduino.cc/
For more information about FAT file systems see:
http://www.microsoft.com/whdc/system/platform/firmware/fatgen.mspx
For information about using SD cards as SPI devices see:
http://www.sdcard.org/developers/tech/sdcard/pls/Simplified_Physical_Layer_Spec.pdf
The ATmega328 datasheet:
http://www.atmel.com/dyn/resources/prod_documents/doc8161.pdf
*/

View file

@ -0,0 +1,83 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#include <SdFile.h>
/** Create a file object and open it in the current working directory.
*
* \param[in] path A path with a valid 8.3 DOS name for a file to be opened.
*
* \param[in] oflag Values for \a oflag are constructed by a bitwise-inclusive
* OR of open flags. see SdBaseFile::open(SdBaseFile*, const char*, uint8_t).
*/
SdFile::SdFile(const char* path, uint8_t oflag) : SdBaseFile(path, oflag) {
}
//------------------------------------------------------------------------------
/** Write data to an open file.
*
* \note Data is moved to the cache but may not be written to the
* storage device until sync() is called.
*
* \param[in] buf Pointer to the location of the data to be written.
*
* \param[in] nbyte Number of bytes to write.
*
* \return For success write() returns the number of bytes written, always
* \a nbyte. If an error occurs, write() returns -1. Possible errors
* include write() is called before a file has been opened, write is called
* for a read-only file, device is full, a corrupt file system or an I/O error.
*
*/
int SdFile::write(const void* buf, size_t nbyte) {
return SdBaseFile::write(buf, nbyte);
}
//------------------------------------------------------------------------------
/** Write a byte to a file. Required by the Arduino Print class.
* \param[in] b the byte to be written.
* Use getWriteError to check for errors.
* \return 1 for success and 0 for failure.
*/
size_t SdFile::write(uint8_t b) {
return SdBaseFile::write(&b, 1) == 1 ? 1 : 0;
}
//------------------------------------------------------------------------------
/** Write a string to a file. Used by the Arduino Print class.
* \param[in] str Pointer to the string.
* Use getWriteError to check for errors.
* \return count of characters written for success or -1 for failure.
*/
int SdFile::write(const char* str) {
return SdBaseFile::write(str, strlen(str));
}
//------------------------------------------------------------------------------
/** Write a PROGMEM string to a file.
* \param[in] str Pointer to the PROGMEM string.
* Use getWriteError to check for errors.
*/
void SdFile::write_P(PGM_P str) {
for (uint8_t c; (c = pgm_read_byte(str)); str++) write(c);
}
//------------------------------------------------------------------------------
/** Write a PROGMEM string followed by CR/LF to a file.
* \param[in] str Pointer to the PROGMEM string.
* Use getWriteError to check for errors.
*/
void SdFile::writeln_P(PGM_P str) {
write_P(str);
write_P(PSTR("\r\n"));
}

View file

@ -0,0 +1,49 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
/**
* \file
* \brief SdFile class
*/
#include <SdBaseFile.h>
#ifndef SdFile_h
#define SdFile_h
//------------------------------------------------------------------------------
/**
* \class SdFile
* \brief SdBaseFile with Print.
*/
class SdFile : public SdBaseFile, public Print {
public:
SdFile() {}
SdFile(const char* name, uint8_t oflag);
#if DESTRUCTOR_CLOSES_FILE
~SdFile() {}
#endif // DESTRUCTOR_CLOSES_FILE
/** \return value of writeError */
bool getWriteError() {return SdBaseFile::getWriteError();}
/** Set writeError to zero */
void clearWriteError() {SdBaseFile::clearWriteError();}
size_t write(uint8_t b);
int write(const char* str);
int write(const void* buf, size_t nbyte);
void write_P(PGM_P str);
void writeln_P(PGM_P str);
};
#endif // SdFile_h

View file

@ -0,0 +1,277 @@
/* Arduino Sd2Card Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino Sd2Card Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino Sd2Card Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef SdInfo_h
#define SdInfo_h
#include <stdint.h>
// Based on the document:
//
// SD Specifications
// Part 1
// Physical Layer
// Simplified Specification
// Version 3.01
// May 18, 2010
//
// http://www.sdcard.org/developers/tech/sdcard/pls/simplified_specs
//------------------------------------------------------------------------------
// SD card commands
/** GO_IDLE_STATE - init card in spi mode if CS low */
uint8_t const CMD0 = 0X00;
/** SEND_IF_COND - verify SD Memory Card interface operating condition.*/
uint8_t const CMD8 = 0X08;
/** SEND_CSD - read the Card Specific Data (CSD register) */
uint8_t const CMD9 = 0X09;
/** SEND_CID - read the card identification information (CID register) */
uint8_t const CMD10 = 0X0A;
/** STOP_TRANSMISSION - end multiple block read sequence */
uint8_t const CMD12 = 0X0C;
/** SEND_STATUS - read the card status register */
uint8_t const CMD13 = 0X0D;
/** READ_SINGLE_BLOCK - read a single data block from the card */
uint8_t const CMD17 = 0X11;
/** READ_MULTIPLE_BLOCK - read a multiple data blocks from the card */
uint8_t const CMD18 = 0X12;
/** WRITE_BLOCK - write a single data block to the card */
uint8_t const CMD24 = 0X18;
/** WRITE_MULTIPLE_BLOCK - write blocks of data until a STOP_TRANSMISSION */
uint8_t const CMD25 = 0X19;
/** ERASE_WR_BLK_START - sets the address of the first block to be erased */
uint8_t const CMD32 = 0X20;
/** ERASE_WR_BLK_END - sets the address of the last block of the continuous
range to be erased*/
uint8_t const CMD33 = 0X21;
/** ERASE - erase all previously selected blocks */
uint8_t const CMD38 = 0X26;
/** APP_CMD - escape for application specific command */
uint8_t const CMD55 = 0X37;
/** READ_OCR - read the OCR register of a card */
uint8_t const CMD58 = 0X3A;
/** CRC_ON_OFF - enable or disable CRC checking */
uint8_t const CMD59 = 0X3B;
/** SET_WR_BLK_ERASE_COUNT - Set the number of write blocks to be
pre-erased before writing */
uint8_t const ACMD23 = 0X17;
/** SD_SEND_OP_COMD - Sends host capacity support information and
activates the card's initialization process */
uint8_t const ACMD41 = 0X29;
//------------------------------------------------------------------------------
/** status for card in the ready state */
uint8_t const R1_READY_STATE = 0X00;
/** status for card in the idle state */
uint8_t const R1_IDLE_STATE = 0X01;
/** status bit for illegal command */
uint8_t const R1_ILLEGAL_COMMAND = 0X04;
/** start data token for read or write single block*/
uint8_t const DATA_START_BLOCK = 0XFE;
/** stop token for write multiple blocks*/
uint8_t const STOP_TRAN_TOKEN = 0XFD;
/** start data token for write multiple blocks*/
uint8_t const WRITE_MULTIPLE_TOKEN = 0XFC;
/** mask for data response tokens after a write block operation */
uint8_t const DATA_RES_MASK = 0X1F;
/** write data accepted token */
uint8_t const DATA_RES_ACCEPTED = 0X05;
//------------------------------------------------------------------------------
/** Card IDentification (CID) register */
typedef struct CID {
// byte 0
/** Manufacturer ID */
unsigned char mid;
// byte 1-2
/** OEM/Application ID */
char oid[2];
// byte 3-7
/** Product name */
char pnm[5];
// byte 8
/** Product revision least significant digit */
unsigned char prv_m : 4;
/** Product revision most significant digit */
unsigned char prv_n : 4;
// byte 9-12
/** Product serial number */
uint32_t psn;
// byte 13
/** Manufacturing date year low digit */
unsigned char mdt_year_high : 4;
/** not used */
unsigned char reserved : 4;
// byte 14
/** Manufacturing date month */
unsigned char mdt_month : 4;
/** Manufacturing date year low digit */
unsigned char mdt_year_low :4;
// byte 15
/** not used always 1 */
unsigned char always1 : 1;
/** CRC7 checksum */
unsigned char crc : 7;
}__attribute__((packed)) cid_t;
//------------------------------------------------------------------------------
/** CSD for version 1.00 cards */
typedef struct CSDV1 {
// byte 0
unsigned char reserved1 : 6;
unsigned char csd_ver : 2;
// byte 1
unsigned char taac;
// byte 2
unsigned char nsac;
// byte 3
unsigned char tran_speed;
// byte 4
unsigned char ccc_high;
// byte 5
unsigned char read_bl_len : 4;
unsigned char ccc_low : 4;
// byte 6
unsigned char c_size_high : 2;
unsigned char reserved2 : 2;
unsigned char dsr_imp : 1;
unsigned char read_blk_misalign :1;
unsigned char write_blk_misalign : 1;
unsigned char read_bl_partial : 1;
// byte 7
unsigned char c_size_mid;
// byte 8
unsigned char vdd_r_curr_max : 3;
unsigned char vdd_r_curr_min : 3;
unsigned char c_size_low :2;
// byte 9
unsigned char c_size_mult_high : 2;
unsigned char vdd_w_cur_max : 3;
unsigned char vdd_w_curr_min : 3;
// byte 10
unsigned char sector_size_high : 6;
unsigned char erase_blk_en : 1;
unsigned char c_size_mult_low : 1;
// byte 11
unsigned char wp_grp_size : 7;
unsigned char sector_size_low : 1;
// byte 12
unsigned char write_bl_len_high : 2;
unsigned char r2w_factor : 3;
unsigned char reserved3 : 2;
unsigned char wp_grp_enable : 1;
// byte 13
unsigned char reserved4 : 5;
unsigned char write_partial : 1;
unsigned char write_bl_len_low : 2;
// byte 14
unsigned char reserved5: 2;
unsigned char file_format : 2;
unsigned char tmp_write_protect : 1;
unsigned char perm_write_protect : 1;
unsigned char copy : 1;
/** Indicates the file format on the card */
unsigned char file_format_grp : 1;
// byte 15
unsigned char always1 : 1;
unsigned char crc : 7;
}__attribute__((packed)) csd1_t;
//------------------------------------------------------------------------------
/** CSD for version 2.00 cards */
typedef struct CSDV2 {
// byte 0
unsigned char reserved1 : 6;
unsigned char csd_ver : 2;
// byte 1
/** fixed to 0X0E */
unsigned char taac;
// byte 2
/** fixed to 0 */
unsigned char nsac;
// byte 3
unsigned char tran_speed;
// byte 4
unsigned char ccc_high;
// byte 5
/** This field is fixed to 9h, which indicates READ_BL_LEN=512 Byte */
unsigned char read_bl_len : 4;
unsigned char ccc_low : 4;
// byte 6
/** not used */
unsigned char reserved2 : 4;
unsigned char dsr_imp : 1;
/** fixed to 0 */
unsigned char read_blk_misalign :1;
/** fixed to 0 */
unsigned char write_blk_misalign : 1;
/** fixed to 0 - no partial read */
unsigned char read_bl_partial : 1;
// byte 7
/** high part of card size */
unsigned char c_size_high : 6;
/** not used */
unsigned char reserved3 : 2;
// byte 8
/** middle part of card size */
unsigned char c_size_mid;
// byte 9
/** low part of card size */
unsigned char c_size_low;
// byte 10
/** sector size is fixed at 64 KB */
unsigned char sector_size_high : 6;
/** fixed to 1 - erase single is supported */
unsigned char erase_blk_en : 1;
/** not used */
unsigned char reserved4 : 1;
// byte 11
unsigned char wp_grp_size : 7;
/** sector size is fixed at 64 KB */
unsigned char sector_size_low : 1;
// byte 12
/** write_bl_len fixed for 512 byte blocks */
unsigned char write_bl_len_high : 2;
/** fixed value of 2 */
unsigned char r2w_factor : 3;
/** not used */
unsigned char reserved5 : 2;
/** fixed value of 0 - no write protect groups */
unsigned char wp_grp_enable : 1;
// byte 13
unsigned char reserved6 : 5;
/** always zero - no partial block read*/
unsigned char write_partial : 1;
/** write_bl_len fixed for 512 byte blocks */
unsigned char write_bl_len_low : 2;
// byte 14
unsigned char reserved7: 2;
/** Do not use always 0 */
unsigned char file_format : 2;
unsigned char tmp_write_protect : 1;
unsigned char perm_write_protect : 1;
unsigned char copy : 1;
/** Do not use always 0 */
unsigned char file_format_grp : 1;
// byte 15
/** not used always 1 */
unsigned char always1 : 1;
/** checksum */
unsigned char crc : 7;
}__attribute__((packed)) csd2_t;
//------------------------------------------------------------------------------
/** union of old and new style CSD register */
union csd_t {
csd1_t v1;
csd2_t v2;
};
#endif // SdInfo_h

View file

@ -0,0 +1,151 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#include <SdFat.h>
//==============================================================================
/// @cond SHOW_PROTECTED
int16_t SdStreamBase::getch() {
uint8_t c;
int8_t s = read(&c, 1);
if (s != 1) {
if (s < 0) {
setstate(badbit);
} else {
setstate(eofbit);
}
return -1;
}
if (c != '\r' || (getmode() & ios::binary)) return c;
s = read(&c, 1);
if (s == 1 && c == '\n') return c;
if (s == 1) seekCur(-1);
return '\r';
}
//------------------------------------------------------------------------------
void SdStreamBase::open(const char* path, ios::openmode mode) {
uint8_t flags;
switch (mode & (app | in | out | trunc)) {
case app | in:
case app | in | out:
flags = O_RDWR | O_APPEND | O_CREAT;
break;
case app:
case app | out:
flags = O_WRITE | O_APPEND | O_CREAT;
break;
case in:
flags = O_READ;
break;
case in | out:
flags = O_RDWR;
break;
case in | out | trunc:
flags = O_RDWR | O_TRUNC | O_CREAT;
break;
case out:
case out | trunc:
flags = O_WRITE | O_TRUNC | O_CREAT;
break;
default:
goto fail;
}
if (mode & ios::ate) flags |= O_AT_END;
if (!SdBaseFile::open(path, flags)) goto fail;
setmode(mode);
clear();
return;
fail:
SdBaseFile::close();
setstate(failbit);
return;
}
//------------------------------------------------------------------------------
void SdStreamBase::putch(char c) {
if (c == '\n' && !(getmode() & ios::binary)) {
write('\r');
}
write(c);
if (writeError) setstate(badbit);
}
//------------------------------------------------------------------------------
void SdStreamBase::putstr(const char* str) {
size_t n = 0;
while (1) {
char c = str[n];
if (c == '\0' || (c == '\n' && !(getmode() & ios::binary))) {
if (n > 0) write(str, n);
if (c == '\0') break;
write('\r');
str += n;
n = 0;
}
n++;
}
if (writeError) setstate(badbit);
}
//------------------------------------------------------------------------------
/** Internal do not use
* \param[in] off
* \param[in] way
*/
bool SdStreamBase::seekoff(off_type off, seekdir way) {
pos_type pos;
switch (way) {
case beg:
pos = off;
break;
case cur:
pos = curPosition() + off;
break;
case end:
pos = fileSize() + off;
break;
default:
return false;
}
return seekpos(pos);
}
//------------------------------------------------------------------------------
/** Internal do not use
* \param[in] pos
*/
bool SdStreamBase::seekpos(pos_type pos) {
return seekSet(pos);
}
//------------------------------------------------------------------------------
int SdStreamBase::write(const void* buf, size_t n) {
return SdBaseFile::write(buf, n);
}
//------------------------------------------------------------------------------
void SdStreamBase::write(char c) {
write(&c, 1);
}
/// @endcond

View file

@ -0,0 +1,263 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef SdStream_h
#define SdStream_h
/**
* \file
* \brief \ref fstream, \ref ifstream, and \ref ofstream classes
*/
#include <SdBaseFile.h>
#include <iostream.h>
//==============================================================================
/**
* \class SdStreamBase
* \brief Base class for SD streams
*/
class SdStreamBase : protected SdBaseFile, virtual public ios {
protected:
/// @cond SHOW_PROTECTED
int16_t getch();
void putch(char c);
void putstr(const char *str);
void open(const char* path, ios::openmode mode);
/** Internal do not use
* \return mode
*/
ios::openmode getmode() {return mode_;}
/** Internal do not use
* \param[in] mode
*/
void setmode(ios::openmode mode) {mode_ = mode;}
bool seekoff(off_type off, seekdir way);
bool seekpos(pos_type pos);
int write(const void* buf, size_t n);
void write(char c);
/// @endcond
private:
ios::openmode mode_;
};
//==============================================================================
/**
* \class fstream
* \brief SD file input/output stream.
*/
class fstream : public iostream, SdStreamBase {
public:
using iostream::peek;
fstream() {}
/** Constructor with open
*
* \param[in] path path to open
* \param[in] mode open mode
*/
explicit fstream(const char* path, openmode mode = in | out) {
open(path, mode);
}
#if DESTRUCTOR_CLOSES_FILE
~fstream() {}
#endif // DESTRUCTOR_CLOSES_FILE
/** Clear state and writeError
* \param[in] state new state for stream
*/
void clear(iostate state = goodbit) {
ios::clear(state);
SdBaseFile::writeError = false;
}
/** Close a file and force cached data and directory information
* to be written to the storage device.
*/
void close() {SdBaseFile::close();}
/** Open a fstream
* \param[in] path file to open
* \param[in] mode open mode
*
* Valid open modes are (at end, ios::ate, and/or ios::binary may be added):
*
* ios::in - Open file for reading.
*
* ios::out or ios::out | ios::trunc - Truncate to 0 length, if existent,
* or create a file for writing only.
*
* ios::app or ios::out | ios::app - Append; open or create file for
* writing at end-of-file.
*
* ios::in | ios::out - Open file for update (reading and writing).
*
* ios::in | ios::out | ios::trunc - Truncate to zero length, if existent,
* or create file for update.
*
* ios::in | ios::app or ios::in | ios::out | ios::app - Append; open or
* create text file for update, writing at end of file.
*/
void open(const char* path, openmode mode = in | out) {
SdStreamBase::open(path, mode);
}
/** \return True if stream is open else false. */
bool is_open () {return SdBaseFile::isOpen();}
protected:
/// @cond SHOW_PROTECTED
/** Internal - do not use
* \return
*/
int16_t getch() {return SdStreamBase::getch();}
/** Internal - do not use
* \param[out] pos
*/
void getpos(FatPos_t* pos) {SdBaseFile::getpos(pos);}
/** Internal - do not use
* \param[in] c
*/
void putch(char c) {SdStreamBase::putch(c);}
/** Internal - do not use
* \param[in] str
*/
void putstr(const char *str) {SdStreamBase::putstr(str);}
/** Internal - do not use
* \param[in] pos
*/
bool seekoff(off_type off, seekdir way) {
return SdStreamBase::seekoff(off, way);
}
bool seekpos(pos_type pos) {return SdStreamBase::seekpos(pos);}
void setpos(FatPos_t* pos) {SdBaseFile::setpos(pos);}
bool sync() {return SdStreamBase::sync();}
pos_type tellpos() {return SdStreamBase::curPosition();}
/// @endcond
};
//==============================================================================
/**
* \class ifstream
* \brief SD file input stream.
*/
class ifstream : public istream, SdStreamBase {
public:
using istream::peek;
ifstream() {}
/** Constructor with open
* \param[in] path file to open
* \param[in] mode open mode
*/
explicit ifstream(const char* path, openmode mode = in) {
open(path, mode);
}
#if DESTRUCTOR_CLOSES_FILE
~ifstream() {}
#endif // DESTRUCTOR_CLOSES_FILE
/** Close a file and force cached data and directory information
* to be written to the storage device.
*/
void close() {SdBaseFile::close();}
/** \return True if stream is open else false. */
bool is_open() {return SdBaseFile::isOpen();}
/** Open an ifstream
* \param[in] path file to open
* \param[in] mode open mode
*
* \a mode See fstream::open() for valid modes.
*/
void open(const char* path, openmode mode = in) {
SdStreamBase::open(path, mode | in);
}
protected:
/// @cond SHOW_PROTECTED
/** Internal - do not use
* \return
*/
int16_t getch() {return SdStreamBase::getch();}
/** Internal - do not use
* \param[out] pos
*/
void getpos(FatPos_t* pos) {SdBaseFile::getpos(pos);}
/** Internal - do not use
* \param[in] pos
*/
bool seekoff(off_type off, seekdir way) {
return SdStreamBase::seekoff(off, way);
}
bool seekpos(pos_type pos) {return SdStreamBase::seekpos(pos);}
void setpos(FatPos_t* pos) {SdBaseFile::setpos(pos);}
pos_type tellpos() {return SdStreamBase::curPosition();}
/// @endcond
};
//==============================================================================
/**
* \class ofstream
* \brief SD card output stream.
*/
class ofstream : public ostream, SdStreamBase {
public:
ofstream() {}
/** Constructor with open
* \param[in] path file to open
* \param[in] mode open mode
*/
explicit ofstream(const char* path, ios::openmode mode = out) {
open(path, mode);
}
#if DESTRUCTOR_CLOSES_FILE
~ofstream() {}
#endif // DESTRUCTOR_CLOSES_FILE
/** Clear state and writeError
* \param[in] state new state for stream
*/
void clear(iostate state = goodbit) {
ios::clear(state);
SdBaseFile::writeError = false;
}
/** Close a file and force cached data and directory information
* to be written to the storage device.
*/
void close() {SdBaseFile::close();}
/** Open an ofstream
* \param[in] path file to open
* \param[in] mode open mode
*
* \a mode See fstream::open() for valid modes.
*/
void open(const char* path, openmode mode = out) {
SdStreamBase::open(path, mode | out);
}
/** \return True if stream is open else false. */
bool is_open() {return SdBaseFile::isOpen();}
protected:
/// @cond SHOW_PROTECTED
/**
* Internal do not use
* \param[in] c
*/
void putch(char c) {SdStreamBase::putch(c);}
void putstr(const char* str) {SdStreamBase::putstr(str);}
bool seekoff(off_type off, seekdir way) {
return SdStreamBase::seekoff(off, way);
}
bool seekpos(pos_type pos) {return SdStreamBase::seekpos(pos);}
/**
* Internal do not use
* \param[in] b
*/
bool sync() {return SdStreamBase::sync();}
pos_type tellpos() {return SdStreamBase::curPosition();}
/// @endcond
};
//------------------------------------------------------------------------------
#endif // SdStream_h

View file

@ -0,0 +1,599 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#include <SdVolume.h>
// macro for debug
#define DBG_FAIL_MACRO // Serial.print(__FILE__);Serial.println(__LINE__)
//------------------------------------------------------------------------------
#if !USE_MULTIPLE_CARDS
// raw block cache
cache_t SdVolume::cacheBuffer_; // 512 byte cache for Sd2Card
uint32_t SdVolume::cacheBlockNumber_; // current block number
uint8_t SdVolume::cacheStatus_; // status of cache block
uint32_t SdVolume::cacheFatOffset_; // offset for mirrored FAT
#if USE_SEPARATE_FAT_CACHE
cache_t SdVolume::cacheFatBuffer_; // 512 byte cache for FAT
uint32_t SdVolume::cacheFatBlockNumber_; // current Fat block number
uint8_t SdVolume::cacheFatStatus_; // status of cache Fatblock
#endif // USE_SEPARATE_FAT_CACHE
Sd2Card* SdVolume::sdCard_; // pointer to SD card object
#endif // USE_MULTIPLE_CARDS
//------------------------------------------------------------------------------
// find a contiguous group of clusters
bool SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) {
// start of group
uint32_t bgnCluster;
// end of group
uint32_t endCluster;
// last cluster of FAT
uint32_t fatEnd = clusterCount_ + 1;
// flag to save place to start next search
bool setStart;
// set search start cluster
if (*curCluster) {
// try to make file contiguous
bgnCluster = *curCluster + 1;
// don't save new start location
setStart = false;
} else {
// start at likely place for free cluster
bgnCluster = allocSearchStart_;
// save next search start if one cluster
setStart = count == 1;
}
// end of group
endCluster = bgnCluster;
// search the FAT for free clusters
for (uint32_t n = 0;; n++, endCluster++) {
// can't find space checked all clusters
if (n >= clusterCount_) {
DBG_FAIL_MACRO;
goto fail;
}
// past end - start from beginning of FAT
if (endCluster > fatEnd) {
bgnCluster = endCluster = 2;
}
uint32_t f;
if (!fatGet(endCluster, &f)) {
DBG_FAIL_MACRO;
goto fail;
}
if (f != 0) {
// cluster in use try next cluster as bgnCluster
bgnCluster = endCluster + 1;
} else if ((endCluster - bgnCluster + 1) == count) {
// done - found space
break;
}
}
// mark end of chain
if (!fatPutEOC(endCluster)) {
DBG_FAIL_MACRO;
goto fail;
}
// link clusters
while (endCluster > bgnCluster) {
if (!fatPut(endCluster - 1, endCluster)) {
DBG_FAIL_MACRO;
goto fail;
}
endCluster--;
}
if (*curCluster != 0) {
// connect chains
if (!fatPut(*curCluster, bgnCluster)) {
DBG_FAIL_MACRO;
goto fail;
}
}
// return first cluster number to caller
*curCluster = bgnCluster;
// remember possible next free cluster
if (setStart) allocSearchStart_ = bgnCluster + 1;
return true;
fail:
return false;
}
//==============================================================================
// cache functions
#if USE_SEPARATE_FAT_CACHE
//------------------------------------------------------------------------------
cache_t* SdVolume::cacheFetch(uint32_t blockNumber, uint8_t options) {
return cacheFetchData(blockNumber, options);
}
//------------------------------------------------------------------------------
cache_t* SdVolume::cacheFetchData(uint32_t blockNumber, uint8_t options) {
if (cacheBlockNumber_ != blockNumber) {
if (!cacheWriteData()) {
DBG_FAIL_MACRO;
goto fail;
}
if (!(options & CACHE_OPTION_NO_READ)) {
if (!sdCard_->readBlock(blockNumber, cacheBuffer_.data)) {
DBG_FAIL_MACRO;
goto fail;
}
}
cacheStatus_ = 0;
cacheBlockNumber_ = blockNumber;
}
cacheStatus_ |= options & CACHE_STATUS_MASK;
return &cacheBuffer_;
fail:
return 0;
}
//------------------------------------------------------------------------------
cache_t* SdVolume::cacheFetchFat(uint32_t blockNumber, uint8_t options) {
if (cacheFatBlockNumber_ != blockNumber) {
if (!cacheWriteFat()) {
DBG_FAIL_MACRO;
goto fail;
}
if (!(options & CACHE_OPTION_NO_READ)) {
if (!sdCard_->readBlock(blockNumber, cacheFatBuffer_.data)) {
DBG_FAIL_MACRO;
goto fail;
}
}
cacheFatStatus_ = 0;
cacheFatBlockNumber_ = blockNumber;
}
cacheFatStatus_ |= options & CACHE_STATUS_MASK;
return &cacheFatBuffer_;
fail:
return 0;
}
//------------------------------------------------------------------------------
bool SdVolume::cacheSync() {
return cacheWriteData() && cacheWriteFat();
}
//------------------------------------------------------------------------------
bool SdVolume::cacheWriteData() {
if (cacheStatus_ & CACHE_STATUS_DIRTY) {
if (!sdCard_->writeBlock(cacheBlockNumber_, cacheBuffer_.data)) {
DBG_FAIL_MACRO;
goto fail;
}
cacheStatus_ &= ~CACHE_STATUS_DIRTY;
}
return true;
fail:
return false;
}
//------------------------------------------------------------------------------
bool SdVolume::cacheWriteFat() {
if (cacheFatStatus_ & CACHE_STATUS_DIRTY) {
if (!sdCard_->writeBlock(cacheFatBlockNumber_, cacheFatBuffer_.data)) {
DBG_FAIL_MACRO;
goto fail;
}
// mirror second FAT
if (cacheFatOffset_) {
uint32_t lbn = cacheFatBlockNumber_ + cacheFatOffset_;
if (!sdCard_->writeBlock(lbn, cacheFatBuffer_.data)) {
DBG_FAIL_MACRO;
goto fail;
}
}
cacheFatStatus_ &= ~CACHE_STATUS_DIRTY;
}
return true;
fail:
return false;
}
#else // USE_SEPARATE_FAT_CACHE
//------------------------------------------------------------------------------
cache_t* SdVolume::cacheFetch(uint32_t blockNumber, uint8_t options) {
if (cacheBlockNumber_ != blockNumber) {
if (!cacheSync()) {
DBG_FAIL_MACRO;
goto fail;
}
if (!(options & CACHE_OPTION_NO_READ)) {
if (!sdCard_->readBlock(blockNumber, cacheBuffer_.data)) {
DBG_FAIL_MACRO;
goto fail;
}
}
cacheStatus_ = 0;
cacheBlockNumber_ = blockNumber;
}
cacheStatus_ |= options & CACHE_STATUS_MASK;
return &cacheBuffer_;
fail:
return 0;
}
//------------------------------------------------------------------------------
cache_t* SdVolume::cacheFetchFat(uint32_t blockNumber, uint8_t options) {
return cacheFetch(blockNumber, options | CACHE_STATUS_FAT_BLOCK);
}
//------------------------------------------------------------------------------
bool SdVolume::cacheSync() {
if (cacheStatus_ & CACHE_STATUS_DIRTY) {
if (!sdCard_->writeBlock(cacheBlockNumber_, cacheBuffer_.data)) {
DBG_FAIL_MACRO;
goto fail;
}
// mirror second FAT
if ((cacheStatus_ & CACHE_STATUS_FAT_BLOCK) && cacheFatOffset_) {
uint32_t lbn = cacheBlockNumber_ + cacheFatOffset_;
if (!sdCard_->writeBlock(lbn, cacheBuffer_.data)) {
DBG_FAIL_MACRO;
goto fail;
}
}
cacheStatus_ &= ~CACHE_STATUS_DIRTY;
}
return true;
fail:
return false;
}
//------------------------------------------------------------------------------
bool SdVolume::cacheWriteData() {
return cacheSync();
}
#endif // USE_SEPARATE_FAT_CACHE
//------------------------------------------------------------------------------
void SdVolume::cacheInvalidate() {
cacheBlockNumber_ = 0XFFFFFFFF;
cacheStatus_ = 0;
}
//==============================================================================
//------------------------------------------------------------------------------
uint32_t SdVolume::clusterStartBlock(uint32_t cluster) const {
return dataStartBlock_ + ((cluster - 2)*blocksPerCluster_);
}
//------------------------------------------------------------------------------
// Fetch a FAT entry
bool SdVolume::fatGet(uint32_t cluster, uint32_t* value) {
uint32_t lba;
cache_t* pc;
// error if reserved cluster of beyond FAT
if (cluster < 2 || cluster > (clusterCount_ + 1)) {
DBG_FAIL_MACRO;
goto fail;
}
if (FAT12_SUPPORT && fatType_ == 12) {
uint16_t index = cluster;
index += index >> 1;
lba = fatStartBlock_ + (index >> 9);
pc = cacheFetchFat(lba, CACHE_FOR_READ);
if (!pc) {
DBG_FAIL_MACRO;
goto fail;
}
index &= 0X1FF;
uint16_t tmp = pc->data[index];
index++;
if (index == 512) {
pc = cacheFetchFat(lba + 1, CACHE_FOR_READ);
if (!pc) {
DBG_FAIL_MACRO;
goto fail;
}
index = 0;
}
tmp |= pc->data[index] << 8;
*value = cluster & 1 ? tmp >> 4 : tmp & 0XFFF;
return true;
}
if (fatType_ == 16) {
lba = fatStartBlock_ + (cluster >> 8);
} else if (fatType_ == 32) {
lba = fatStartBlock_ + (cluster >> 7);
} else {
DBG_FAIL_MACRO;
goto fail;
}
pc = cacheFetchFat(lba, CACHE_FOR_READ);
if (!pc) {
DBG_FAIL_MACRO;
goto fail;
}
if (fatType_ == 16) {
*value = pc->fat16[cluster & 0XFF];
} else {
*value = pc->fat32[cluster & 0X7F] & FAT32MASK;
}
return true;
fail:
return false;
}
//------------------------------------------------------------------------------
// Store a FAT entry
bool SdVolume::fatPut(uint32_t cluster, uint32_t value) {
uint32_t lba;
cache_t* pc;
// error if reserved cluster of beyond FAT
if (cluster < 2 || cluster > (clusterCount_ + 1)) {
DBG_FAIL_MACRO;
goto fail;
}
if (FAT12_SUPPORT && fatType_ == 12) {
uint16_t index = cluster;
index += index >> 1;
lba = fatStartBlock_ + (index >> 9);
pc = cacheFetchFat(lba, CACHE_FOR_WRITE);
if (!pc) {
DBG_FAIL_MACRO;
goto fail;
}
index &= 0X1FF;
uint8_t tmp = value;
if (cluster & 1) {
tmp = (pc->data[index] & 0XF) | tmp << 4;
}
pc->data[index] = tmp;
index++;
if (index == 512) {
lba++;
index = 0;
pc = cacheFetchFat(lba, CACHE_FOR_WRITE);
if (!pc) {
DBG_FAIL_MACRO;
goto fail;
}
}
tmp = value >> 4;
if (!(cluster & 1)) {
tmp = ((pc->data[index] & 0XF0)) | tmp >> 4;
}
pc->data[index] = tmp;
return true;
}
if (fatType_ == 16) {
lba = fatStartBlock_ + (cluster >> 8);
} else if (fatType_ == 32) {
lba = fatStartBlock_ + (cluster >> 7);
} else {
DBG_FAIL_MACRO;
goto fail;
}
pc = cacheFetchFat(lba, CACHE_FOR_WRITE);
if (!pc) {
DBG_FAIL_MACRO;
goto fail;
}
// store entry
if (fatType_ == 16) {
pc->fat16[cluster & 0XFF] = value;
} else {
pc->fat32[cluster & 0X7F] = value;
}
return true;
fail:
return false;
}
//------------------------------------------------------------------------------
// free a cluster chain
bool SdVolume::freeChain(uint32_t cluster) {
uint32_t next;
// clear free cluster location
allocSearchStart_ = 2;
do {
if (!fatGet(cluster, &next)) {
DBG_FAIL_MACRO;
goto fail;
}
// free cluster
if (!fatPut(cluster, 0)) {
DBG_FAIL_MACRO;
goto fail;
}
cluster = next;
} while (!isEOC(cluster));
return true;
fail:
return false;
}
//------------------------------------------------------------------------------
/** Volume free space in clusters.
*
* \return Count of free clusters for success or -1 if an error occurs.
*/
int32_t SdVolume::freeClusterCount() {
uint32_t free = 0;
uint32_t lba;
uint32_t todo = clusterCount_ + 2;
uint16_t n;
if (FAT12_SUPPORT && fatType_ == 12) {
for (unsigned i = 2; i < todo; i++) {
uint32_t c;
if (!fatGet(i, &c)) {
DBG_FAIL_MACRO;
goto fail;
}
if (c == 0) free++;
}
} else if (fatType_ == 16 || fatType_ == 32) {
lba = fatStartBlock_;
while (todo) {
cache_t* pc = cacheFetchFat(lba++, CACHE_FOR_READ);
if (!pc) {
DBG_FAIL_MACRO;
goto fail;
}
n = fatType_ == 16 ? 256 : 128;
if (todo < n) n = todo;
if (fatType_ == 16) {
for (uint16_t i = 0; i < n; i++) {
if (pc->fat16[i] == 0) free++;
}
} else {
for (uint16_t i = 0; i < n; i++) {
if (pc->fat32[i] == 0) free++;
}
}
todo -= n;
}
} else {
// invalid FAT type
DBG_FAIL_MACRO;
goto fail;
}
return free;
fail:
return -1;
}
//------------------------------------------------------------------------------
/** Initialize a FAT volume.
*
* \param[in] dev The SD card where the volume is located.
*
* \param[in] part The partition to be used. Legal values for \a part are
* 1-4 to use the corresponding partition on a device formatted with
* a MBR, Master Boot Record, or zero if the device is formatted as
* a super floppy with the FAT boot sector in block zero.
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure. Reasons for
* failure include not finding a valid partition, not finding a valid
* FAT file system in the specified partition or an I/O error.
*/
bool SdVolume::init(Sd2Card* dev, uint8_t part) {
uint32_t totalBlocks;
uint32_t volumeStartBlock = 0;
fat32_boot_t* fbs;
cache_t* pc;
sdCard_ = dev;
fatType_ = 0;
allocSearchStart_ = 2;
cacheStatus_ = 0; // cacheSync() will write block if true
cacheBlockNumber_ = 0XFFFFFFFF;
cacheFatOffset_ = 0;
#if USE_SERARATEFAT_CACHE
cacheFatStatus_ = 0; // cacheSync() will write block if true
cacheFatBlockNumber_ = 0XFFFFFFFF;
#endif // USE_SERARATEFAT_CACHE
// if part == 0 assume super floppy with FAT boot sector in block zero
// if part > 0 assume mbr volume with partition table
if (part) {
if (part > 4) {
DBG_FAIL_MACRO;
goto fail;
}
pc = cacheFetch(volumeStartBlock, CACHE_FOR_READ);
if (!pc) {
DBG_FAIL_MACRO;
goto fail;
}
part_t* p = &pc->mbr.part[part-1];
if ((p->boot & 0X7F) !=0 ||
p->totalSectors < 100 ||
p->firstSector == 0) {
// not a valid partition
DBG_FAIL_MACRO;
goto fail;
}
volumeStartBlock = p->firstSector;
}
pc = cacheFetch(volumeStartBlock, CACHE_FOR_READ);
if (!pc) {
DBG_FAIL_MACRO;
goto fail;
}
fbs = &(pc->fbs32);
if (fbs->bytesPerSector != 512 ||
fbs->fatCount == 0 ||
fbs->reservedSectorCount == 0 ||
fbs->sectorsPerCluster == 0) {
// not valid FAT volume
DBG_FAIL_MACRO;
goto fail;
}
fatCount_ = fbs->fatCount;
blocksPerCluster_ = fbs->sectorsPerCluster;
// determine shift that is same as multiply by blocksPerCluster_
clusterSizeShift_ = 0;
while (blocksPerCluster_ != (1 << clusterSizeShift_)) {
// error if not power of 2
if (clusterSizeShift_++ > 7) {
DBG_FAIL_MACRO;
goto fail;
}
}
blocksPerFat_ = fbs->sectorsPerFat16 ?
fbs->sectorsPerFat16 : fbs->sectorsPerFat32;
if (fatCount_ > 0) cacheFatOffset_ = blocksPerFat_;
fatStartBlock_ = volumeStartBlock + fbs->reservedSectorCount;
// count for FAT16 zero for FAT32
rootDirEntryCount_ = fbs->rootDirEntryCount;
// directory start for FAT16 dataStart for FAT32
rootDirStart_ = fatStartBlock_ + fbs->fatCount * blocksPerFat_;
// data start for FAT16 and FAT32
dataStartBlock_ = rootDirStart_ + ((32 * fbs->rootDirEntryCount + 511)/512);
// total blocks for FAT16 or FAT32
totalBlocks = fbs->totalSectors16 ?
fbs->totalSectors16 : fbs->totalSectors32;
// total data blocks
clusterCount_ = totalBlocks - (dataStartBlock_ - volumeStartBlock);
// divide by cluster size to get cluster count
clusterCount_ >>= clusterSizeShift_;
// FAT type is determined by cluster count
if (clusterCount_ < 4085) {
fatType_ = 12;
if (!FAT12_SUPPORT) {
DBG_FAIL_MACRO;
goto fail;
}
} else if (clusterCount_ < 65525) {
fatType_ = 16;
} else {
rootDirStart_ = fbs->fat32RootCluster;
fatType_ = 32;
}
return true;
fail:
return false;
}

View file

@ -0,0 +1,234 @@
/* Arduino SdFat Library
* Copyright (C) 2012 by William Greiman
*
* This file is part of the Arduino SdFat Library
*
* This Library is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This Library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with the Arduino SdFat Library. If not, see
* <http://www.gnu.org/licenses/>.
*/
#ifndef SdVolume_h
#define SdVolume_h
/**
* \file
* \brief SdVolume class
*/
#include <SdFatConfig.h>
#include <Sd2Card.h>
#include <SdFatStructs.h>
//==============================================================================
// SdVolume class
/**
* \brief Cache for an SD data block
*/
union cache_t {
/** Used to access cached file data blocks. */
uint8_t data[512];
/** Used to access cached FAT16 entries. */
uint16_t fat16[256];
/** Used to access cached FAT32 entries. */
uint32_t fat32[128];
/** Used to access cached directory entries. */
dir_t dir[16];
/** Used to access a cached Master Boot Record. */
mbr_t mbr;
/** Used to access to a cached FAT boot sector. */
fat_boot_t fbs;
/** Used to access to a cached FAT32 boot sector. */
fat32_boot_t fbs32;
/** Used to access to a cached FAT32 FSINFO sector. */
fat32_fsinfo_t fsinfo;
};
//------------------------------------------------------------------------------
/**
* \class SdVolume
* \brief Access FAT16 and FAT32 volumes on SD and SDHC cards.
*/
class SdVolume {
public:
/** Create an instance of SdVolume */
SdVolume() : fatType_(0) {}
/** Clear the cache and returns a pointer to the cache. Used by the WaveRP
* recorder to do raw write to the SD card. Not for normal apps.
* \return A pointer to the cache buffer or zero if an error occurs.
*/
cache_t* cacheClear() {
if (!cacheSync()) return 0;
cacheBlockNumber_ = 0XFFFFFFFF;
return &cacheBuffer_;
}
/** Initialize a FAT volume. Try partition one first then try super
* floppy format.
*
* \param[in] dev The Sd2Card where the volume is located.
*
* \return The value one, true, is returned for success and
* the value zero, false, is returned for failure. Reasons for
* failure include not finding a valid partition, not finding a valid
* FAT file system or an I/O error.
*/
bool init(Sd2Card* dev) { return init(dev, 1) ? true : init(dev, 0);}
bool init(Sd2Card* dev, uint8_t part);
// inline functions that return volume info
/** \return The volume's cluster size in blocks. */
uint8_t blocksPerCluster() const {return blocksPerCluster_;}
/** \return The number of blocks in one FAT. */
uint32_t blocksPerFat() const {return blocksPerFat_;}
/** \return The total number of clusters in the volume. */
uint32_t clusterCount() const {return clusterCount_;}
/** \return The shift count required to multiply by blocksPerCluster. */
uint8_t clusterSizeShift() const {return clusterSizeShift_;}
/** \return The logical block number for the start of file data. */
uint32_t dataStartBlock() const {return dataStartBlock_;}
/** \return The number of FAT structures on the volume. */
uint8_t fatCount() const {return fatCount_;}
/** \return The logical block number for the start of the first FAT. */
uint32_t fatStartBlock() const {return fatStartBlock_;}
/** \return The FAT type of the volume. Values are 12, 16 or 32. */
uint8_t fatType() const {return fatType_;}
int32_t freeClusterCount();
/** \return The number of entries in the root directory for FAT16 volumes. */
uint32_t rootDirEntryCount() const {return rootDirEntryCount_;}
/** \return The logical block number for the start of the root directory
on FAT16 volumes or the first cluster number on FAT32 volumes. */
uint32_t rootDirStart() const {return rootDirStart_;}
/** Sd2Card object for this volume
* \return pointer to Sd2Card object.
*/
Sd2Card* sdCard() {return sdCard_;}
/** Debug access to FAT table
*
* \param[in] n cluster number.
* \param[out] v value of entry
* \return true for success or false for failure
*/
bool dbgFat(uint32_t n, uint32_t* v) {return fatGet(n, v);}
//------------------------------------------------------------------------------
private:
// Allow SdBaseFile access to SdVolume private data.
friend class SdBaseFile;
//------------------------------------------------------------------------------
uint32_t allocSearchStart_; // start cluster for alloc search
uint8_t blocksPerCluster_; // cluster size in blocks
uint32_t blocksPerFat_; // FAT size in blocks
uint32_t clusterCount_; // clusters in one FAT
uint8_t clusterSizeShift_; // shift to convert cluster count to block count
uint32_t dataStartBlock_; // first data block number
uint8_t fatCount_; // number of FATs on volume
uint32_t fatStartBlock_; // start block for first FAT
uint8_t fatType_; // volume type (12, 16, OR 32)
uint16_t rootDirEntryCount_; // number of entries in FAT16 root dir
uint32_t rootDirStart_; // root start block for FAT16, cluster for FAT32
//------------------------------------------------------------------------------
// block caches
// use of static functions save a bit of flash - maybe not worth complexity
//
static const uint8_t CACHE_STATUS_DIRTY = 1;
static const uint8_t CACHE_STATUS_FAT_BLOCK = 2;
static const uint8_t CACHE_STATUS_MASK
= CACHE_STATUS_DIRTY | CACHE_STATUS_FAT_BLOCK;
static const uint8_t CACHE_OPTION_NO_READ = 4;
// value for option argument in cacheFetch to indicate read from cache
static uint8_t const CACHE_FOR_READ = 0;
// value for option argument in cacheFetch to indicate write to cache
static uint8_t const CACHE_FOR_WRITE = CACHE_STATUS_DIRTY;
// reserve cache block with no read
static uint8_t const CACHE_RESERVE_FOR_WRITE
= CACHE_STATUS_DIRTY | CACHE_OPTION_NO_READ;
#if USE_MULTIPLE_CARDS
cache_t cacheBuffer_; // 512 byte cache for device blocks
uint32_t cacheBlockNumber_; // Logical number of block in the cache
uint32_t cacheFatOffset_; // offset for mirrored FAT
Sd2Card* sdCard_; // Sd2Card object for cache
uint8_t cacheStatus_; // status of cache block
#if USE_SEPARATE_FAT_CACHE
cache_t cacheFatBuffer_; // 512 byte cache for FAT
uint32_t cacheFatBlockNumber_; // current Fat block number
uint8_t cacheFatStatus_; // status of cache Fatblock
#endif // USE_SEPARATE_FAT_CACHE
#else // USE_MULTIPLE_CARDS
static cache_t cacheBuffer_; // 512 byte cache for device blocks
static uint32_t cacheBlockNumber_; // Logical number of block in the cache
static uint32_t cacheFatOffset_; // offset for mirrored FAT
static uint8_t cacheStatus_; // status of cache block
#if USE_SEPARATE_FAT_CACHE
static cache_t cacheFatBuffer_; // 512 byte cache for FAT
static uint32_t cacheFatBlockNumber_; // current Fat block number
static uint8_t cacheFatStatus_; // status of cache Fatblock
#endif // USE_SEPARATE_FAT_CACHE
static Sd2Card* sdCard_; // Sd2Card object for cache
#endif // USE_MULTIPLE_CARDS
cache_t *cacheAddress() {return &cacheBuffer_;}
uint32_t cacheBlockNumber() {return cacheBlockNumber_;}
#if USE_MULTIPLE_CARDS
cache_t* cacheFetch(uint32_t blockNumber, uint8_t options);
cache_t* cacheFetchData(uint32_t blockNumber, uint8_t options);
cache_t* cacheFetchFat(uint32_t blockNumber, uint8_t options);
void cacheInvalidate();
bool cacheSync();
bool cacheWriteData();
bool cacheWriteFat();
#else // USE_MULTIPLE_CARDS
static cache_t* cacheFetch(uint32_t blockNumber, uint8_t options);
static cache_t* cacheFetchData(uint32_t blockNumber, uint8_t options);
static cache_t* cacheFetchFat(uint32_t blockNumber, uint8_t options);
static void cacheInvalidate();
static bool cacheSync();
static bool cacheWriteData();
static bool cacheWriteFat();
#endif // USE_MULTIPLE_CARDS
//------------------------------------------------------------------------------
bool allocContiguous(uint32_t count, uint32_t* curCluster);
uint8_t blockOfCluster(uint32_t position) const {
return (position >> 9) & (blocksPerCluster_ - 1);}
uint32_t clusterStartBlock(uint32_t cluster) const;
bool fatGet(uint32_t cluster, uint32_t* value);
bool fatPut(uint32_t cluster, uint32_t value);
bool fatPutEOC(uint32_t cluster) {
return fatPut(cluster, 0x0FFFFFFF);
}
bool freeChain(uint32_t cluster);
bool isEOC(uint32_t cluster) const {
if (FAT12_SUPPORT && fatType_ == 12) return cluster >= FAT12EOC_MIN;
if (fatType_ == 16) return cluster >= FAT16EOC_MIN;
return cluster >= FAT32EOC_MIN;
}
bool readBlock(uint32_t block, uint8_t* dst) {
return sdCard_->readBlock(block, dst);}
bool writeBlock(uint32_t block, const uint8_t* dst) {
return sdCard_->writeBlock(block, dst);
}
//------------------------------------------------------------------------------
// Deprecated functions - suppress cpplint warnings with NOLINT comment
#if ALLOW_DEPRECATED_FUNCTIONS && !defined(DOXYGEN)
public:
/** \deprecated Use: bool SdVolume::init(Sd2Card* dev);
* \param[in] dev The SD card where the volume is located.
* \return true for success or false for failure.
*/
bool init(Sd2Card& dev) {return init(&dev);} // NOLINT
/** \deprecated Use: bool SdVolume::init(Sd2Card* dev, uint8_t vol);
* \param[in] dev The SD card where the volume is located.
* \param[in] part The partition to be used.
* \return true for success or false for failure.
*/
bool init(Sd2Card& dev, uint8_t part) { // NOLINT
return init(&dev, part);
}
#endif // ALLOW_DEPRECATED_FUNCTIONS
};
#endif // SdVolume

Some files were not shown because too many files have changed in this diff Show more