mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-27 02:58:31 -04:00
GCS_MAVLink: for high RC_CHANNELS_OVERRIDE channels zero means ignore the field
This commit is contained in:
parent
9b2ef4f6f1
commit
6f4bbd3f57
@ -3126,12 +3126,19 @@ void GCS_MAVLINK::handle_rc_channels_override(const mavlink_message_t &msg)
|
||||
packet.chan16_raw
|
||||
};
|
||||
|
||||
for (uint8_t i=0; i<ARRAY_SIZE(override_data); i++) {
|
||||
for (uint8_t i=0; i<8; i++) {
|
||||
// Per MAVLink spec a value of UINT16_MAX means to ignore this field.
|
||||
if (override_data[i] != UINT16_MAX) {
|
||||
RC_Channels::set_override(i, override_data[i], tnow);
|
||||
}
|
||||
}
|
||||
for (uint8_t i=8; i<ARRAY_SIZE(override_data); i++) {
|
||||
// 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);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// allow override of RC channel values for HIL or for complete GCS
|
||||
|
Loading…
Reference in New Issue
Block a user