Browse Source

GCS_MAVLink: allow control to be return to radio for higher-numbered RC_CHANNELS_OVERRIDE

zr-v5.1
Peter Barker 5 years ago committed by Peter Barker
parent
commit
b8827e6486
  1. 5
      libraries/GCS_MAVLink/GCS_Common.cpp

5
libraries/GCS_MAVLink/GCS_Common.cpp

@ -3136,7 +3136,10 @@ void GCS_MAVLINK::handle_rc_channels_override(const mavlink_message_t &msg) @@ -3136,7 +3136,10 @@ void GCS_MAVLINK::handle_rc_channels_override(const mavlink_message_t &msg)
// Per MAVLink spec a value of zero or UINT16_MAX means to
// ignore this field.
if (override_data[i] != 0 && override_data[i] != UINT16_MAX) {
RC_Channels::set_override(i, override_data[i], tnow);
// per the mavlink spec, a value of UINT16_MAX-1 means
// return the field to RC radio values:
const uint16_t value = override_data[i] == (UINT16_MAX-1) ? 0 : override_data[i];
RC_Channels::set_override(i, value, tnow);
}
}
}

Loading…
Cancel
Save