mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
fix commander: run preflight checks on GCS connection
Regression from 6dec451babf1b4c6394fbf8678585d66932adefb, leading to preflight failures not being reported at all. Only after a failed arming attempt the messages would be sent. And for GPS check failures, in case they are set to optional (default), arming would be possible, but switching to position would be rejected w/o error. We need to run the preflight checks periodically, but this at least restores the previous behavior.
This commit is contained in:
parent
2a67d22ac7
commit
db49e5abcd
@ -3558,12 +3558,18 @@ void Commander::data_link_check()
|
||||
switch (telemetry.remote_type) {
|
||||
case telemetry_status_s::MAV_TYPE_GCS:
|
||||
|
||||
// Recover from data link lost
|
||||
// Initial connection or recovery from data link lost
|
||||
if (status.data_link_lost) {
|
||||
if (telemetry.heartbeat_time > _datalink_last_heartbeat_gcs) {
|
||||
status.data_link_lost = false;
|
||||
_status_changed = true;
|
||||
|
||||
if (!armed.armed) {
|
||||
// make sure to report preflight check failures to a connecting GCS
|
||||
PreFlightCheck::preflightCheck(&mavlink_log_pub, status, status_flags,
|
||||
_arm_requirements.global_position, true, true, hrt_elapsed_time(&_boot_timestamp));
|
||||
}
|
||||
|
||||
if (_datalink_last_heartbeat_gcs != 0) {
|
||||
mavlink_log_info(&mavlink_log_pub, "Data link regained");
|
||||
}
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user