From f4e2d462f766a33b3445a7390783f0a0fb509930 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Tue, 25 May 2021 01:55:54 +0200 Subject: [PATCH] AP_MSP: Telem_Backend: do not round vertical speed to 1m/s --- libraries/AP_MSP/AP_MSP_Telem_Backend.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp b/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp index af28097e9d..6240f7779c 100644 --- a/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp +++ b/libraries/AP_MSP/AP_MSP_Telem_Backend.cpp @@ -820,7 +820,7 @@ MSPCommandResult AP_MSP_Telem_Backend::msp_process_out_altitude(sbuf_t *dst) update_home_pos(home_state); sbuf_write_u32(dst, home_state.rel_altitude_cm); // relative altitude cm - sbuf_write_u16(dst, (int16_t)get_vspeed_ms() * 100); // climb rate cm/s + sbuf_write_u16(dst, int16_t(get_vspeed_ms() * 100)); // climb rate cm/s return MSP_RESULT_ACK; }