GCS_MAVLink: Correct a bug in the FOR_EACH_ACTIVE_CHANNEL macro

This commit is contained in:
Michael du Breuil 2017-08-28 23:04:40 -07:00 committed by Tom Pittenger
parent 8630037fd7
commit a895d69b42

View File

@ -22,12 +22,12 @@ void GCS::send_text(MAV_SEVERITY severity, const char *fmt, ...)
if (!chan(i).initialised) { \
continue; \
} \
if (!(GCS_MAVLINK::active_channel_mask() & (chan(i).get_chan()-MAVLINK_COMM_0))) { \
if (!(GCS_MAVLINK::active_channel_mask() & (1 << (chan(i).get_chan()-MAVLINK_COMM_0)))) { \
continue; \
} \
chan(i).methodcall; \
} \
} while (0);
} while (0)
void GCS::send_home(const Location &home) const
{