... and SITL....
Copter currently spits out so many messages on a banner-send (e.g what
we do when parameters are fetched) that it puses the first sent message
straight out of the queue before it gets a chance to be sent from the
queue.
When using external yaw, EKF3 always reports use_compass as false,
which causes the GCS to get a bad compass health message.
thanks to Argosdyne for reporting
We should only need to do a single PAYLOAD_SIZE check for each mavlink
backend now.
- stop iterating over all channels, only do instantiated mavlink
backends
- if we don't have space for a statustext on a channel, break
immediately and don't do remaining texts
- resposibility is now on the GCS_MAVLINK backend for sending texts
- that's a timing change
- only iterate over entries actually in the queue rather than maximum
queue size
- it's likely to be the full length anyway as we don't expire things
from the queue and most setups will have full channels
// because MISSION_SET_CURRENT is a message not a command,
// there is not ACK associated with us successfully changing
// our waypoint. Some GCSs use the fact we return exactly the
// same mission sequence number in this packet as an ACK - so
// if they send a MISSION_SET_CURRENT with seq number of 4
// then they expect to receive a MISSION_CURRENT message with
// exactly that sequence number in it, even if ArduPilot never
// actually holds that as a sequence number (e.g. packet.seq==0).
In the case you only have a forward-pointing LIDAR we'd send messages
for each of the other orientations from proximty's horizontal-distances
array, chewing up bandwidth and processing time.
Update libraries/GCS_MAVLink/MissionItemProtocol.cpp
Co-authored-by: WickedShell <Wicked.Shell.Scripts@gmail.com>
GCS_MAVLink: Notify the maximum number of missions