mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fixed warnings
This commit is contained in:
parent
df4cb00970
commit
0ffe2e75be
|
@ -51,6 +51,7 @@
|
||||||
#include "flash.h"
|
#include "flash.h"
|
||||||
#include "hal.h"
|
#include "hal.h"
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
#include "stm32_util.h"
|
||||||
|
|
||||||
// #pragma GCC optimize("O0")
|
// #pragma GCC optimize("O0")
|
||||||
|
|
||||||
|
@ -379,7 +380,7 @@ bool stm32_flash_erasepage(uint32_t page)
|
||||||
|
|
||||||
stm32_flash_wait_idle();
|
stm32_flash_wait_idle();
|
||||||
|
|
||||||
stm32_cacheBufferInvalidate(stm32_flash_getpageaddr(page), stm32_flash_getpagesize(page));
|
stm32_cacheBufferInvalidate((void*)stm32_flash_getpageaddr(page), stm32_flash_getpagesize(page));
|
||||||
|
|
||||||
stm32_flash_lock();
|
stm32_flash_lock();
|
||||||
#if STM32_FLASH_DISABLE_ISR
|
#if STM32_FLASH_DISABLE_ISR
|
||||||
|
|
|
@ -119,98 +119,3 @@ __wrap_sscanf (const char *buf, const char *fmt, ...)
|
||||||
va_end (ap);
|
va_end (ap);
|
||||||
return (count);
|
return (count);
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(HAL_OS_FATFS_IO) && HAL_OS_FATFS_IO
|
|
||||||
static char *
|
|
||||||
_getbase(char *p, int *basep)
|
|
||||||
{
|
|
||||||
if (p[0] == '0') {
|
|
||||||
switch (p[1]) {
|
|
||||||
case 'x':
|
|
||||||
*basep = 16;
|
|
||||||
break;
|
|
||||||
case 't': case 'n':
|
|
||||||
*basep = 10;
|
|
||||||
break;
|
|
||||||
case 'o':
|
|
||||||
*basep = 8;
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
*basep = 10;
|
|
||||||
return (p);
|
|
||||||
}
|
|
||||||
return (p + 2);
|
|
||||||
}
|
|
||||||
*basep = 10;
|
|
||||||
return (p);
|
|
||||||
}
|
|
||||||
|
|
||||||
static int16_t
|
|
||||||
_atob (uint32_t *vp, char *p, int base)
|
|
||||||
{
|
|
||||||
uint32_t value, v1, v2;
|
|
||||||
char *q, tmp[20];
|
|
||||||
int digit;
|
|
||||||
|
|
||||||
if (p[0] == '0' && (p[1] == 'x' || p[1] == 'X')) {
|
|
||||||
base = 16;
|
|
||||||
p += 2;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (base == 16 && (q = strchr (p, '.')) != 0) {
|
|
||||||
if ((unsigned)(q - p) > (unsigned)(sizeof(tmp) - 1))
|
|
||||||
return (0);
|
|
||||||
|
|
||||||
strncpy (tmp, p, q - p);
|
|
||||||
tmp[q - p] = '\0';
|
|
||||||
if (!_atob (&v1, tmp, 16))
|
|
||||||
return (0);
|
|
||||||
|
|
||||||
q++;
|
|
||||||
if (strchr (q, '.'))
|
|
||||||
return (0);
|
|
||||||
|
|
||||||
if (!_atob (&v2, q, 16))
|
|
||||||
return (0);
|
|
||||||
*vp = (v1 << 16) + v2;
|
|
||||||
return (1);
|
|
||||||
}
|
|
||||||
|
|
||||||
value = *vp = 0;
|
|
||||||
for (; *p; p++) {
|
|
||||||
if (*p >= '0' && *p <= '9')
|
|
||||||
digit = *p - '0';
|
|
||||||
else if (*p >= 'a' && *p <= 'f')
|
|
||||||
digit = *p - 'a' + 10;
|
|
||||||
else if (*p >= 'A' && *p <= 'F')
|
|
||||||
digit = *p - 'A' + 10;
|
|
||||||
else
|
|
||||||
return (0);
|
|
||||||
|
|
||||||
if (digit >= base)
|
|
||||||
return (0);
|
|
||||||
value *= base;
|
|
||||||
value += digit;
|
|
||||||
}
|
|
||||||
*vp = value;
|
|
||||||
return (1);
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
|
||||||
* atob(vp,p,base)
|
|
||||||
* converts p to binary result in vp, rtn 1 on success
|
|
||||||
*/
|
|
||||||
static int16_t atob(uint32_t *vp, char *p, int base)
|
|
||||||
{
|
|
||||||
uint32_t v;
|
|
||||||
|
|
||||||
if (base == 0)
|
|
||||||
p = _getbase (p, &base);
|
|
||||||
if (_atob (&v, p, base)) {
|
|
||||||
*vp = v;
|
|
||||||
return (1);
|
|
||||||
}
|
|
||||||
return (0);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue