mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 02:33:58 -04:00
AP_Math: add get_twos_complement() from betaflight
This commit is contained in:
parent
1b9b24e347
commit
fba40313ce
@ -566,3 +566,15 @@ double uint64_to_double_le(const uint64_t& value)
|
||||
memcpy(&out, &value, sizeof(out));
|
||||
return out;
|
||||
}
|
||||
|
||||
/*
|
||||
get a twos-complement value from the first 'length' bits of a uint32_t
|
||||
With thanks to betaflight
|
||||
*/
|
||||
int32_t get_twos_complement(uint32_t raw, uint8_t length)
|
||||
{
|
||||
if (raw & ((int)1 << (length - 1))) {
|
||||
return ((int32_t)raw) - ((int32_t)1 << length);
|
||||
}
|
||||
return raw;
|
||||
}
|
||||
|
@ -396,3 +396,9 @@ float int32_to_float_le(const uint32_t& value) WARN_IF_UNUSED;
|
||||
Convert from uint64_t to double without breaking Wstrict-aliasing due to type punning
|
||||
*/
|
||||
double uint64_to_double_le(const uint64_t& value) WARN_IF_UNUSED;
|
||||
|
||||
/*
|
||||
get a twos-complement value from the first 'length' bits of a uint32_t
|
||||
With thanks to betaflight
|
||||
*/
|
||||
int32_t get_twos_complement(uint32_t raw, uint8_t length) WARN_IF_UNUSED;
|
||||
|
Loading…
Reference in New Issue
Block a user