mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AP_HAL_Linux: fix warning due to limited storage
ardupilot/libraries/AP_HAL_Linux/Storage_FRAM.cpp: In member function 'int32_t Linux::Storage_FRAM::read(uint16_t, uint8_t*, uint16_t)': /home/lucas/p/dronecode/ardupilot/libraries/AP_HAL_Linux/Storage_FRAM.cpp:183:24: war ning: comparison is always false due to limited range of data type [-Wtype-limits] if(Buff[i-fptr]==-1){ ^
This commit is contained in:
parent
11b599bcd0
commit
b326856635
@ -5,6 +5,7 @@
|
||||
#include <sys/types.h>
|
||||
#include <sys/stat.h>
|
||||
#include <fcntl.h>
|
||||
#include <inttypes.h>
|
||||
#include <unistd.h>
|
||||
#include <errno.h>
|
||||
#include <stdio.h>
|
||||
@ -180,7 +181,7 @@ int32_t Storage_FRAM::read(uint16_t fd, uint8_t *Buff, uint16_t NumBytes){
|
||||
for(uint16_t i=fptr;i<(fptr+NumBytes);i++){
|
||||
Buff[i-fptr]= _register_read(i,OPCODE_READ);
|
||||
|
||||
if(Buff[i-fptr]==-1){
|
||||
if(Buff[i-fptr]==UINT8_MAX){
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user