mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 01:48:29 -04:00
HAL_ChibiOS: fixed build warnings
This commit is contained in:
parent
bc96cb8a19
commit
86189393a7
@ -109,6 +109,7 @@ along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|||||||
|
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
#include "posix.h"
|
#include "posix.h"
|
||||||
|
#include "stdio.h"
|
||||||
#undef strerror_r
|
#undef strerror_r
|
||||||
|
|
||||||
/// Note: fdevopen assigns stdin,stdout,stderr
|
/// Note: fdevopen assigns stdin,stdout,stderr
|
||||||
@ -231,7 +232,6 @@ fgetc(FILE *stream)
|
|||||||
} else {
|
} else {
|
||||||
if(!stream->get)
|
if(!stream->get)
|
||||||
{
|
{
|
||||||
printf("fgetc stream->get NULL\n");
|
|
||||||
return(EOF);
|
return(EOF);
|
||||||
}
|
}
|
||||||
// get character from device or file
|
// get character from device or file
|
||||||
@ -266,13 +266,6 @@ fputc(int c, FILE *stream)
|
|||||||
errno = 0;
|
errno = 0;
|
||||||
int ret;
|
int ret;
|
||||||
|
|
||||||
if(stream == NULL)
|
|
||||||
{
|
|
||||||
errno = EBADF; // Bad File Number
|
|
||||||
return(EOF);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
if(stream != stdout && stream != stderr)
|
if(stream != stdout && stream != stderr)
|
||||||
{
|
{
|
||||||
return(fatfs_putc(c,stream));
|
return(fatfs_putc(c,stream));
|
||||||
@ -291,7 +284,6 @@ fputc(int c, FILE *stream)
|
|||||||
} else {
|
} else {
|
||||||
if(!stream->put)
|
if(!stream->put)
|
||||||
{
|
{
|
||||||
printf("fputc stream->put NULL\n");
|
|
||||||
return(EOF);
|
return(EOF);
|
||||||
}
|
}
|
||||||
ret = stream->put(c, stream);
|
ret = stream->put(c, stream);
|
||||||
@ -1225,7 +1217,8 @@ ssize_t write(int fd, const void *buf, size_t count)
|
|||||||
|
|
||||||
FILE * __wrap_freopen ( const char * filename, const char * mode, FILE * stream )
|
FILE * __wrap_freopen ( const char * filename, const char * mode, FILE * stream )
|
||||||
{
|
{
|
||||||
int ret = close(stream);
|
int fn = fileno(stream);
|
||||||
|
int ret = close(fn);
|
||||||
if (ret < 0) {
|
if (ret < 0) {
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
@ -1411,7 +1404,7 @@ int utime(const char *filename, const struct utimbuf *times)
|
|||||||
|
|
||||||
int64_t fs_getfree() {
|
int64_t fs_getfree() {
|
||||||
FATFS *fs;
|
FATFS *fs;
|
||||||
DWORD fre_clust, fre_sect, tot_sect;
|
DWORD fre_clust, fre_sect;
|
||||||
|
|
||||||
|
|
||||||
/* Get volume information and free clusters of drive 1 */
|
/* Get volume information and free clusters of drive 1 */
|
||||||
@ -1426,7 +1419,7 @@ int64_t fs_getfree() {
|
|||||||
|
|
||||||
int64_t fs_gettotal() {
|
int64_t fs_gettotal() {
|
||||||
FATFS *fs;
|
FATFS *fs;
|
||||||
DWORD fre_clust, fre_sect, tot_sect;
|
DWORD fre_clust, tot_sect;
|
||||||
|
|
||||||
|
|
||||||
/* Get volume information and free clusters of drive 1 */
|
/* Get volume information and free clusters of drive 1 */
|
||||||
@ -2238,7 +2231,6 @@ int fatfs_to_fileno(FIL *fh)
|
|||||||
*/
|
*/
|
||||||
static time_t replace_mktime(const struct tm *t)
|
static time_t replace_mktime(const struct tm *t)
|
||||||
{
|
{
|
||||||
struct tm *u;
|
|
||||||
time_t epoch = 0;
|
time_t epoch = 0;
|
||||||
int n;
|
int n;
|
||||||
int mon [] = { 31, 28, 31, 30, 31, 30, 31, 31, 30, 31, 30, 31 }, y, m, i;
|
int mon [] = { 31, 28, 31, 30, 31, 30, 31, 31, 30, 31, 30, 31 }, y, m, i;
|
||||||
|
@ -28,6 +28,7 @@
|
|||||||
#include <hal.h>
|
#include <hal.h>
|
||||||
#include <memstreams.h>
|
#include <memstreams.h>
|
||||||
#include <chprintf.h>
|
#include <chprintf.h>
|
||||||
|
#include <ctype.h>
|
||||||
#include "stdio.h"
|
#include "stdio.h"
|
||||||
|
|
||||||
int vsnprintf(char *str, size_t size, const char *fmt, va_list ap)
|
int vsnprintf(char *str, size_t size, const char *fmt, va_list ap)
|
||||||
@ -236,7 +237,8 @@ atob(uint32_t *vp, char *p, int base)
|
|||||||
int
|
int
|
||||||
vsscanf (const char *buf, const char *s, va_list ap)
|
vsscanf (const char *buf, const char *s, va_list ap)
|
||||||
{
|
{
|
||||||
int count, noassign, width, base, lflag;
|
int count, noassign, base=0, lflag;
|
||||||
|
uint32_t width;
|
||||||
const char *tc;
|
const char *tc;
|
||||||
char *t, tmp[MAXLN];
|
char *t, tmp[MAXLN];
|
||||||
|
|
||||||
@ -318,6 +320,8 @@ vsscanf (const char *buf, const char *s, va_list ap)
|
|||||||
return (count);
|
return (count);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static int vfscanf(FILE *stream, const char *fmt, va_list ap);
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* fscanf(stream,fmt,va_alist)
|
* fscanf(stream,fmt,va_alist)
|
||||||
*/
|
*/
|
||||||
|
Loading…
Reference in New Issue
Block a user