From b8630d55b8701dadbaf50c023be38df6c4a65b38 Mon Sep 17 00:00:00 2001 From: Ryan Friedman Date: Sat, 23 Mar 2024 18:11:13 -0600 Subject: [PATCH] AP_HAL: Fix incorrect return type * This caused position quantization errors in the MicroStrain7 Signed-off-by: Ryan Friedman --- libraries/AP_HAL/utility/sparse-endian.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL/utility/sparse-endian.h b/libraries/AP_HAL/utility/sparse-endian.h index ee594fe8ea071..f562e1166dca0 100644 --- a/libraries/AP_HAL/utility/sparse-endian.h +++ b/libraries/AP_HAL/utility/sparse-endian.h @@ -102,8 +102,8 @@ static inline uint64_t be64toh_ptr(const uint8_t *p) { return (uint64_t) p[7] | static inline float be32tofloat_ptr(const uint8_t *p) { return int32_to_float_le(be32toh_ptr(p)); } static inline float be32tofloat_ptr(const uint8_t *p, const uint8_t offset) { return be32tofloat_ptr(&p[offset]); } #ifdef ALLOW_DOUBLE_MATH_FUNCTIONS -static inline float be64todouble_ptr(const uint8_t *p) { return uint64_to_double_le(be64toh_ptr(p)); } -static inline float be64todouble_ptr(const uint8_t *p, const uint8_t offset) { return be64todouble_ptr(&p[offset]); } +static inline double be64todouble_ptr(const uint8_t *p) { return uint64_to_double_le(be64toh_ptr(p)); } +static inline double be64todouble_ptr(const uint8_t *p, const uint8_t offset) { return be64todouble_ptr(&p[offset]); } #endif static inline void put_le16_ptr(uint8_t *p, uint16_t v) { p[0] = (v&0xFF); p[1] = (v>>8); }