mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
desktop: be more careful with signed/unsigned in DataFlash
This commit is contained in:
parent
c2082fdd7b
commit
997091e0d6
@ -237,22 +237,22 @@ byte DataFlash_Class::ReadByte()
|
|||||||
|
|
||||||
int16_t DataFlash_Class::ReadInt()
|
int16_t DataFlash_Class::ReadInt()
|
||||||
{
|
{
|
||||||
int16_t result;
|
uint16_t result;
|
||||||
|
|
||||||
result = ReadByte(); // High byte
|
result = ReadByte(); // High byte
|
||||||
result = (result<<8) | ReadByte(); // Low byte
|
result = (result<<8) | ReadByte(); // Low byte
|
||||||
return result;
|
return (int16_t)result;
|
||||||
}
|
}
|
||||||
|
|
||||||
int32_t DataFlash_Class::ReadLong()
|
int32_t DataFlash_Class::ReadLong()
|
||||||
{
|
{
|
||||||
int32_t result;
|
uint32_t result;
|
||||||
|
|
||||||
result = ReadByte(); // First byte
|
result = ReadByte(); // First byte
|
||||||
result = (result<<8) | ReadByte();
|
result = (result<<8) | ReadByte();
|
||||||
result = (result<<8) | ReadByte();
|
result = (result<<8) | ReadByte();
|
||||||
result = (result<<8) | ReadByte(); // Last byte
|
result = (result<<8) | ReadByte(); // Last byte
|
||||||
return result;
|
return (int32_t)result;
|
||||||
}
|
}
|
||||||
|
|
||||||
// make one instance for the user to use
|
// make one instance for the user to use
|
||||||
|
Loading…
Reference in New Issue
Block a user