GCS_Mavlink: Correctly check if a channel is streaming

In GCS_MAVLINK::stream_trigger(), chan_is_streaming would be checked
with a bitwise OR, instead of a bitwise AND.  This way, the condition
would always be true if chan_is_streaming were to be non-zero.
This commit is contained in:
Leandro Pereira 2016-08-23 14:11:24 -03:00 committed by Lucas De Marchi
parent 31965689cb
commit bf3f8c05e7
1 changed files with 1 additions and 1 deletions

View File

@ -681,7 +681,7 @@ bool GCS_MAVLINK::stream_trigger(enum streams stream_num)
rate *= adjust_rate_for_stream_trigger(stream_num);
if (rate <= 0) {
if (chan_is_streaming | (1U<<(chan-MAVLINK_COMM_0))) {
if (chan_is_streaming & (1U<<(chan-MAVLINK_COMM_0))) {
// if currently streaming then check if all streams are disabled
// to allow runtime detection of user disabling streaming
bool is_streaming = false;