From a24f039f1dfa629bd2f7febe39fc414f69681539 Mon Sep 17 00:00:00 2001 From: Oleg Kalachev Date: Wed, 31 Jan 2024 12:04:44 +0300 Subject: [PATCH] Fix RC_CHANNELS_SCALED inactive channel values They should be INT16_MAX not UINT16_MAX --- flix/mavlink.ino | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flix/mavlink.ino b/flix/mavlink.ino index 816534e..44e7005 100644 --- a/flix/mavlink.ino +++ b/flix/mavlink.ino @@ -44,7 +44,7 @@ void sendMavlink() { mavlink_msg_rc_channels_scaled_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, time, 0, controls[0] * 10000, controls[1] * 10000, controls[2] * 10000, controls[3] * 10000, controls[4] * 10000, controls[5] * 10000, - UINT16_MAX, UINT16_MAX, 255); + INT16_MAX, INT16_MAX, UINT8_MAX); sendMessage(&msg); float actuator[32];