mirror of https://github.com/ArduPilot/ardupilot
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:
parent
31965689cb
commit
bf3f8c05e7
|
@ -681,7 +681,7 @@ bool GCS_MAVLINK::stream_trigger(enum streams stream_num)
|
||||||
rate *= adjust_rate_for_stream_trigger(stream_num);
|
rate *= adjust_rate_for_stream_trigger(stream_num);
|
||||||
|
|
||||||
if (rate <= 0) {
|
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
|
// if currently streaming then check if all streams are disabled
|
||||||
// to allow runtime detection of user disabling streaming
|
// to allow runtime detection of user disabling streaming
|
||||||
bool is_streaming = false;
|
bool is_streaming = false;
|
||||||
|
|
Loading…
Reference in New Issue