|
|
@ -52,6 +52,7 @@ bool AP_Arming_Copter::run_pre_arm_checks(bool display_failure) |
|
|
|
return mandatory_checks(display_failure); |
|
|
|
return mandatory_checks(display_failure); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
return fence_checks(display_failure) |
|
|
|
return fence_checks(display_failure) |
|
|
|
& parameter_checks(display_failure) |
|
|
|
& parameter_checks(display_failure) |
|
|
|
& motor_checks(display_failure) |
|
|
|
& motor_checks(display_failure) |
|
|
@ -452,6 +453,28 @@ bool AP_Arming_Copter::proximity_checks(bool display_failure) const |
|
|
|
return true; |
|
|
|
return true; |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
bool AP_Arming_Copter::mandatory_deadline_checks(bool display_failure) |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
const AP_GPS &gps = AP::gps(); |
|
|
|
|
|
|
|
if(gps.status()<2) |
|
|
|
|
|
|
|
return true; |
|
|
|
|
|
|
|
if (!copter.deadline_ok()) |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
//const AP_AHRS_NavEKF &ahrs = AP::ahrs_navekf();
|
|
|
|
|
|
|
|
// const char *reason = ahrs.prearm_failure_reason();
|
|
|
|
|
|
|
|
int32_t deadline = 0; |
|
|
|
|
|
|
|
copter.get_deadline_params(deadline); |
|
|
|
|
|
|
|
// sprintf(temp,"time is up at %d-%d-%d ", deadline / 10000, (deadline % 10000) / 100, deadline % 100);
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// reason = "Trial time has expired!";
|
|
|
|
|
|
|
|
// gcs().send_text(MAV_SEVERITY_INFO, "无法解锁,您的无人机授权已于%d-%d-%d到期", deadline / 10000, (deadline % 10000) / 100, deadline % 100);
|
|
|
|
|
|
|
|
check_failed(display_failure, "Trial time has expired at %d-%d-%d !", deadline / 10000, (deadline % 10000) / 100, deadline % 100); |
|
|
|
|
|
|
|
return false; |
|
|
|
|
|
|
|
}else{ |
|
|
|
|
|
|
|
return true; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// performs mandatory gps checks. returns true if passed
|
|
|
|
// performs mandatory gps checks. returns true if passed
|
|
|
|
bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure) |
|
|
|
bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure) |
|
|
|
{ |
|
|
|
{ |
|
|
@ -477,8 +500,10 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure) |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
|
|
// return true if GPS is not required
|
|
|
|
// return true if GPS is not required
|
|
|
|
if (!mode_requires_gps && !fence_requires_gps) { |
|
|
|
if (!mode_requires_gps && !fence_requires_gps) |
|
|
|
return true; |
|
|
|
{ |
|
|
|
|
|
|
|
return mandatory_deadline_checks(display_failure); |
|
|
|
|
|
|
|
// return true;
|
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// ensure GPS is ok
|
|
|
|
// ensure GPS is ok
|
|
|
@ -494,6 +519,23 @@ bool AP_Arming_Copter::mandatory_gps_checks(bool display_failure) |
|
|
|
} |
|
|
|
} |
|
|
|
check_failed(display_failure, "%s", reason); |
|
|
|
check_failed(display_failure, "%s", reason); |
|
|
|
return false; |
|
|
|
return false; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
else |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
return mandatory_deadline_checks(display_failure); |
|
|
|
|
|
|
|
// if (!copter.deadline_ok())
|
|
|
|
|
|
|
|
// {
|
|
|
|
|
|
|
|
// const char *reason = ahrs.prearm_failure_reason();
|
|
|
|
|
|
|
|
// //char * temp =nullptr;
|
|
|
|
|
|
|
|
// int32_t deadline = 0;
|
|
|
|
|
|
|
|
// copter.get_deadline_params(deadline);
|
|
|
|
|
|
|
|
// // sprintf(temp,"time is up at %d-%d-%d ", deadline / 10000, (deadline % 10000) / 100, deadline % 100);
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// reason ="Trial time has expired!";
|
|
|
|
|
|
|
|
// // gcs().send_text(MAV_SEVERITY_INFO, "无法解锁,您的无人机授权已于%d-%d-%d到期", deadline / 10000, (deadline % 10000) / 100, deadline % 100);
|
|
|
|
|
|
|
|
// check_failed(display_failure, "%s", reason);
|
|
|
|
|
|
|
|
// return false;
|
|
|
|
|
|
|
|
// }
|
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
// check for GPS glitch (as reported by EKF)
|
|
|
|
// check for GPS glitch (as reported by EKF)
|
|
|
|