Fix RC_CHANNELS_SCALED inactive channel values

They should be INT16_MAX not UINT16_MAX
This commit is contained in:
Oleg Kalachev 2024-01-31 12:04:44 +03:00
parent 6b52ad562b
commit a24f039f1d

View File

@ -44,7 +44,7 @@ void sendMavlink() {
mavlink_msg_rc_channels_scaled_pack(SYSTEM_ID, MAV_COMP_ID_AUTOPILOT1, &msg, time, 0, 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[0] * 10000, controls[1] * 10000, controls[2] * 10000,
controls[3] * 10000, controls[4] * 10000, controls[5] * 10000, controls[3] * 10000, controls[4] * 10000, controls[5] * 10000,
UINT16_MAX, UINT16_MAX, 255); INT16_MAX, INT16_MAX, UINT8_MAX);
sendMessage(&msg); sendMessage(&msg);
float actuator[32]; float actuator[32];