mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
GCS_MAVLink: Correct a bug in the FOR_EACH_ACTIVE_CHANNEL macro
This commit is contained in:
parent
8630037fd7
commit
a895d69b42
@ -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
|
||||
{
|
||||
|
Loading…
Reference in New Issue
Block a user