mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
HAL_ChibiOS: use AP_Filesystem API
This commit is contained in:
parent
abe53e1c9e
commit
b867ef35c0
@ -19,7 +19,7 @@
|
||||
|
||||
#include "Storage.h"
|
||||
#include "hwdef/common/flash.h"
|
||||
#include "hwdef/common/posix.h"
|
||||
#include <AP_Filesystem/AP_Filesystem.h>
|
||||
#include "sdcard.h"
|
||||
|
||||
using namespace ChibiOS;
|
||||
@ -76,23 +76,23 @@ void Storage::_storage_open(void)
|
||||
// allow for fallback to microSD based storage
|
||||
sdcard_retry();
|
||||
|
||||
log_fd = open(HAL_STORAGE_FILE, O_RDWR|O_CREAT);
|
||||
log_fd = AP::FS().open(HAL_STORAGE_FILE, O_RDWR|O_CREAT);
|
||||
if (log_fd == -1) {
|
||||
hal.console->printf("open failed of " HAL_STORAGE_FILE "\n");
|
||||
return;
|
||||
}
|
||||
int ret = read(log_fd, _buffer, CH_STORAGE_SIZE);
|
||||
int ret = AP::FS().read(log_fd, _buffer, CH_STORAGE_SIZE);
|
||||
if (ret < 0) {
|
||||
hal.console->printf("read failed for " HAL_STORAGE_FILE "\n");
|
||||
close(log_fd);
|
||||
AP::FS().close(log_fd);
|
||||
log_fd = -1;
|
||||
return;
|
||||
}
|
||||
// pre-fill to full size
|
||||
if (lseek(log_fd, ret, SEEK_SET) != ret ||
|
||||
write(log_fd, &_buffer[ret], CH_STORAGE_SIZE-ret) != CH_STORAGE_SIZE-ret) {
|
||||
if (AP::FS().lseek(log_fd, ret, SEEK_SET) != ret ||
|
||||
AP::FS().write(log_fd, &_buffer[ret], CH_STORAGE_SIZE-ret) != CH_STORAGE_SIZE-ret) {
|
||||
hal.console->printf("setup failed for " HAL_STORAGE_FILE "\n");
|
||||
close(log_fd);
|
||||
AP::FS().close(log_fd);
|
||||
log_fd = -1;
|
||||
return;
|
||||
}
|
||||
@ -113,10 +113,10 @@ void Storage::_save_backup(void)
|
||||
#ifdef USE_POSIX
|
||||
// allow for fallback to microSD based storage
|
||||
sdcard_retry();
|
||||
int fd = open(HAL_STORAGE_BACKUP_FILE, O_WRONLY|O_CREAT|O_TRUNC);
|
||||
int fd = AP::FS().open(HAL_STORAGE_BACKUP_FILE, O_WRONLY|O_CREAT|O_TRUNC);
|
||||
if (fd != -1) {
|
||||
write(fd, _buffer, CH_STORAGE_SIZE);
|
||||
close(fd);
|
||||
AP::FS().write(fd, _buffer, CH_STORAGE_SIZE);
|
||||
AP::FS().close(fd);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
@ -194,13 +194,13 @@ void Storage::_timer_tick(void)
|
||||
#ifdef USE_POSIX
|
||||
if (using_filesystem && log_fd != -1) {
|
||||
uint32_t offset = CH_STORAGE_LINE_SIZE*i;
|
||||
if (lseek(log_fd, offset, SEEK_SET) != offset) {
|
||||
if (AP::FS().lseek(log_fd, offset, SEEK_SET) != offset) {
|
||||
return;
|
||||
}
|
||||
if (write(log_fd, &_buffer[offset], CH_STORAGE_LINE_SIZE) != CH_STORAGE_LINE_SIZE) {
|
||||
if (AP::FS().write(log_fd, &_buffer[offset], CH_STORAGE_LINE_SIZE) != CH_STORAGE_LINE_SIZE) {
|
||||
return;
|
||||
}
|
||||
if (fsync(log_fd) != 0) {
|
||||
if (AP::FS().fsync(log_fd) != 0) {
|
||||
return;
|
||||
}
|
||||
_dirty_mask.clear(i);
|
||||
|
@ -126,11 +126,6 @@ CSRC += $(HWDEF)/common/stubs.c \
|
||||
$(HWDEF)/common/bouncebuffer.c \
|
||||
$(HWDEF)/common/watchdog.c
|
||||
|
||||
ifeq ($(USE_FATFS),yes)
|
||||
CSRC += $(HWDEF)/common/posix.c
|
||||
endif
|
||||
|
||||
|
||||
# $(TESTSRC) \
|
||||
# test.c
|
||||
|
||||
|
File diff suppressed because it is too large
Load Diff
@ -1,346 +0,0 @@
|
||||
/**
|
||||
@file fatfs/posix.h
|
||||
|
||||
@brief POSIX wrapper for FatFS
|
||||
|
||||
@par Copyright © 2015 Mike Gore, GPL License
|
||||
@par You are free to use this code under the terms of GPL
|
||||
please retain a copy of this notice in any code you use it in.
|
||||
|
||||
This 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 software 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 this program. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#ifndef _POSIX_H_
|
||||
#define _POSIX_H_
|
||||
#include <board.h>
|
||||
#ifdef USE_POSIX
|
||||
#define POSIX
|
||||
#pragma GCC diagnostic ignored "-Wshadow"
|
||||
#include <stdint.h>
|
||||
#include <stddef.h>
|
||||
#include <ff.h>
|
||||
#include <stdarg.h>
|
||||
#include <time.h>
|
||||
#include <errno.h>
|
||||
|
||||
#define MAXLN 128
|
||||
#define ISSPACE " \t\n\r\f\v"
|
||||
|
||||
#define BUFSIZ 256
|
||||
|
||||
///@brief make sure we use our strerror_r function
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
///@brief POSIX stat structure
|
||||
///@see stat()
|
||||
///@see fstat()
|
||||
struct stat
|
||||
{
|
||||
dev_t st_dev; /*< ID of device containing file */
|
||||
ino_t st_ino; /*< inode number */
|
||||
mode_t st_mode; /*< protection */
|
||||
nlink_t st_nlink; /*< number of hard links */
|
||||
uid_t st_uid; /*< user ID of owner */
|
||||
gid_t st_gid; /*< group ID of owner */
|
||||
dev_t st_rdev; /*< device ID (if special file) */
|
||||
off_t st_size; /*< total size, in bytes */
|
||||
uint32_t st_blksize;/*< blocksize for filesystem I/O */
|
||||
uint32_t st_blocks; /*< number of 512B blocks allocated */
|
||||
time_t st_atime; /*< time of last access */
|
||||
time_t st_mtime; /*< time of last modification */
|
||||
time_t st_ctime; /*< time of last status change */
|
||||
};
|
||||
|
||||
///@brief POSIX utimbuf structure
|
||||
///@see utime()
|
||||
typedef struct utimbuf
|
||||
{
|
||||
time_t actime; /* access time */
|
||||
time_t modtime; /* modification time */
|
||||
} utime_t;
|
||||
|
||||
#if FF_USE_LFN != 0
|
||||
#define MAX_NAME_LEN FF_MAX_LFN
|
||||
#else
|
||||
#define MAX_NAME_LEN 13
|
||||
#endif
|
||||
|
||||
struct dirent {
|
||||
#if 0 // unsupported
|
||||
ino_t d_ino; /* inode number */
|
||||
off_t d_off; /* not an offset; see NOTES */
|
||||
unsigned short d_reclen; /* length of this record */
|
||||
unsigned char d_type; /* type of file; not supported
|
||||
by all filesystem types */
|
||||
#endif
|
||||
char d_name[MAX_NAME_LEN]; /* filename */
|
||||
};
|
||||
|
||||
typedef struct dirent dirent_t;
|
||||
|
||||
|
||||
///@brief POSIX lstat()
|
||||
///@see stat()
|
||||
#define lstat stat
|
||||
// =============================================
|
||||
///@brief FILE type structure
|
||||
struct __file {
|
||||
char *buf; /* buffer pointer */
|
||||
unsigned char unget; /* ungetc() buffer */
|
||||
uint8_t flags; /* flags, see below */
|
||||
#define __SRD 0x0001 /* OK to read */
|
||||
#define __SWR 0x0002 /* OK to write */
|
||||
#define __SSTR 0x0004 /* this is an sprintf/snprintf string */
|
||||
#define __SPGM 0x0008 /* fmt string is in progmem */
|
||||
#define __SERR 0x0010 /* found error */
|
||||
#define __SEOF 0x0020 /* found EOF */
|
||||
#define __SUNGET 0x040 /* ungetc() happened */
|
||||
#define __SMALLOC 0x80 /* handle is malloc()ed */
|
||||
#if 0
|
||||
/* possible future extensions, will require uint16_t flags */
|
||||
#define __SRW 0x0100 /* open for reading & writing */
|
||||
#define __SLBF 0x0200 /* line buffered */
|
||||
#define __SNBF 0x0400 /* unbuffered */
|
||||
#define __SMBF 0x0800 /* buf is from malloc */
|
||||
#endif
|
||||
int size; /* size of buffer */
|
||||
int len; /* characters read or written so far */
|
||||
int (*put)(char, struct __file *); /* write one char to device */
|
||||
int (*get)(struct __file *); /* read one char from device */
|
||||
// FIXME add all low level functions here like _open, _close, ... like newlib does
|
||||
void *udata; /* User defined and accessible data. */
|
||||
};
|
||||
// =============================================
|
||||
///@brief POSIX open modes - no other combination are allowed.
|
||||
/// - man page open(2)
|
||||
/// - Note: The POSIX correct test of O_RDONLY is: (mode & O_ACCMODE) == O_RDONLY.
|
||||
#define O_ACCMODE 00000003 /*< read, write, read-write modes */
|
||||
#define O_RDONLY 00000000 /*< Read only */
|
||||
#define O_WRONLY 00000001 /*< Write only */
|
||||
#define O_RDWR 00000002 /*< Read/Write */
|
||||
#define O_CREAT 00000100 /*< Create file only if it does not exist */
|
||||
#define O_EXCL 00000200 /*< O_CREAT option, Create fails if file exists
|
||||
*/
|
||||
#define O_NOCTTY 00000400 /*< @todo */
|
||||
#define O_TRUNC 00001000 /*< Truncate if exists */
|
||||
#define O_APPEND 00002000 /*< All writes are to EOF */
|
||||
#define O_NONBLOCK 00004000 /*< @todo */
|
||||
#define O_BINARY 00000004 /*< Binary */
|
||||
#define O_TEXT 00000004 /*< Text End Of Line translation */
|
||||
#define O_CLOEXEC 00000000
|
||||
///@brief POSIX File types, see fstat and stat.
|
||||
#define S_IFMT 0170000 /*< These bits determine file type. */
|
||||
#define S_IFDIR 0040000 /*< Directory. */
|
||||
#define S_IFCHR 0020000 /*< Character device. */
|
||||
#define S_IFBLK 0060000 /*< Block device. */
|
||||
#define S_IFREG 0100000 /*< Regular file. */
|
||||
#define S_IFIFO 0010000 /*< FIFO. */
|
||||
#define S_IFLNK 0120000 /*< Symbolic link. */
|
||||
#define S_IFSOCK 0140000 /*< Socket. */
|
||||
#define S_IREAD 0400 /*< Read by owner. */
|
||||
#define S_IWRITE 0200 /*< Write by owner. */
|
||||
#define S_IEXEC 0100 /*< Execute by owner. */
|
||||
|
||||
///@brief POSIX File type test macros.
|
||||
#define S_ISTYPE(mode, mask) (((mode) & S_IFMT) == (mask))
|
||||
#define S_ISDIR(mode) S_ISTYPE((mode), S_IFDIR)
|
||||
#define S_ISCHR(mode) S_ISTYPE((mode), S_IFCHR)
|
||||
#define S_ISBLK(mode) S_ISTYPE((mode), S_IFBLK)
|
||||
#define S_ISREG(mode) S_ISTYPE((mode), S_IFREG)
|
||||
|
||||
//@brief POSIX File permissions, see fstat and stat
|
||||
#define S_IRUSR S_IREAD /*< Read by owner. */
|
||||
#define S_IWUSR S_IWRITE /*< Write by owner. */
|
||||
#define S_IXUSR S_IEXEC /*< Execute by owner. */
|
||||
#define S_IRWXU (S_IREAD|S_IWRITE|S_IEXEC) /*< Read,Write,Execute by owner */
|
||||
|
||||
#define S_IRGRP (S_IRUSR >> 3) /*< Read by group. */
|
||||
#define S_IWGRP (S_IWUSR >> 3) /*< Write by group. */
|
||||
#define S_IXGRP (S_IXUSR >> 3) /*< Execute by group. */
|
||||
#define S_IRWXG (S_IRWXU >> 3) /*< Read,Write,Execute by user */
|
||||
|
||||
#define S_IROTH (S_IRGRP >> 3) /*< Read by others. */
|
||||
#define S_IWOTH (S_IWGRP >> 3) /*< Write by others. */
|
||||
#define S_IXOTH (S_IXGRP >> 3) /*< Execute by others. */
|
||||
#define S_IRWXO (S_IRWXG >> 3) /*< Read,Write,Execute by other */
|
||||
// =============================================
|
||||
|
||||
///@brief used in posix.c to compare to ascii file modes
|
||||
#define modecmp(str, pat) (strcmp(str, pat) == 0 ? 1: 0)
|
||||
|
||||
// =============================================
|
||||
///@brief FATFS open modes
|
||||
#define FATFS_R (S_IRUSR | S_IRGRP | S_IROTH) /*< FatFs Read perms */
|
||||
#define FATFS_W (S_IWUSR | S_IWGRP | S_IWOTH) /*< FatFs Write perms */
|
||||
#define FATFS_X (S_IXUSR | S_IXGRP | S_IXOTH) /*< FatFs Execute perms */
|
||||
|
||||
// =============================================
|
||||
///@brief End of file or device read
|
||||
#define EOF (-1)
|
||||
|
||||
///@brief Seek offset macros
|
||||
#define SEEK_SET 0
|
||||
#define SEEK_CUR 1
|
||||
#define SEEK_END 2
|
||||
|
||||
// =============================================
|
||||
///@brief define FILE type
|
||||
typedef struct __file FILE;
|
||||
|
||||
///@brief Maximum number of POSIX file handles.
|
||||
#define MAX_FILES 16
|
||||
extern FILE *__iob[MAX_FILES];
|
||||
|
||||
///@brief define stdin, stdout and stderr
|
||||
#undef stdin
|
||||
#undef stdout
|
||||
#undef stderr
|
||||
|
||||
// Hard coded stdin,stdout and stderr locations
|
||||
#define stdin (__iob[0])
|
||||
#define stdout (__iob[1])
|
||||
#define stderr (__iob[2])
|
||||
|
||||
// =============================================
|
||||
//#define IO_MACROS
|
||||
#ifdef IO_MACROS
|
||||
///@briefdefine putc, putchar and getc in terms of the posix fgetc() and fputc() interface
|
||||
/// MAKE SURE that fdevopen() has been called BEFORE any input/output is processed
|
||||
/// @see uart.c for the fdevopen() call
|
||||
#define putc(__c, __stream) fputc(__c, __stream)
|
||||
#define getc(__stream) fgetc(__stream)
|
||||
/**
|
||||
The macro \c putchar sends character \c c to \c stdout.
|
||||
*/
|
||||
#define putchar(__c) fputc(__c,stdout)
|
||||
|
||||
#define puts(__str) fputs(__str,stdout)
|
||||
#endif
|
||||
|
||||
// =============================================
|
||||
///@brief device IO udata
|
||||
#define fdev_set_udata(stream, u) do { (stream)->udata = u; } while(0)
|
||||
#define fdev_get_udata(stream) ((stream)->udata)
|
||||
|
||||
///@brief device status flags
|
||||
#define _FDEV_EOF (-1)
|
||||
#define _FDEV_ERR (-2)
|
||||
//@brief device read/write flags
|
||||
#define _FDEV_SETUP_READ __SRD /**< fdev_setup_stream() with read intent */
|
||||
#define _FDEV_SETUP_WRITE __SWR /**< fdev_setup_stream() with write intent */
|
||||
#define _FDEV_SETUP_RW (__SRD|__SWR) /**< fdev_setup_stream() with read/write intent */
|
||||
|
||||
// =============================================
|
||||
|
||||
|
||||
/* posix.c */
|
||||
int isatty ( int fileno );
|
||||
int fgetc ( FILE *stream );
|
||||
int fputc ( int c , FILE *stream );
|
||||
void clearerr(FILE *stream);
|
||||
#ifndef IO_MACROS
|
||||
int getchar ( void );
|
||||
int putchar ( int c );
|
||||
#endif
|
||||
//int ungetc ( int c , FILE *stream );
|
||||
#ifndef IO_MACROS
|
||||
int putc ( int c , FILE *stream );
|
||||
#endif
|
||||
char *fgets ( char *str , int size , FILE *stream );
|
||||
int fputs ( const char *str , FILE *stream );
|
||||
#ifndef IO_MACROS
|
||||
int puts ( const char *str );
|
||||
#endif
|
||||
int feof ( FILE *stream );
|
||||
int fgetpos ( FILE *stream , size_t *pos );
|
||||
int fseek ( FILE *stream , long offset , int whence );
|
||||
int fsetpos ( FILE *stream , size_t *pos );
|
||||
long ftell ( FILE *stream );
|
||||
off_t lseek ( int fileno , off_t position , int whence );
|
||||
void rewind ( FILE *stream );
|
||||
int close ( int fileno );
|
||||
int fileno ( FILE *stream );
|
||||
FILE *fileno_to_stream ( int fileno );
|
||||
FILE *fopen ( const char *path , const char *mode );
|
||||
size_t __wrap_fread ( void *ptr , size_t size , size_t nmemb , FILE *stream );
|
||||
int ftruncate ( int fd , off_t length );
|
||||
size_t fwrite ( const void *ptr , size_t size , size_t nmemb , FILE *stream );
|
||||
int open (const char *pathname, int flags);
|
||||
ssize_t read ( int fd , void *buf , size_t count );
|
||||
void sync ( void );
|
||||
int syncfs(int fd);
|
||||
int fsync ( int fd );
|
||||
int truncate ( const char *path , off_t length );
|
||||
ssize_t write ( int fd , const void *buf , size_t count );
|
||||
int __wrap_fclose ( FILE *stream );
|
||||
FILE * __wrap_freopen ( const char * filename, const char * mode, FILE * stream );
|
||||
int getc(FILE *fp);
|
||||
char *gets (char *p);
|
||||
//void dump_stat ( struct stat *sp );
|
||||
|
||||
#if 0
|
||||
int fstat ( int fd , struct stat *buf );
|
||||
#endif
|
||||
int64_t fs_getfree(void);
|
||||
int64_t fs_gettotal(void);
|
||||
int stat ( const char *name , struct stat *buf );
|
||||
char *basename (const char *str );
|
||||
char *baseext ( char *str );
|
||||
int chdir ( const char *pathname );
|
||||
int chmod ( const char *pathname , mode_t mode );
|
||||
int dirname ( char *str );
|
||||
int utime(const char *filename, const struct utimbuf *times);
|
||||
|
||||
#if 0
|
||||
int fchmod ( int fd , mode_t mode );
|
||||
#endif
|
||||
|
||||
char *getcwd ( char *pathname , size_t len );
|
||||
int mkdir ( const char *pathname , mode_t mode );
|
||||
int rename ( const char *oldpath , const char *newpath );
|
||||
int rmdir ( const char *pathname );
|
||||
int unlink ( const char *pathname );
|
||||
int __wrap_remove(const char *pathname);
|
||||
int closedir ( DIR *dirp );
|
||||
DIR *opendir ( const char *pathdir );
|
||||
struct dirent *readdir ( DIR *dirp );
|
||||
void clrerror ( FILE *stream );
|
||||
int ferror ( FILE *stream );
|
||||
char *strerror ( int errnum );
|
||||
char *__wrap_strerror_r ( int errnum , char *buf , size_t buflen );
|
||||
FILE *fdevopen ( int (*put )(char ,FILE *), int (*get )(FILE *));
|
||||
//int mkfs(char *name );
|
||||
int fatfs_getc ( FILE *stream );
|
||||
int fatfs_putc ( char c , FILE *stream );
|
||||
int fatfs_to_errno ( FRESULT Result );
|
||||
int fatfs_to_fileno ( FIL *fh );
|
||||
time_t fat_time_to_unix ( uint16_t date , uint16_t time );
|
||||
void unix_time_to_fat(time_t epoch, uint16_t *date, uint16_t *time);
|
||||
FIL *fileno_to_fatfs ( int fileno );
|
||||
int free_file_descriptor ( int fileno );
|
||||
int new_file_descriptor ( void );
|
||||
int posix_fopen_modes_to_open ( const char *mode );
|
||||
|
||||
int __wrap_fprintf(FILE *fp, const char *format, ...);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
// =============================================
|
||||
#endif //USE_POSIX
|
||||
#endif //_POSIX_H_
|
@ -16,10 +16,10 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "posix.h"
|
||||
#include <stdarg.h>
|
||||
#include <stdint.h>
|
||||
#include <stddef.h>
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
@ -31,9 +31,6 @@ int vasprintf(char **strp, const char *fmt, va_list ap);
|
||||
int asprintf(char **strp, const char *fmt, ...);
|
||||
int vprintf(const char *fmt, va_list arg);
|
||||
int printf(const char *fmt, ...);
|
||||
#if defined(USE_FATFS) || (defined(HAL_OS_FATFS_IO) && HAL_OS_FATFS_IO)
|
||||
int fscanf ( FILE * stream, const char * format, ... );
|
||||
#endif
|
||||
|
||||
int scanf (const char *fmt, ...);
|
||||
int __wrap_sscanf (const char *buf, const char *fmt, ...);
|
||||
|
@ -18,6 +18,7 @@
|
||||
#include "sdcard.h"
|
||||
#include "hwdef/common/spi_hook.h"
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
#include <AP_Filesystem/AP_Filesystem.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
@ -78,7 +79,7 @@ bool sdcard_init()
|
||||
printf("Successfully mounted SDCard (slowdown=%u)\n", (unsigned)sd_slowdown);
|
||||
|
||||
// Create APM Directory if needed
|
||||
mkdir("/APM", 0777);
|
||||
AP::FS().mkdir("/APM");
|
||||
sdcard_running = true;
|
||||
return true;
|
||||
}
|
||||
@ -123,7 +124,7 @@ bool sdcard_init()
|
||||
printf("Successfully mounted SDCard (slowdown=%u)\n", (unsigned)sd_slowdown);
|
||||
|
||||
// Create APM Directory if needed
|
||||
mkdir("/APM", 0777);
|
||||
AP::FS().mkdir("/APM");
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
@ -27,7 +27,6 @@
|
||||
#include <hal.h>
|
||||
#include <chprintf.h>
|
||||
#include <ctype.h>
|
||||
#include "hwdef/common/posix.h"
|
||||
#include "hwdef/common/stdio.h"
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
|
||||
@ -215,123 +214,3 @@ static int16_t atob(uint32_t *vp, char *p, int base)
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
* vsscanf(buf,fmt,ap)
|
||||
*/
|
||||
int
|
||||
vsscanf (const char *buf, const char *s, va_list ap)
|
||||
{
|
||||
int count, noassign, base=0, lflag;
|
||||
uint32_t width;
|
||||
const char *tc;
|
||||
char *t, tmp[MAXLN];
|
||||
|
||||
count = noassign = width = lflag = 0;
|
||||
while (*s && *buf) {
|
||||
while (isspace ((unsigned char)(*s)))
|
||||
s++;
|
||||
if (*s == '%') {
|
||||
s++;
|
||||
for (; *s; s++) {
|
||||
if (strchr ("dibouxcsefg%", *s))
|
||||
break;
|
||||
if (*s == '*')
|
||||
noassign = 1;
|
||||
else if (*s == 'l' || *s == 'L')
|
||||
lflag = 1;
|
||||
else if (*s >= '1' && *s <= '9') {
|
||||
for (tc = s; isdigit ((unsigned)(*s)); s++);
|
||||
strncpy (tmp, tc, s - tc);
|
||||
tmp[s - tc] = '\0';
|
||||
atob (&width, tmp, 10);
|
||||
s--;
|
||||
}
|
||||
}
|
||||
if (*s == 's') {
|
||||
while (isspace ((unsigned char)(*buf)))
|
||||
buf++;
|
||||
if (!width)
|
||||
width = strcspn (buf, ISSPACE);
|
||||
if (!noassign) {
|
||||
strncpy (t = va_arg (ap, char *), buf, width);
|
||||
t[width] = '\0';
|
||||
}
|
||||
buf += width;
|
||||
} else if (*s == 'c') {
|
||||
if (!width)
|
||||
width = 1;
|
||||
if (!noassign) {
|
||||
strncpy (t = va_arg (ap, char *), buf, width);
|
||||
t[width] = '\0';
|
||||
}
|
||||
buf += width;
|
||||
} else if (strchr ("dobxu", *s)) {
|
||||
while (isspace ((unsigned char)(*buf)))
|
||||
buf++;
|
||||
if (*s == 'd' || *s == 'u')
|
||||
base = 10;
|
||||
else if (*s == 'x')
|
||||
base = 16;
|
||||
else if (*s == 'o')
|
||||
base = 8;
|
||||
else if (*s == 'b')
|
||||
base = 2;
|
||||
if (!width) {
|
||||
if (isspace ((unsigned char)(*(s + 1))) || *(s + 1) == 0)
|
||||
width = strcspn (buf, ISSPACE);
|
||||
else
|
||||
width = strchr (buf, *(s + 1)) - buf;
|
||||
}
|
||||
strncpy (tmp, buf, width);
|
||||
tmp[width] = '\0';
|
||||
buf += width;
|
||||
if (!noassign)
|
||||
atob (va_arg (ap, uint32_t *), tmp, base);
|
||||
}
|
||||
if (!noassign)
|
||||
count++;
|
||||
width = noassign = lflag = 0;
|
||||
s++;
|
||||
} else {
|
||||
while (isspace ((unsigned char)(*buf)))
|
||||
buf++;
|
||||
if (*s != *buf)
|
||||
break;
|
||||
else
|
||||
s++, buf++;
|
||||
}
|
||||
}
|
||||
return (count);
|
||||
}
|
||||
|
||||
static int vfscanf(FILE *stream, const char *fmt, va_list ap);
|
||||
|
||||
/*
|
||||
* fscanf(stream,fmt,va_alist)
|
||||
*/
|
||||
int fscanf (FILE *stream, const char *fmt, ...)
|
||||
{
|
||||
int count;
|
||||
va_list ap;
|
||||
|
||||
va_start (ap, fmt);
|
||||
count = vfscanf (stream, fmt, ap);
|
||||
va_end (ap);
|
||||
return (count);
|
||||
}
|
||||
|
||||
/*
|
||||
* vfscanf(stream,fmt,ap)
|
||||
*/
|
||||
static int vfscanf (FILE *stream, const char *fmt, va_list ap)
|
||||
{
|
||||
int count;
|
||||
char buf[MAXLN + 1];
|
||||
|
||||
if (fgets (buf, MAXLN, stream) == 0) {
|
||||
return (-1);
|
||||
}
|
||||
count = vsscanf (buf, fmt, ap);
|
||||
return (count);
|
||||
}
|
||||
#endif // HAL_OS_FATFS_IO
|
||||
|
Loading…
Reference in New Issue
Block a user