Browse Source

AP_MSP: Telem_Backend: do not round vertical speed to 1m/s

zr-v5.1
Michel Pastor 4 years ago committed by Andrew Tridgell
parent
commit
f4e2d462f7
  1. 2
      libraries/AP_MSP/AP_MSP_Telem_Backend.cpp

2
libraries/AP_MSP/AP_MSP_Telem_Backend.cpp

@ -820,7 +820,7 @@ MSPCommandResult AP_MSP_Telem_Backend::msp_process_out_altitude(sbuf_t *dst) @@ -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;
}

Loading…
Cancel
Save