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 Andrew Tridgell
parent 427c046145
commit 740e1c4326

View File

@ -22,12 +22,12 @@ void GCS::send_text(MAV_SEVERITY severity, const char *fmt, ...)
if (!chan(i).initialised) { \ if (!chan(i).initialised) { \
continue; \ 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; \ continue; \
} \ } \
chan(i).methodcall; \ chan(i).methodcall; \
} \ } \
} while (0); } while (0)
void GCS::send_home(const Location &home) const void GCS::send_home(const Location &home) const
{ {