From 618f2999d2e8647dd4c2821af7ad5450fb6f67a3 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Mon, 9 Dec 2013 17:37:15 +0100 Subject: Fixes for sim for CLANG --- nuttx/arch/sim/include/math.h | 488 +++++++++++++++++++++++++++++++++++++++++ nuttx/arch/sim/src/up_setjmp.S | 12 +- 2 files changed, 494 insertions(+), 6 deletions(-) create mode 100644 nuttx/arch/sim/include/math.h (limited to 'nuttx') diff --git a/nuttx/arch/sim/include/math.h b/nuttx/arch/sim/include/math.h new file mode 100644 index 000000000..15ab63167 --- /dev/null +++ b/nuttx/arch/sim/include/math.h @@ -0,0 +1,488 @@ +/* + * ==================================================== + * Copyright (C) 1993 by Sun Microsystems, Inc. All rights reserved. + * + * Developed at SunPro, a Sun Microsystems, Inc. business. + * Permission to use, copy, modify, and distribute this + * software is freely granted, provided that this notice + * is preserved. + * ==================================================== + */ + +/* + * from: @(#)fdlibm.h 5.1 93/09/24 + * $FreeBSD$ + */ + +#ifndef _MATH_H_ +#define _MATH_H_ + +#include +#include +#include + +#define __ISO_C_VISIBLE 1999 +#define __BSD_VISIBLE 1 + +/* + * ANSI/POSIX + */ +extern const union __infinity_un { + unsigned char __uc[8]; + double __ud; +} __infinity; + +extern const union __nan_un { + unsigned char __uc[sizeof(float)]; + float __uf; +} __nan; + +#if (defined(__GNUC__) && __GNUC__ >= 3) || defined(__INTEL_COMPILER) +#define __MATH_BUILTIN_CONSTANTS +#endif + +#if (defined(__GNUC__) && __GNUC__ >= 3) +#define __MATH_BUILTIN_RELOPS +#endif + +#ifdef __MATH_BUILTIN_CONSTANTS +#define HUGE_VAL __builtin_huge_val() +#else +#define HUGE_VAL (__infinity.__ud) +#endif + +#if __ISO_C_VISIBLE >= 1999 +#define FP_ILOGB0 (-__INT_MAX) +#define FP_ILOGBNAN __INT_MAX + +#ifdef __MATH_BUILTIN_CONSTANTS +#define HUGE_VALF __builtin_huge_valf() +#define HUGE_VALL __builtin_huge_vall() +#define INFINITY __builtin_inf() +#define NAN __builtin_nan("") +#else +#define HUGE_VALF (float)HUGE_VAL +#define HUGE_VALL (long double)HUGE_VAL +#define INFINITY HUGE_VALF +#define NAN (__nan.__uf) +#endif /* __MATH_BUILTIN_CONSTANTS */ + +#define MATH_ERRNO 1 +#define MATH_ERREXCEPT 2 +#define math_errhandling 0 + +/* Symbolic constants to classify floating point numbers. */ +#define FP_INFINITE 0x01 +#define FP_NAN 0x02 +#define FP_NORMAL 0x04 +#define FP_SUBNORMAL 0x08 +#define FP_ZERO 0x10 +#define fpclassify(x) \ + ((sizeof (x) == sizeof (float)) ? __fpclassifyf(x) \ + : (sizeof (x) == sizeof (double)) ? __fpclassifyd(x) \ + : __fpclassifyl(x)) + +#define isfinite(x) ((fpclassify(x) & (FP_INFINITE|FP_NAN)) == 0) +#define isinf(x) (fpclassify(x) == FP_INFINITE) +#define isnan(x) (fpclassify(x) == FP_NAN) +#define isnormal(x) (fpclassify(x) == FP_NORMAL) + +#ifdef __MATH_BUILTIN_RELOPS +#define isgreater(x, y) __builtin_isgreater((x), (y)) +#define isgreaterequal(x, y) __builtin_isgreaterequal((x), (y)) +#define isless(x, y) __builtin_isless((x), (y)) +#define islessequal(x, y) __builtin_islessequal((x), (y)) +#define islessgreater(x, y) __builtin_islessgreater((x), (y)) +#define isunordered(x, y) __builtin_isunordered((x), (y)) +#else +#define isgreater(x, y) (!isunordered((x), (y)) && (x) > (y)) +#define isgreaterequal(x, y) (!isunordered((x), (y)) && (x) >= (y)) +#define isless(x, y) (!isunordered((x), (y)) && (x) < (y)) +#define islessequal(x, y) (!isunordered((x), (y)) && (x) <= (y)) +#define islessgreater(x, y) (!isunordered((x), (y)) && \ + ((x) > (y) || (y) > (x))) +#define isunordered(x, y) (isnan(x) || isnan(y)) +#endif /* __MATH_BUILTIN_RELOPS */ + +#define signbit(x) __signbit(x) + +#endif /* __ISO_C_VISIBLE >= 1999 */ + +/* + * XOPEN/SVID + */ +#if __BSD_VISIBLE || __XSI_VISIBLE +#define M_E 2.7182818284590452354 /* e */ +#define M_LOG2E 1.4426950408889634074 /* log 2e */ +#define M_LOG10E 0.43429448190325182765 /* log 10e */ +#define M_LN2 0.69314718055994530942 /* log e2 */ +#define M_LN10 2.30258509299404568402 /* log e10 */ +#define M_PI 3.14159265358979323846 /* pi */ +#define M_PI_2 1.57079632679489661923 /* pi/2 */ +#define M_PI_4 0.78539816339744830962 /* pi/4 */ +#define M_1_PI 0.31830988618379067154 /* 1/pi */ +#define M_2_PI 0.63661977236758134308 /* 2/pi */ +#define M_2_SQRTPI 1.12837916709551257390 /* 2/sqrt(pi) */ +#define M_SQRT2 1.41421356237309504880 /* sqrt(2) */ +#define M_SQRT1_2 0.70710678118654752440 /* 1/sqrt(2) */ +#define M_DEG_TO_RAD 0.01745329251994 +#define M_RAD_TO_DEG 57.2957795130823 + +#define MAXFLOAT ((float)3.40282346638528860e+38) +extern int signgam; +#endif /* __BSD_VISIBLE || __XSI_VISIBLE */ + +#if __BSD_VISIBLE +enum fdversion {fdlibm_ieee = -1, fdlibm_svid, fdlibm_xopen, fdlibm_posix}; + +#define _LIB_VERSION_TYPE enum fdversion +#define _LIB_VERSION _fdlib_version + +/* if global variable _LIB_VERSION is not desirable, one may + * change the following to be a constant by: + * #define _LIB_VERSION_TYPE const enum version + * In that case, after one initializes the value _LIB_VERSION (see + * s_lib_version.c) during compile time, it cannot be modified + * in the middle of a program + */ +extern _LIB_VERSION_TYPE _LIB_VERSION; + +#define _IEEE_ fdlibm_ieee +#define _SVID_ fdlibm_svid +#define _XOPEN_ fdlibm_xopen +#define _POSIX_ fdlibm_posix + +/* We have a problem when using C++ since `exception' is a reserved + name in C++. */ +#ifndef __cplusplus +struct exception { + int type; + char *name; + double arg1; + double arg2; + double retval; +}; +#endif + +#define isnanf(x) isnan(x) + +#if 0 +/* Old value from 4.4BSD-Lite math.h; this is probably better. */ +#define HUGE HUGE_VAL +#else +#define HUGE MAXFLOAT +#endif + +#define X_TLOSS 1.41484755040568800000e+16 /* pi*2**52 */ + +#define DOMAIN 1 +#define SING 2 +#define OVERFLOW 3 +#define UNDERFLOW 4 +#define TLOSS 5 +#define PLOSS 6 + +#endif /* __BSD_VISIBLE */ + +/* + * Most of these functions have the side effect of setting errno, so they + * are not declared as __pure2. (XXX: this point needs to be revisited, + * since C99 doesn't require the mistake of setting errno, and we mostly + * don't set it anyway. In C99, pragmas and functions for changing the + * rounding mode affect the purity of these functions.) + */ +__BEGIN_DECLS +/* + * ANSI/POSIX + */ +int __fpclassifyd(double) __pure2; +int __fpclassifyf(float) __pure2; +int __fpclassifyl(long double) __pure2; +int __signbit(double) __pure2; + +double acos(double); +double asin(double); +double atan(double); +double atan2(double, double); +double cos(double); +double sin(double); +double tan(double); + +double cosh(double); +double sinh(double); +double tanh(double); + +double exp(double); +double frexp(double, int *); /* fundamentally !__pure2 */ +double ldexp(double, int); +double log(double); +double log10(double); +double modf(double, double *); /* fundamentally !__pure2 */ + +double pow(double, double); +double sqrt(double); + +double ceil(double); +double fabs(double); +double floor(double); +double fmod(double, double); + +/* + * These functions are not in C90 so they can be "right". The ones that + * never set errno in lib/msun are declared as __pure2. + */ +#if __BSD_VISIBLE || __ISO_C_VISIBLE >= 1999 || __XSI_VISIBLE +double acosh(double); +double asinh(double); +double atanh(double); +double cbrt(double) __pure2; +double erf(double); +double erfc(double) __pure2; +double expm1(double) __pure2; +double fdim(double, double); +double fmax(double, double) __pure2; +double fmin(double, double) __pure2; +double hypot(double, double); +int ilogb(double); +double lgamma(double); +double log1p(double) __pure2; +double logb(double) __pure2; +double nearbyint(double) __pure2; +double nextafter(double, double); +double remainder(double, double); +double rint(double) __pure2; +double round(double); +double trunc(double); +#endif /* __BSD_VISIBLE || __ISO_C_VISIBLE >= 1999 || __XSI_VISIBLE */ + +#if __BSD_VISIBLE || __XSI_VISIBLE +double j0(double); +double j1(double); +double jn(int, double); +double scalb(double, double); +double y0(double); +double y1(double); +double yn(int, double); + +#if __XSI_VISIBLE <= 500 || __BSD_VISIBLE +double gamma(double); +#endif +#endif /* __BSD_VISIBLE || __XSI_VISIBLE */ + +#if __BSD_VISIBLE || __ISO_C_VISIBLE >= 1999 +double copysign(double, double) __pure2; +double scalbln(double, long); +double scalbn(double, int); +double tgamma(double); +#endif + +/* + * BSD math library entry points + */ +#if __BSD_VISIBLE +double drem(double, double); +int finite(double) __pure2; + +/* + * Reentrant version of gamma & lgamma; passes signgam back by reference + * as the second argument; user must allocate space for signgam. + */ +double gamma_r(double, int *); +double lgamma_r(double, int *); + +/* + * IEEE Test Vector + */ +double significand(double); + +#ifndef __cplusplus +int matherr(struct exception *); +#endif +#endif /* __BSD_VISIBLE */ + +/* float versions of ANSI/POSIX functions */ +float acosf(float); +float asinf(float); +float atanf(float); +float atan2f(float, float); +float cosf(float); +float sinf(float); +float tanf(float); + +float coshf(float); +float sinhf(float); +float tanhf(float); + +float expf(float); +float expm1f(float) __pure2; +float frexpf(float, int *); /* fundamentally !__pure2 */ +int ilogbf(float); +float ldexpf(float, int); +float log10f(float); +float log1pf(float) __pure2; +float logf(float); +float modff(float, float *); /* fundamentally !__pure2 */ + +float powf(float, float); +float sqrtf(float); + +float ceilf(float); +float fabsf(float); +float floorf(float); +float fmodf(float, float); +float roundf(float); + +float erff(float); +float erfcf(float) __pure2; +float hypotf(float, float) __pure2; +float lgammaf(float); + +float acoshf(float); +float asinhf(float); +float atanhf(float); +float cbrtf(float) __pure2; +float logbf(float) __pure2; +float copysignf(float, float) __pure2; +float nearbyintf(float) __pure2; +float nextafterf(float, float); +float remainderf(float, float); +float rintf(float); +float scalblnf(float, long); +float scalbnf(float, int); +float truncf(float); + +float fdimf(float, float); +float fmaxf(float, float) __pure2; +float fminf(float, float) __pure2; + +/* + * float versions of BSD math library entry points + */ +#if __BSD_VISIBLE +float dremf(float, float); +int finitef(float) __pure2; +float gammaf(float); +float j0f(float); +float j1f(float); +float jnf(int, float); +float scalbf(float, float); +float y0f(float); +float y1f(float); +float ynf(int, float); + +/* + * Float versions of reentrant version of gamma & lgamma; passes + * signgam back by reference as the second argument; user must + * allocate space for signgam. + */ +float gammaf_r(float, int *); +float lgammaf_r(float, int *); + +/* + * float version of IEEE Test Vector + */ +float significandf(float); +#endif /* __BSD_VISIBLE */ + +/* + * long double versions of ISO/POSIX math functions + */ +#if __ISO_C_VISIBLE >= 1999 +#if 0 +long double acoshl(long double); +long double acosl(long double); +long double asinhl(long double); +long double asinl(long double); +long double atan2l(long double, long double); +long double atanhl(long double); +long double atanl(long double); +long double cbrtl(long double); +long double ceill(long double); +#endif +long double copysignl(long double, long double); +#if 0 +long double coshl(long double); +long double cosl(long double); +long double erfcl(long double); +long double erfl(long double); +long double exp2l(long double); +long double expl(long double); +long double expm1l(long double); +#endif +long double fabsl(long double); +long double fdiml(long double, long double); +#if 0 +long double floorl(long double); +long double fmal(long double, long double, long double); +#endif +long double fmaxl(long double, long double) __pure2; +long double fminl(long double, long double) __pure2; +#if 0 +long double fmodl(long double, long double); +long double frexpl(long double value, int *); +long double hypotl(long double, long double); +int ilogbl(long double); +long double ldexpl(long double, int); +long double lgammal(long double); +long long llrintl(long double); +long long llroundl(long double); +long double log10l(long double); +long double log1pl(long double); +long double log2l(long double); +long double logbl(long double); +long double logl(long double); +long lrintl(long double); +long lroundl(long double); +long double modfl(long double, long double *); +long double nanl(const char *); +long double nearbyintl(long double); +long double nextafterl(long double, long double); +double nexttoward(double, long double); +float nexttowardf(float, long double); +long double nexttowardl(long double, long double); +long double powl(long double, long double); +long double remainderl(long double, long double); +long double remquol(long double, long double, int *); +long double rintl(long double); +long double roundl(long double); +long double scalblnl(long double, long); +long double scalbnl(long double, int); +long double sinhl(long double); +long double sinl(long double); +long double sqrtl(long double); +long double tanhl(long double); +long double tanl(long double); +long double tgammal(long double); +long double truncl(long double); +#endif + +#endif /* __ISO_C_VISIBLE >= 1999 */ + +#define M_E_F 2.7182818284590452354f +#define M_LOG2E_F 1.4426950408889634074f +#define M_LOG10E_F 0.43429448190325182765f +#define M_LN2_F _M_LN2_F +#define M_LN10_F 2.30258509299404568402f +#define M_PI_F 3.14159265358979323846f +#define M_TWOPI_F (M_PI_F * 2.0f) +#define M_PI_2_F 1.57079632679489661923f +#define M_PI_4_F 0.78539816339744830962f +#define M_3PI_4_F 2.3561944901923448370E0f +#define M_SQRTPI_F 1.77245385090551602792981f +#define M_1_PI_F 0.31830988618379067154f +#define M_2_PI_F 0.63661977236758134308f +#define M_2_SQRTPI_F 1.12837916709551257390f +#define M_DEG_TO_RAD_F 0.01745329251994f +#define M_RAD_TO_DEG_F 57.2957795130823f +#define M_SQRT2_F 1.41421356237309504880f +#define M_SQRT1_2_F 0.70710678118654752440f +#define M_LN2LO_F 1.9082149292705877000E-10f +#define M_LN2HI_F 6.9314718036912381649E-1f +#define M_SQRT3_F 1.73205080756887719000f +#define M_IVLN10_F 0.43429448190325182765f /* 1 / log(10) */ +#define M_LOG2_E_F _M_LN2_F +#define M_INVLN2_F 1.4426950408889633870E0f /* 1 / log(2) */ + +__END_DECLS + +#endif /* !_MATH_H_ */ \ No newline at end of file diff --git a/nuttx/arch/sim/src/up_setjmp.S b/nuttx/arch/sim/src/up_setjmp.S index a65317c65..20ec5539f 100644 --- a/nuttx/arch/sim/src/up_setjmp.S +++ b/nuttx/arch/sim/src/up_setjmp.S @@ -47,7 +47,7 @@ * Private Definitions **************************************************************************/ -#ifdef __CYGWIN__ +#if !((defined __CYGWIN__) || (defined __APPLE__)) # define SYMBOL(s) _##s #else # define SYMBOL(s) s @@ -79,7 +79,7 @@ .text .globl SYMBOL(up_setjmp) -#ifndef __CYGWIN__ +#if !((defined __CYGWIN__) || (defined __APPLE__)) .type SYMBOL(up_setjmp), @function #endif SYMBOL(up_setjmp): @@ -110,11 +110,11 @@ SYMBOL(up_setjmp): xorl %eax, %eax ret -#ifndef __CYGWIN__ +#if !((defined __CYGWIN__) || (defined __APPLE__)) .size SYMBOL(up_setjmp), . - SYMBOL(up_setjmp) #endif .globl SYMBOL(up_longjmp) -#ifndef __CYGWIN__ +#if !((defined __CYGWIN__) || (defined __APPLE__)) .type SYMBOL(up_longjmp), @function #endif SYMBOL(up_longjmp): @@ -135,8 +135,8 @@ SYMBOL(up_longjmp): /* Jump to saved PC. */ - jmp *%edx -#ifndef __CYGWIN__ + jmp (*%edx) +#if !((defined __CYGWIN__) || (defined __APPLE__)) .size SYMBOL(up_longjmp), . - SYMBOL(up_longjmp) #endif -- cgit v1.2.3 From ed3bd647073cec70430c7a4f4cc1db968a50becc Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 10 Dec 2013 14:14:41 +0100 Subject: Minor adjustment to make CLANG assembler happy --- nuttx/arch/sim/src/up_setjmp.S | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'nuttx') diff --git a/nuttx/arch/sim/src/up_setjmp.S b/nuttx/arch/sim/src/up_setjmp.S index 20ec5539f..d9c9c02f8 100644 --- a/nuttx/arch/sim/src/up_setjmp.S +++ b/nuttx/arch/sim/src/up_setjmp.S @@ -135,7 +135,7 @@ SYMBOL(up_longjmp): /* Jump to saved PC. */ - jmp (*%edx) + jmp *(%edx) #if !((defined __CYGWIN__) || (defined __APPLE__)) .size SYMBOL(up_longjmp), . - SYMBOL(up_longjmp) #endif -- cgit v1.2.3 From 2c8760a676e3b7e448e49e6faf6e1e317f89a15a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Tue, 17 Dec 2013 10:49:20 +0100 Subject: Fixed location of DMA console reinitialization --- nuttx/arch/arm/src/stm32/stm32_serial.c | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) (limited to 'nuttx') diff --git a/nuttx/arch/arm/src/stm32/stm32_serial.c b/nuttx/arch/arm/src/stm32/stm32_serial.c index d751b0f36..0cf1f209b 100644 --- a/nuttx/arch/arm/src/stm32/stm32_serial.c +++ b/nuttx/arch/arm/src/stm32/stm32_serial.c @@ -2424,13 +2424,12 @@ void up_serialinit(void) (void)uart_register("/dev/ttyS0", &uart_devs[CONSOLE_UART - 1]->dev); minor = 1; - /* If we need to re-initialise the console to enable DMA do that here. */ +#endif /* CONFIG_SERIAL_DISABLE_REORDERING not defined */ +/* If we need to re-initialise the console to enable DMA do that here. */ # ifdef SERIAL_HAVE_CONSOLE_DMA up_dma_setup(&uart_devs[CONSOLE_UART - 1]->dev); # endif -#endif /* CONFIG_SERIAL_DISABLE_REORDERING not defined */ - #endif /* CONSOLE_UART > 0 */ /* Register all remaining USARTs */ -- cgit v1.2.3 From b9d19cdef62210683d27e69bae22201ff3aa23d7 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Sun, 22 Dec 2013 23:37:26 +0100 Subject: STM32F10xxx single wire usart support --- nuttx/arch/arm/src/stm32/stm32_serial.c | 16 ++++++++++++++-- 1 file changed, 14 insertions(+), 2 deletions(-) (limited to 'nuttx') diff --git a/nuttx/arch/arm/src/stm32/stm32_serial.c b/nuttx/arch/arm/src/stm32/stm32_serial.c index 0cf1f209b..6b56165db 100644 --- a/nuttx/arch/arm/src/stm32/stm32_serial.c +++ b/nuttx/arch/arm/src/stm32/stm32_serial.c @@ -1741,8 +1741,19 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg) /* Change the TX port to be open-drain/push-pull and enable/disable * half-duplex mode. */ - uint32_t cr = up_serialin(priv, STM32_USART_CR3_OFFSET); +#if defined(CONFIG_STM32_STM32F10XX) + if (arg == SER_SINGLEWIRE_ENABLED) + { + stm32_configgpio((priv->tx_gpio & ~(GPIO_CNF_MASK)) | GPIO_CNF_AFOD); + cr |= USART_CR3_HDSEL; + } + else + { + stm32_configgpio((priv->tx_gpio & ~(GPIO_CNF_MASK)) | GPIO_CNF_AFPP); + cr &= ~USART_CR3_HDSEL; + } +#else if (arg == SER_SINGLEWIRE_ENABLED) { @@ -1754,10 +1765,11 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg) stm32_configgpio(priv->tx_gpio | GPIO_PUSHPULL); cr &= ~USART_CR3_HDSEL; } +#endif up_serialout(priv, STM32_USART_CR3_OFFSET, cr); } - break; + break; #endif #ifdef CONFIG_SERIAL_TERMIOS -- cgit v1.2.3 From b4a58caddb56ea3b6a6f750eed0c0c77a008e9c4 Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Thu, 2 Jan 2014 17:50:53 +0100 Subject: small whitespace correction --- nuttx/arch/arm/src/stm32/stm32_serial.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) (limited to 'nuttx') diff --git a/nuttx/arch/arm/src/stm32/stm32_serial.c b/nuttx/arch/arm/src/stm32/stm32_serial.c index 6b56165db..e2a0da226 100644 --- a/nuttx/arch/arm/src/stm32/stm32_serial.c +++ b/nuttx/arch/arm/src/stm32/stm32_serial.c @@ -1741,6 +1741,7 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg) /* Change the TX port to be open-drain/push-pull and enable/disable * half-duplex mode. */ + uint32_t cr = up_serialin(priv, STM32_USART_CR3_OFFSET); #if defined(CONFIG_STM32_STM32F10XX) if (arg == SER_SINGLEWIRE_ENABLED) @@ -1769,7 +1770,7 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg) up_serialout(priv, STM32_USART_CR3_OFFSET, cr); } - break; + break; #endif #ifdef CONFIG_SERIAL_TERMIOS -- cgit v1.2.3 From a7b819f5b92d639a0602582411601c6b3714e730 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 14 Jan 2014 00:12:53 +1100 Subject: FAT: cope with files of size equal to multiple of cluster size when the file size is 4096 we should use 1 cluster, not two --- nuttx/fs/fat/fs_fat32.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) (limited to 'nuttx') diff --git a/nuttx/fs/fat/fs_fat32.c b/nuttx/fs/fat/fs_fat32.c index e7e32eee2..f55475f09 100644 --- a/nuttx/fs/fat/fs_fat32.c +++ b/nuttx/fs/fat/fs_fat32.c @@ -621,7 +621,7 @@ fat_read_restart: * cluster boundary */ - if (ff->ff_sectorsincluster < 1) + if (buflen != 0 && ff->ff_sectorsincluster < 1) { /* Find the next cluster in the FAT. */ @@ -896,7 +896,7 @@ fat_write_restart: * cluster boundary */ - if (ff->ff_sectorsincluster < 1) + if (buflen != 0 && ff->ff_sectorsincluster < 1) { /* Extend the current cluster by one (unless lseek was used to * move the file position back from the end of the file) -- cgit v1.2.3 From 64fc22ccb08fe115ba1d74ee85b4fa0a99cdddc0 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 14 Jan 2014 06:36:38 +1100 Subject: FAT: fixed start cluster of .. directory entry this should be 0 on FAT32 as well (tested on Windows8 and Linux) --- nuttx/fs/fat/fs_fat32.c | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) (limited to 'nuttx') diff --git a/nuttx/fs/fat/fs_fat32.c b/nuttx/fs/fat/fs_fat32.c index f55475f09..2fbb0cba2 100644 --- a/nuttx/fs/fat/fs_fat32.c +++ b/nuttx/fs/fat/fs_fat32.c @@ -2119,7 +2119,11 @@ static int fat_mkdir(struct inode *mountpt, const char *relpath, mode_t mode) DIR_PUTFSTCLUSTLO(direntry, dircluster); parentcluster = dirinfo.dir.fd_startcluster; - if (fs->fs_type != FSTYPE_FAT32 && parentcluster == fs->fs_rootbase) + /* + parent cluster for .. is set to 0 on all FAT types (including + FAT32). Tested on Windows8 and Linux + */ + if (parentcluster == fs->fs_rootbase) { parentcluster = 0; } -- cgit v1.2.3 From c8b0ca23d9cb4304f856fc3fa9137fdff601b30a Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Wed, 15 Jan 2014 16:55:24 +0100 Subject: Abort after N retries, propagate error throughout driver layers --- nuttx/drivers/mtd/ramtron.c | 48 ++++++++++++++++++++++++++++++++++----------- 1 file changed, 37 insertions(+), 11 deletions(-) (limited to 'nuttx') diff --git a/nuttx/drivers/mtd/ramtron.c b/nuttx/drivers/mtd/ramtron.c index 44bc46c2e..fa058d423 100644 --- a/nuttx/drivers/mtd/ramtron.c +++ b/nuttx/drivers/mtd/ramtron.c @@ -247,9 +247,9 @@ static struct ramtron_parts_s ramtron_parts[] = static void ramtron_lock(FAR struct spi_dev_s *dev); static inline void ramtron_unlock(FAR struct spi_dev_s *dev); static inline int ramtron_readid(struct ramtron_dev_s *priv); -static void ramtron_waitwritecomplete(struct ramtron_dev_s *priv); +static int ramtron_waitwritecomplete(struct ramtron_dev_s *priv); static void ramtron_writeenable(struct ramtron_dev_s *priv); -static inline void ramtron_pagewrite(struct ramtron_dev_s *priv, FAR const uint8_t *buffer, +static inline int ramtron_pagewrite(struct ramtron_dev_s *priv, FAR const uint8_t *buffer, off_t offset); /* MTD driver methods */ @@ -367,7 +367,7 @@ static inline int ramtron_readid(struct ramtron_dev_s *priv) * Name: ramtron_waitwritecomplete ************************************************************************************/ -static void ramtron_waitwritecomplete(struct ramtron_dev_s *priv) +static int ramtron_waitwritecomplete(struct ramtron_dev_s *priv) { uint8_t status; @@ -379,20 +379,33 @@ static void ramtron_waitwritecomplete(struct ramtron_dev_s *priv) (void)SPI_SEND(priv->dev, RAMTRON_RDSR); - /* Loop as long as the memory is busy with a write cycle */ + /* Loop as long as the memory is busy with a write cycle, + * but limit the cycles. + * + * RAMTRON FRAM is never busy per spec compared to flash, + * and so anything exceeding the default timeout number + * is highly suspicious. + */ + unsigned int tries = 100; // XXX should be CONFIG_MTD_RAMTRON_WRITEWAIT_COUNT do { /* Send a dummy byte to generate the clock needed to shift out the status */ status = SPI_SEND(priv->dev, RAMTRON_DUMMY); + tries--; } - while ((status & RAMTRON_SR_WIP) != 0); + while ((status & RAMTRON_SR_WIP) != 0 && tries > 0); /* Deselect the FLASH */ SPI_SELECT(priv->dev, SPIDEV_FLASH, false); fvdbg("Complete\n"); + + if (tries == 0) + return -EAGAIN; + else + return OK; } /************************************************************************************ @@ -436,7 +449,7 @@ static inline void ramtron_sendaddr(const struct ramtron_dev_s *priv, uint32_t a * Name: ramtron_pagewrite ************************************************************************************/ -static inline void ramtron_pagewrite(struct ramtron_dev_s *priv, FAR const uint8_t *buffer, +static inline int ramtron_pagewrite(struct ramtron_dev_s *priv, FAR const uint8_t *buffer, off_t page) { off_t offset = page << priv->pageshift; @@ -449,7 +462,10 @@ static inline void ramtron_pagewrite(struct ramtron_dev_s *priv, FAR const uint8 * improve performance. */ - ramtron_waitwritecomplete(priv); + int ret = ramtron_waitwritecomplete(priv); + + if (ret) + return ret; /* Enable the write access to the FLASH */ @@ -475,6 +491,8 @@ static inline void ramtron_pagewrite(struct ramtron_dev_s *priv, FAR const uint8 SPI_SELECT(priv->dev, SPIDEV_FLASH, false); fvdbg("Written\n"); + + return OK; } /************************************************************************************ @@ -525,15 +543,21 @@ static ssize_t ramtron_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_ /* Lock the SPI bus and write each page to FLASH */ + int ret = nblocks; + ramtron_lock(priv->dev); while (blocksleft-- > 0) { - ramtron_pagewrite(priv, buffer, startblock); + if (ramtron_pagewrite(priv, buffer, startblock)) { + nblocks = 0; + goto error; + } startblock++; } - ramtron_unlock(priv->dev); - return nblocks; + error: + ramtron_unlock(priv->dev); + return nblocks; } /************************************************************************************ @@ -553,7 +577,9 @@ static ssize_t ramtron_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyt * improve performance. */ - ramtron_waitwritecomplete(priv); + int ret = ramtron_waitwritecomplete(priv); + if (ret) + return ret; /* Lock the SPI bus and select this FLASH part */ -- cgit v1.2.3 From 7387831eb2354f22b37abebb9be712247ad6bd1a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 16 Jan 2014 12:48:27 +1100 Subject: ramtron: give errors for IO operations immediately waiting for write completion and checking the status register on read will improve the chance that we catch IO errors immediately rather than on the next IO. This improves the chance that callers will be able to take reasonable action on IO errors. We have one example board that does give intermittent IO errors, and this change helps for that board --- nuttx/drivers/mtd/ramtron.c | 51 ++++++++++++++++++++++++--------------------- 1 file changed, 27 insertions(+), 24 deletions(-) (limited to 'nuttx') diff --git a/nuttx/drivers/mtd/ramtron.c b/nuttx/drivers/mtd/ramtron.c index fa058d423..8f6ae022d 100644 --- a/nuttx/drivers/mtd/ramtron.c +++ b/nuttx/drivers/mtd/ramtron.c @@ -402,10 +402,12 @@ static int ramtron_waitwritecomplete(struct ramtron_dev_s *priv) SPI_SELECT(priv->dev, SPIDEV_FLASH, false); fvdbg("Complete\n"); - if (tries == 0) + if (tries == 0) { + fdbg("timeout waiting for write completion\n"); return -EAGAIN; - else - return OK; + } + + return OK; } /************************************************************************************ @@ -456,17 +458,6 @@ static inline int ramtron_pagewrite(struct ramtron_dev_s *priv, FAR const uint8_ fvdbg("page: %08lx offset: %08lx\n", (long)page, (long)offset); - /* Wait for any preceding write to complete. We could simplify things by - * perform this wait at the end of each write operation (rather than at - * the beginning of ALL operations), but have the wait first will slightly - * improve performance. - */ - - int ret = ramtron_waitwritecomplete(priv); - - if (ret) - return ret; - /* Enable the write access to the FLASH */ ramtron_writeenable(priv); @@ -492,6 +483,14 @@ static inline int ramtron_pagewrite(struct ramtron_dev_s *priv, FAR const uint8_ SPI_SELECT(priv->dev, SPIDEV_FLASH, false); fvdbg("Written\n"); + // we wait for write completion now so we can report any errors to + // the caller. Otherwise the caller has no way of knowing if the + // data is on stable storage + int ret = ramtron_waitwritecomplete(priv); + + if (ret) + return ret; + return OK; } @@ -571,16 +570,6 @@ static ssize_t ramtron_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyt fvdbg("offset: %08lx nbytes: %d\n", (long)offset, (int)nbytes); - /* Wait for any preceding write to complete. We could simplify things by - * perform this wait at the end of each write operation (rather than at - * the beginning of ALL operations), but have the wait first will slightly - * improve performance. - */ - - int ret = ramtron_waitwritecomplete(priv); - if (ret) - return ret; - /* Lock the SPI bus and select this FLASH part */ ramtron_lock(priv->dev); @@ -598,6 +587,20 @@ static ssize_t ramtron_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyt SPI_RECVBLOCK(priv->dev, buffer, nbytes); + // read the status register. This isn't strictly needed, but it + // gives us a chance to detect if SPI transactions are operating + // correctly, which allows us to catch complete device failures in + // the read path. We expect the status register to just have the + // write enable bit set to the write enable state + (void)SPI_SEND(priv->dev, RAMTRON_RDSR); + uint8_t status = SPI_SEND(priv->dev, RAMTRON_DUMMY); + if ((status & ~RAMTRON_SR_SRWD) == 0) { + fdbg("read status failed - got 0x%02x\n", (unsigned)status); + SPI_SELECT(priv->dev, SPIDEV_FLASH, false); + ramtron_unlock(priv->dev); + return -EIO; + } + /* Deselect the FLASH and unlock the SPI bus */ SPI_SELECT(priv->dev, SPIDEV_FLASH, false); -- cgit v1.2.3 From 353eaa23ed92943caa85ed051943b84c825216a2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 16 Jan 2014 12:51:40 +1100 Subject: ramtron: the driver has been tested now --- nuttx/drivers/mtd/ramtron.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'nuttx') diff --git a/nuttx/drivers/mtd/ramtron.c b/nuttx/drivers/mtd/ramtron.c index 8f6ae022d..44716cbe8 100644 --- a/nuttx/drivers/mtd/ramtron.c +++ b/nuttx/drivers/mtd/ramtron.c @@ -1,6 +1,6 @@ /************************************************************************************ * drivers/mtd/ramtron.c - * Driver for SPI-based RAMTRON NVRAM Devices FM25V10 and others (not tested) + * Driver for SPI-based RAMTRON NVRAM Devices FM25V10 and others * * Copyright (C) 2011 Uros Platise. All rights reserved. * Copyright (C) 2009-2010, 2012-2013 Gregory Nutt. All rights reserved. -- cgit v1.2.3 From f84093e66b0280af575ecadc5625092ab4d7146d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 16 Jan 2014 16:57:52 +1100 Subject: mtd: added timeouts to at24xx eeprom driver --- nuttx/drivers/mtd/at24xx.c | 15 +++++++++++++-- 1 file changed, 13 insertions(+), 2 deletions(-) (limited to 'nuttx') diff --git a/nuttx/drivers/mtd/at24xx.c b/nuttx/drivers/mtd/at24xx.c index 2eb7c9af0..8d89f9bd2 100644 --- a/nuttx/drivers/mtd/at24xx.c +++ b/nuttx/drivers/mtd/at24xx.c @@ -230,12 +230,17 @@ static ssize_t at24c_bread(FAR struct mtd_dev_s *dev, off_t startblock, uint8_t buf[2]; buf[1] = offset & 0xff; buf[0] = (offset >> 8) & 0xff; + uint8_t tries = 100; - while (I2C_WRITE(priv->dev, buf, 2) < 0) + while (I2C_WRITE(priv->dev, buf, 2) < 0 && tries-- > 0) { fvdbg("wait\n"); usleep(1000); } + if (tries == 0) { + fdbg("timed out reading at offset %u\n", (unsigned)offset); + return 0; + } I2C_READ(priv->dev, buffer, priv->pagesize); startblock++; @@ -286,11 +291,17 @@ static ssize_t at24c_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_t while (blocksleft-- > 0) { uint16_t offset = startblock * priv->pagesize; - while (I2C_WRITE(priv->dev, (uint8_t *)&offset, 2) < 0) + uint8_t tries = 100; + + while (I2C_WRITE(priv->dev, (uint8_t *)&offset, 2) < 0 && tries-- > 0) { fvdbg("wait\n"); usleep(1000); } + if (tries == 0) { + fdbg("timed out writing at offset %u\n", (unsigned)offset); + return 0; + } buf[1] = offset & 0xff; buf[0] = (offset >> 8) & 0xff; -- cgit v1.2.3 From b11d7d4de316444f72e81762446d8b1d18078b0c Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 16 Jan 2014 16:58:25 +1100 Subject: mtd: added MTDIOC_SETSPEED ioctl allows setting of SPI bus speed --- nuttx/drivers/mtd/ramtron.c | 41 +++++++++++++++++++++-------------------- nuttx/include/nuttx/fs/ioctl.h | 2 ++ 2 files changed, 23 insertions(+), 20 deletions(-) (limited to 'nuttx') diff --git a/nuttx/drivers/mtd/ramtron.c b/nuttx/drivers/mtd/ramtron.c index 44716cbe8..e7440cc46 100644 --- a/nuttx/drivers/mtd/ramtron.c +++ b/nuttx/drivers/mtd/ramtron.c @@ -40,13 +40,6 @@ * - additional non-jedec standard device: FM25H20 * must be enabled with the CONFIG_RAMTRON_FRAM_NON_JEDEC=y * - * NOTE: - * - frequency is fixed to desired max by RAMTRON_INIT_CLK_MAX - * if new devices with different speed arrive, then SETFREQUENCY() - * needs to handle freq changes and INIT_CLK_MAX must be reduced - * to fit all devices. Note that STM32_SPI driver is prone to - * too high freq. parameters and limit it within physical constraints. - * * TODO: * - add support for sleep * - add support for faster read FSTRD command @@ -146,6 +139,7 @@ struct ramtron_dev_s uint8_t pageshift; uint16_t nsectors; uint32_t npages; + uint32_t speed; // overridable via ioctl const struct ramtron_parts_s *part; /* part instance */ }; @@ -154,10 +148,11 @@ struct ramtron_dev_s ************************************************************************************/ /* Defines the initial speed compatible with all devices. In case of RAMTRON - * the defined devices within the part list have all the same speed. + * the defined devices within the part list have all the same + * speed. */ -#define RAMTRON_INIT_CLK_MAX 40000000UL +#define RAMTRON_INIT_CLK_MAX 11*1000*1000UL static struct ramtron_parts_s ramtron_parts[] = { @@ -244,7 +239,7 @@ static struct ramtron_parts_s ramtron_parts[] = /* Helpers */ -static void ramtron_lock(FAR struct spi_dev_s *dev); +static void ramtron_lock(FAR struct ramtron_dev_s *priv); static inline void ramtron_unlock(FAR struct spi_dev_s *dev); static inline int ramtron_readid(struct ramtron_dev_s *priv); static int ramtron_waitwritecomplete(struct ramtron_dev_s *priv); @@ -275,7 +270,7 @@ static int ramtron_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg); * Name: ramtron_lock ************************************************************************************/ -static void ramtron_lock(FAR struct spi_dev_s *dev) +static void ramtron_lock(FAR struct ramtron_dev_s *priv) { /* On SPI busses where there are multiple devices, it will be necessary to * lock SPI to have exclusive access to the busses for a sequence of @@ -285,7 +280,7 @@ static void ramtron_lock(FAR struct spi_dev_s *dev) * the SPI buss. We will retain that exclusive access until the bus is unlocked. */ - (void)SPI_LOCK(dev, true); + (void)SPI_LOCK(priv->dev, true); /* After locking the SPI bus, the we also need call the setfrequency, setbits, and * setmode methods to make sure that the SPI is properly configured for the device. @@ -293,10 +288,10 @@ static void ramtron_lock(FAR struct spi_dev_s *dev) * state. */ - SPI_SETMODE(dev, SPIDEV_MODE3); - SPI_SETBITS(dev, 8); - - (void)SPI_SETFREQUENCY(dev, RAMTRON_INIT_CLK_MAX); + SPI_SETMODE(priv->dev, SPIDEV_MODE3); + SPI_SETBITS(priv->dev, 8); + + (void)SPI_SETFREQUENCY(priv->dev, priv->speed); } /************************************************************************************ @@ -321,7 +316,7 @@ static inline int ramtron_readid(struct ramtron_dev_s *priv) /* Lock the SPI bus, configure the bus, and select this FLASH part. */ - ramtron_lock(priv->dev); + ramtron_lock(priv); SPI_SELECT(priv->dev, SPIDEV_FLASH, true); /* Send the "Read ID (RDID)" command and read the first three ID bytes */ @@ -356,6 +351,7 @@ static inline int ramtron_readid(struct ramtron_dev_s *priv) priv->nsectors = priv->part->size / (1 << RAMTRON_EMULATE_SECTOR_SHIFT); priv->pageshift = RAMTRON_EMULATE_PAGE_SHIFT; priv->npages = priv->part->size / (1 << RAMTRON_EMULATE_PAGE_SHIFT); + priv->speed = priv->part->speed; return OK; } @@ -542,9 +538,8 @@ static ssize_t ramtron_bwrite(FAR struct mtd_dev_s *dev, off_t startblock, size_ /* Lock the SPI bus and write each page to FLASH */ - int ret = nblocks; + ramtron_lock(priv); - ramtron_lock(priv->dev); while (blocksleft-- > 0) { if (ramtron_pagewrite(priv, buffer, startblock)) { @@ -572,7 +567,7 @@ static ssize_t ramtron_read(FAR struct mtd_dev_s *dev, off_t offset, size_t nbyt /* Lock the SPI bus and select this FLASH part */ - ramtron_lock(priv->dev); + ramtron_lock(priv); SPI_SELECT(priv->dev, SPIDEV_FLASH, true); /* Send "Read from Memory " instruction */ @@ -651,6 +646,11 @@ static int ramtron_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg) fvdbg("BULDERASE: Makes no sense in ramtron. Let's confirm operation as OK\n"); ret = OK; break; + + case MTDIOC_SETSPEED: + priv->speed = (unsigned long)arg; + fvdbg("set bus speed to %lu\n", (unsigned long)priv->speed); + break; case MTDIOC_XIPBASE: default: @@ -702,6 +702,7 @@ FAR struct mtd_dev_s *ramtron_initialize(FAR struct spi_dev_s *dev) priv->mtd.read = ramtron_read; priv->mtd.ioctl = ramtron_ioctl; priv->dev = dev; + priv->speed = RAMTRON_INIT_CLK_MAX; /* Deselect the FLASH */ diff --git a/nuttx/include/nuttx/fs/ioctl.h b/nuttx/include/nuttx/fs/ioctl.h index e36083253..09a6c2e1a 100644 --- a/nuttx/include/nuttx/fs/ioctl.h +++ b/nuttx/include/nuttx/fs/ioctl.h @@ -204,6 +204,8 @@ * of device memory */ #define MTDIOC_BULKERASE _MTDIOC(0x0003) /* IN: None * OUT: None */ +#define MTDIOC_SETSPEED _MTDIOC(0x0004) /* IN: (unsigned long) desired bus speed + * OUT: None */ /* NuttX ARP driver ioctl definitions (see netinet/arp.h) *******************/ -- cgit v1.2.3 From f05aeae293ac93e3ed91e3db3b548a35bc21c172 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 16 Jan 2014 08:24:37 +0100 Subject: Range checking on clock argument for RAMTRON set speed IOCTL --- nuttx/drivers/mtd/ramtron.c | 15 +++++++++++---- 1 file changed, 11 insertions(+), 4 deletions(-) (limited to 'nuttx') diff --git a/nuttx/drivers/mtd/ramtron.c b/nuttx/drivers/mtd/ramtron.c index e7440cc46..7d4c66058 100644 --- a/nuttx/drivers/mtd/ramtron.c +++ b/nuttx/drivers/mtd/ramtron.c @@ -152,7 +152,8 @@ struct ramtron_dev_s * speed. */ -#define RAMTRON_INIT_CLK_MAX 11*1000*1000UL +#define RAMTRON_CLK_MAX 40*1000*1000UL +#define RAMTRON_INIT_CLK_DEFAULT 11*1000*1000UL static struct ramtron_parts_s ramtron_parts[] = { @@ -648,9 +649,15 @@ static int ramtron_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg) break; case MTDIOC_SETSPEED: - priv->speed = (unsigned long)arg; - fvdbg("set bus speed to %lu\n", (unsigned long)priv->speed); + if ((unsigned long)arg > 0 && (unsigned long arg) <= RAMTRON_CLK_MAX) { + priv->speed = (unsigned long)arg; + fvdbg("set bus speed to %lu\n", (unsigned long)priv->speed); + } else { + ret = -EINVAL; /* Bad argument */ + fvdbg("inval arg"); + } break; + } case MTDIOC_XIPBASE: default: @@ -702,7 +709,7 @@ FAR struct mtd_dev_s *ramtron_initialize(FAR struct spi_dev_s *dev) priv->mtd.read = ramtron_read; priv->mtd.ioctl = ramtron_ioctl; priv->dev = dev; - priv->speed = RAMTRON_INIT_CLK_MAX; + priv->speed = RAMTRON_INIT_CLK_DEFAULT; /* Deselect the FLASH */ -- cgit v1.2.3 From 602a2a6522b0a92fdcd1377ce2fc70016e48d833 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 16 Jan 2014 08:56:07 +0100 Subject: Ramtron compile fix --- nuttx/drivers/mtd/ramtron.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'nuttx') diff --git a/nuttx/drivers/mtd/ramtron.c b/nuttx/drivers/mtd/ramtron.c index 7d4c66058..ab025a35c 100644 --- a/nuttx/drivers/mtd/ramtron.c +++ b/nuttx/drivers/mtd/ramtron.c @@ -649,7 +649,7 @@ static int ramtron_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg) break; case MTDIOC_SETSPEED: - if ((unsigned long)arg > 0 && (unsigned long arg) <= RAMTRON_CLK_MAX) { + if ((unsigned long)arg > 0 && (unsigned long)arg <= RAMTRON_CLK_MAX) { priv->speed = (unsigned long)arg; fvdbg("set bus speed to %lu\n", (unsigned long)priv->speed); } else { -- cgit v1.2.3 From bfbccf65227026c961c22612f84555dcd48588ac Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Thu, 16 Jan 2014 08:58:48 +0100 Subject: More compile fixes for RAMTRON device --- nuttx/drivers/mtd/ramtron.c | 1 + 1 file changed, 1 insertion(+) (limited to 'nuttx') diff --git a/nuttx/drivers/mtd/ramtron.c b/nuttx/drivers/mtd/ramtron.c index ab025a35c..b53c7829b 100644 --- a/nuttx/drivers/mtd/ramtron.c +++ b/nuttx/drivers/mtd/ramtron.c @@ -649,6 +649,7 @@ static int ramtron_ioctl(FAR struct mtd_dev_s *dev, int cmd, unsigned long arg) break; case MTDIOC_SETSPEED: + { if ((unsigned long)arg > 0 && (unsigned long)arg <= RAMTRON_CLK_MAX) { priv->speed = (unsigned long)arg; fvdbg("set bus speed to %lu\n", (unsigned long)priv->speed); -- cgit v1.2.3 From d1f13c1d052fbfeb5854d4a45bfef8e2d3b7c60e Mon Sep 17 00:00:00 2001 From: none Date: Wed, 22 Jan 2014 21:58:21 -0800 Subject: Assembler changes with the gcc-47 distribution from ARM mean that we need to be explicit about branch sizes; one or more of the wide branch opcodes results in bad table branching. --- nuttx/arch/arm/src/armv7-m/up_memcpy.S | 32 ++++++++++++++++---------------- 1 file changed, 16 insertions(+), 16 deletions(-) (limited to 'nuttx') diff --git a/nuttx/arch/arm/src/armv7-m/up_memcpy.S b/nuttx/arch/arm/src/armv7-m/up_memcpy.S index a154cab61..c6553730d 100644 --- a/nuttx/arch/arm/src/armv7-m/up_memcpy.S +++ b/nuttx/arch/arm/src/armv7-m/up_memcpy.S @@ -152,7 +152,7 @@ memcpy: /* Quickly check for very short copies */ cmp r2, #4 - blt MEM_DataCopyBytes + blt.n MEM_DataCopyBytes and r14, r0, #3 /* Get destination alignment bits */ bfi r14, r1, #2, #2 /* Get source alignment bits */ @@ -199,7 +199,7 @@ MEM_DataCopy0: /* Check for short word-aligned copy */ cmp r2, #0x28 - blt MEM_DataCopy0_2 + blt.n MEM_DataCopy0_2 /* Bulk copy loop */ @@ -208,7 +208,7 @@ MEM_DataCopy0_1: stmia r0!, {r3-r12} sub r2, r2, #0x28 cmp r2, #0x28 - bge MEM_DataCopy0_1 + bge.n MEM_DataCopy0_1 /* Copy remaining long words */ @@ -224,28 +224,28 @@ MEM_DataCopy0_2: MEM_LongCopyJump: ldr.w r3, [r1], #0x04 /* 4 bytes remain */ str.w r3, [r0], #0x04 - b MEM_LongCopyEnd + b.n MEM_LongCopyEnd ldmia.w r1!, {r3-r4} /* 8 bytes remain */ stmia.w r0!, {r3-r4} - b MEM_LongCopyEnd + b.n MEM_LongCopyEnd ldmia.w r1!, {r3-r5} /* 12 bytes remain */ stmia.w r0!, {r3-r5} - b MEM_LongCopyEnd + b.n MEM_LongCopyEnd ldmia.w r1!, {r3-r6} /* 16 bytes remain */ stmia.w r0!, {r3-r6} - b MEM_LongCopyEnd + b.n MEM_LongCopyEnd ldmia.w r1!, {r3-r7} /* 20 bytes remain */ stmia.w r0!, {r3-r7} - b MEM_LongCopyEnd + b.n MEM_LongCopyEnd ldmia.w r1!, {r3-r8} /* 24 bytes remain */ stmia.w r0!, {r3-r8} - b MEM_LongCopyEnd + b.n MEM_LongCopyEnd ldmia.w r1!, {r3-r9} /* 28 bytes remain */ stmia.w r0!, {r3-r9} - b MEM_LongCopyEnd + b.n MEM_LongCopyEnd ldmia.w r1!, {r3-r10} /* 32 bytes remain */ stmia.w r0!, {r3-r10} - b MEM_LongCopyEnd + b.n MEM_LongCopyEnd ldmia.w r1!, {r3-r11} /* 36 bytes remain */ stmia.w r0!, {r3-r11} @@ -308,7 +308,7 @@ MEM_DataCopy13: MEM_DataCopy2: cmp r2, #0x28 - blt MEM_DataCopy2_1 + blt.n MEM_DataCopy2_1 /* Save regs */ @@ -345,18 +345,18 @@ MEM_DataCopy2_2: sub r2, r2, #0x28 cmp r2, #0x28 - bge MEM_DataCopy2_2 + bge.n MEM_DataCopy2_2 pop {r4-r12} MEM_DataCopy2_1: /* Read longs and write 2 x half words */ cmp r2, #4 - blt MEM_DataCopyBytes + blt.n MEM_DataCopyBytes ldr r3, [r1], #0x04 strh r3, [r0], #0x02 lsr r3, r3, #0x10 strh r3, [r0], #0x02 sub r2, r2, #0x04 - b MEM_DataCopy2 + b.n MEM_DataCopy2 /* Bits: Src=01, Dst=00 - Byte before half word to long * Bits: Src=01, Dst=10 - Byte before half word to half word @@ -410,7 +410,7 @@ MEM_DataCopy3: lsr r3, r3, #0x10 strb r3, [r0], #0x01 sub r2, r2, #0x04 - b MEM_DataCopy3 + b.w MEM_DataCopy3 .size memcpy, .-memcpy .end -- cgit v1.2.3 From ee7804d1f24692ab22c7da5b6db6cb0b61a4c041 Mon Sep 17 00:00:00 2001 From: none Date: Thu, 23 Jan 2014 09:37:37 -0800 Subject: typo, wide branch should be narrow --- nuttx/arch/arm/src/armv7-m/up_memcpy.S | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) (limited to 'nuttx') diff --git a/nuttx/arch/arm/src/armv7-m/up_memcpy.S b/nuttx/arch/arm/src/armv7-m/up_memcpy.S index c6553730d..ea267f78f 100644 --- a/nuttx/arch/arm/src/armv7-m/up_memcpy.S +++ b/nuttx/arch/arm/src/armv7-m/up_memcpy.S @@ -410,7 +410,7 @@ MEM_DataCopy3: lsr r3, r3, #0x10 strb r3, [r0], #0x01 sub r2, r2, #0x04 - b.w MEM_DataCopy3 + b.n MEM_DataCopy3 .size memcpy, .-memcpy .end -- cgit v1.2.3 From 454523bebfbaca9a77ba9827ba11454caffaa31d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 10 Feb 2014 12:08:20 +1100 Subject: stm32_serial: fixed spelling of FLOWCONTROL config option in stm32 serial code this fixes flow control on pixhawk --- nuttx/arch/arm/src/stm32/stm32_serial.c | 40 ++++++++++++++++----------------- 1 file changed, 20 insertions(+), 20 deletions(-) (limited to 'nuttx') diff --git a/nuttx/arch/arm/src/stm32/stm32_serial.c b/nuttx/arch/arm/src/stm32/stm32_serial.c index e2a0da226..89c31addc 100644 --- a/nuttx/arch/arm/src/stm32/stm32_serial.c +++ b/nuttx/arch/arm/src/stm32/stm32_serial.c @@ -519,10 +519,10 @@ static struct up_dev_s g_usart1priv = .usartbase = STM32_USART1_BASE, .tx_gpio = GPIO_USART1_TX, .rx_gpio = GPIO_USART1_RX, -#if defined(CONFIG_SERIAL_OFLOWCONROL) && defined(CONFIG_USART1_OFLOWCONTROL) +#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_USART1_OFLOWCONTROL) .cts_gpio = GPIO_USART1_CTS, #endif -#if defined(CONFIG_SERIAL_IFLOWCONROL) && defined(CONFIG_USART1_IFLOWCONTROL) +#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_USART1_IFLOWCONTROL) .rts_gpio = GPIO_USART1_RTS, #endif #ifdef CONFIG_USART1_RXDMA @@ -585,10 +585,10 @@ static struct up_dev_s g_usart2priv = .usartbase = STM32_USART2_BASE, .tx_gpio = GPIO_USART2_TX, .rx_gpio = GPIO_USART2_RX, -#if defined(CONFIG_SERIAL_OFLOWCONROL) && defined(CONFIG_USART2_OFLOWCONTROL) +#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_USART2_OFLOWCONTROL) .cts_gpio = GPIO_USART2_CTS, #endif -#if defined(CONFIG_SERIAL_IFLOWCONROL) && defined(CONFIG_USART2_IFLOWCONTROL) +#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_USART2_IFLOWCONTROL) .rts_gpio = GPIO_USART2_RTS, #endif #ifdef CONFIG_USART2_RXDMA @@ -651,10 +651,10 @@ static struct up_dev_s g_usart3priv = .usartbase = STM32_USART3_BASE, .tx_gpio = GPIO_USART3_TX, .rx_gpio = GPIO_USART3_RX, -#if defined(CONFIG_SERIAL_OFLOWCONROL) && defined(CONFIG_USART3_OFLOWCONTROL) +#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_USART3_OFLOWCONTROL) .cts_gpio = GPIO_USART3_CTS, #endif -#if defined(CONFIG_SERIAL_IFLOWCONROL) && defined(CONFIG_USART3_IFLOWCONTROL) +#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_USART3_IFLOWCONTROL) .rts_gpio = GPIO_USART3_RTS, #endif #ifdef CONFIG_USART3_RXDMA @@ -717,10 +717,10 @@ static struct up_dev_s g_uart4priv = .usartbase = STM32_UART4_BASE, .tx_gpio = GPIO_UART4_TX, .rx_gpio = GPIO_UART4_RX, -#ifdef CONFIG_SERIAL_OFLOWCONROL +#ifdef CONFIG_SERIAL_OFLOWCONTROL .cts_gpio = 0, #endif -#ifdef CONFIG_SERIAL_IFLOWCONROL +#ifdef CONFIG_SERIAL_IFLOWCONTROL .rts_gpio = 0, #endif #ifdef CONFIG_UART4_RXDMA @@ -783,10 +783,10 @@ static struct up_dev_s g_uart5priv = .usartbase = STM32_UART5_BASE, .tx_gpio = GPIO_UART5_TX, .rx_gpio = GPIO_UART5_RX, -#ifdef CONFIG_SERIAL_OFLOWCONROL +#ifdef CONFIG_SERIAL_OFLOWCONTROL .cts_gpio = 0, #endif -#ifdef CONFIG_SERIAL_IFLOWCONROL +#ifdef CONFIG_SERIAL_IFLOWCONTROL .rts_gpio = 0, #endif #ifdef CONFIG_UART5_RXDMA @@ -849,10 +849,10 @@ static struct up_dev_s g_usart6priv = .usartbase = STM32_USART6_BASE, .tx_gpio = GPIO_USART6_TX, .rx_gpio = GPIO_USART6_RX, -#if defined(CONFIG_SERIAL_OFLOWCONROL) && defined(CONFIG_USART6_OFLOWCONTROL) +#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_USART6_OFLOWCONTROL) .cts_gpio = GPIO_USART6_CTS, #endif -#if defined(CONFIG_SERIAL_IFLOWCONROL) && defined(CONFIG_USART6_IFLOWCONTROL) +#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_USART6_IFLOWCONTROL) .rts_gpio = GPIO_USART6_RTS, #endif #ifdef CONFIG_USART6_RXDMA @@ -909,10 +909,10 @@ static struct up_dev_s g_uart7priv = .usartbase = STM32_UART7_BASE, .tx_gpio = GPIO_UART7_TX, .rx_gpio = GPIO_UART7_RX, -#if defined(CONFIG_SERIAL_OFLOWCONROL) && defined(CONFIG_USART7_OFLOWCONTROL) +#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_USART7_OFLOWCONTROL) .cts_gpio = GPIO_UART7_CTS, #endif -#if defined(CONFIG_SERIAL_IFLOWCONROL) && defined(CONFIG_USART7_IFLOWCONTROL) +#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_USART7_IFLOWCONTROL) .rts_gpio = GPIO_UART7_RTS, #endif #ifdef CONFIG_UART7_RXDMA @@ -969,10 +969,10 @@ static struct up_dev_s g_uart8priv = .usartbase = STM32_UART8_BASE, .tx_gpio = GPIO_UART8_TX, .rx_gpio = GPIO_UART8_RX, -#if defined(CONFIG_SERIAL_OFLOWCONROL) && defined(CONFIG_USART8_OFLOWCONTROL) +#if defined(CONFIG_SERIAL_OFLOWCONTROL) && defined(CONFIG_USART8_OFLOWCONTROL) .cts_gpio = GPIO_UART8_CTS, #endif -#if defined(CONFIG_SERIAL_IFLOWCONROL) && defined(CONFIG_USART8_IFLOWCONTROL) +#if defined(CONFIG_SERIAL_IFLOWCONTROL) && defined(CONFIG_USART8_IFLOWCONTROL) .rts_gpio = GPIO_UART8_RTS, #endif #ifdef CONFIG_UART8_RXDMA @@ -1329,14 +1329,14 @@ static int up_setup(struct uart_dev_s *dev) stm32_configgpio(priv->tx_gpio); stm32_configgpio(priv->rx_gpio); -#ifdef CONFIG_SERIAL_OFLOWCONROL +#ifdef CONFIG_SERIAL_OFLOWCONTROL if (priv->cts_gpio != 0) { stm32_configgpio(priv->cts_gpio); } #endif -#ifdef CONFIG_SERIAL_IFLOWCONROL +#ifdef CONFIG_SERIAL_IFLOWCONTROL if (priv->rts_gpio != 0) { stm32_configgpio(priv->rts_gpio); @@ -1819,10 +1819,10 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg) /* Perform some sanity checks before accepting any changes */ if (((termiosp->c_cflag & CSIZE) != CS8) -#ifdef CONFIG_SERIAL_IFLOWCONROL +#ifdef CONFIG_SERIAL_IFLOWCONTROL || ((termiosp->c_cflag & CCTS_OFLOW) && (priv->cts_gpio == 0)) #endif -#ifdef CONFIG_SERIAL_IFLOWCONROL +#ifdef CONFIG_SERIAL_IFLOWCONTROL || ((termiosp->c_cflag & CRTS_IFLOW) && (priv->rts_gpio == 0)) #endif ) -- cgit v1.2.3