mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 09:43:57 -04:00
AP_Arming: add arming check for logging actually started
This commit is contained in:
parent
3fbcf40a1a
commit
fff2068a5a
@ -146,8 +146,8 @@ bool AP_Arming::logging_checks(bool report)
|
||||
if (DataFlash_Class::instance()->logging_failed()) {
|
||||
if (report) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "PreArm: Logging failed");
|
||||
return false;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
if (!DataFlash_Class::instance()->CardInserted()) {
|
||||
if (report) {
|
||||
@ -465,6 +465,18 @@ bool AP_Arming::pre_arm_checks(bool report)
|
||||
return ret;
|
||||
}
|
||||
|
||||
bool AP_Arming::arm_checks(uint8_t method)
|
||||
{
|
||||
if ((checks_to_perform & ARMING_CHECK_ALL) ||
|
||||
(checks_to_perform & ARMING_CHECK_LOGGING)) {
|
||||
if (!DataFlash_Class::instance()->logging_started()) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "Arm: Logging not started");
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
//returns true if arming occurred successfully
|
||||
bool AP_Arming::arm(uint8_t method)
|
||||
{
|
||||
@ -480,7 +492,7 @@ bool AP_Arming::arm(uint8_t method)
|
||||
return true;
|
||||
}
|
||||
|
||||
if (pre_arm_checks(true)) {
|
||||
if (pre_arm_checks(true) && arm_checks(method)) {
|
||||
armed = true;
|
||||
arming_method = method;
|
||||
|
||||
|
@ -47,7 +47,7 @@ public:
|
||||
const AP_BattMonitor &battery, const enum HomeState &home_set);
|
||||
|
||||
ArmingRequired arming_required();
|
||||
bool arm(uint8_t method);
|
||||
virtual bool arm(uint8_t method);
|
||||
bool disarm();
|
||||
bool is_armed();
|
||||
ArmingRudder rudder_arming() const { return (ArmingRudder)rudder_arming_value.get(); }
|
||||
@ -58,6 +58,10 @@ public:
|
||||
in a vehicle specific subclass
|
||||
*/
|
||||
virtual bool pre_arm_checks(bool report);
|
||||
// some arming checks have side-effects, or require some form of state
|
||||
// change to have occured, and thus should not be done as pre-arm
|
||||
// checks. Those go here:
|
||||
bool arm_checks(uint8_t method);
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user