mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Copter: send extended status to GCS only after initialisation
This commit is contained in:
parent
2f2665c022
commit
bf18fb896a
@ -388,6 +388,7 @@ static union {
|
|||||||
uint8_t rc_receiver_present : 1; // 14 // true if we have an rc receiver present (i.e. if we've ever received an update
|
uint8_t rc_receiver_present : 1; // 14 // true if we have an rc receiver present (i.e. if we've ever received an update
|
||||||
uint8_t compass_mot : 1; // 15 // true if we are currently performing compassmot calibration
|
uint8_t compass_mot : 1; // 15 // true if we are currently performing compassmot calibration
|
||||||
uint8_t motor_test : 1; // 16 // true if we are currently performing the motors test
|
uint8_t motor_test : 1; // 16 // true if we are currently performing the motors test
|
||||||
|
uint8_t initialised : 1; // 17 // true once the init_ardupilot function has completed. Extended status to GCS is not sent until this completes
|
||||||
};
|
};
|
||||||
uint32_t value;
|
uint32_t value;
|
||||||
} ap;
|
} ap;
|
||||||
|
@ -481,10 +481,14 @@ bool GCS_MAVLINK::try_send_message(enum ap_message id)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_EXTENDED_STATUS1:
|
case MSG_EXTENDED_STATUS1:
|
||||||
CHECK_PAYLOAD_SIZE(SYS_STATUS);
|
// send extended status only once vehicle has been initialised
|
||||||
send_extended_status1(chan);
|
// to avoid unnecessary errors being reported to user
|
||||||
CHECK_PAYLOAD_SIZE(POWER_STATUS);
|
if (ap.initialised) {
|
||||||
gcs[chan-MAVLINK_COMM_0].send_power_status();
|
CHECK_PAYLOAD_SIZE(SYS_STATUS);
|
||||||
|
send_extended_status1(chan);
|
||||||
|
CHECK_PAYLOAD_SIZE(POWER_STATUS);
|
||||||
|
gcs[chan-MAVLINK_COMM_0].send_power_status();
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSG_EXTENDED_STATUS2:
|
case MSG_EXTENDED_STATUS2:
|
||||||
|
@ -295,6 +295,9 @@ static void init_ardupilot()
|
|||||||
}
|
}
|
||||||
|
|
||||||
cliSerial->print_P(PSTR("\nReady to FLY "));
|
cliSerial->print_P(PSTR("\nReady to FLY "));
|
||||||
|
|
||||||
|
// flag that initialisation has completed
|
||||||
|
ap.initialised = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user