mirror of https://github.com/ArduPilot/ardupilot
Sub: try_send_message caller checks telemetry_delayed
This commit is contained in:
parent
17f244ce9f
commit
87d27957d9
|
@ -385,10 +385,6 @@ bool GCS_MAVLINK_Sub::vehicle_initialised() const {
|
||||||
// try to send a message, return false if it won't fit in the serial tx buffer
|
// try to send a message, return false if it won't fit in the serial tx buffer
|
||||||
bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
|
bool GCS_MAVLINK_Sub::try_send_message(enum ap_message id)
|
||||||
{
|
{
|
||||||
if (telemetry_delayed()) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
// if we don't have at least 250 micros remaining before the main loop
|
// if we don't have at least 250 micros remaining before the main loop
|
||||||
// wants to fire then don't send a mavlink message. We want to
|
// wants to fire then don't send a mavlink message. We want to
|
||||||
// prioritise the main flight control loop over communications
|
// prioritise the main flight control loop over communications
|
||||||
|
|
Loading…
Reference in New Issue