Skip to content

Commit 504372f

Browse files
MaEtUgRdagar
authored andcommitted
MAVLink: RC_CHANNELS_OVERRIDE generate correct RC channel count (PX4#11219)
* mavlink_receiver: generate rc channel count * mavlink_receiver: zero out ignored rc channels, add comments
1 parent 5bcd7c0 commit 504372f

File tree

1 file changed

+16
-1
lines changed

1 file changed

+16
-1
lines changed

src/modules/mavlink/mavlink_receiver.cpp

Lines changed: 16 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1834,7 +1834,6 @@ MavlinkReceiver::handle_message_rc_channels_override(mavlink_message_t *msg)
18341834
// metadata
18351835
rc.timestamp = hrt_absolute_time();
18361836
rc.timestamp_last_signal = rc.timestamp;
1837-
rc.channel_count = 18;
18381837
rc.rssi = RC_INPUT_RSSI_MAX;
18391838
rc.rc_failsafe = false;
18401839
rc.rc_lost = false;
@@ -1862,6 +1861,22 @@ MavlinkReceiver::handle_message_rc_channels_override(mavlink_message_t *msg)
18621861
rc.values[16] = man.chan17_raw;
18631862
rc.values[17] = man.chan18_raw;
18641863

1864+
// check how many channels are valid
1865+
for (int i = 17; i >= 0; i--) {
1866+
const bool ignore_max = rc.values[i] == UINT16_MAX; // ignore any channel with value UINT16_MAX
1867+
const bool ignore_zero = (i > 7) && (rc.values[i] == 0); // ignore channel 8-18 if value is 0
1868+
1869+
if (ignore_max || ignore_zero) {
1870+
// set all ignored values to zero
1871+
rc.values[i] = 0;
1872+
1873+
} else {
1874+
// first channel to not ignore -> set count considering zero-based index
1875+
rc.channel_count = i + 1;
1876+
break;
1877+
}
1878+
}
1879+
18651880
// publish uORB message
18661881
int instance; // provides the instance ID or the publication
18671882
ORB_PRIO priority = ORB_PRIO_HIGH; // since it is an override, set priority high

0 commit comments

Comments
 (0)