AP_Arming: remove unused arming_method member

This commit is contained in:
Peter Barker 2018-06-24 09:01:42 +10:00 committed by Peter Barker
parent 1dece80c88
commit 6979f0d3a0
2 changed files with 1 additions and 8 deletions

View File

@ -76,10 +76,7 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = {
AP_GROUPEND AP_GROUPEND
}; };
//The function point is particularly hacky, hacky, tacky AP_Arming::AP_Arming()
//but I don't want to reimplement messaging to GCS at the moment:
AP_Arming::AP_Arming() :
arming_method(NONE)
{ {
AP_Param::setup_object_defaults(this, var_info); AP_Param::setup_object_defaults(this, var_info);
} }
@ -601,14 +598,12 @@ bool AP_Arming::arm(uint8_t method, const bool do_arming_checks)
//are arming checks disabled? //are arming checks disabled?
if (!do_arming_checks || checks_to_perform == ARMING_CHECK_NONE) { if (!do_arming_checks || checks_to_perform == ARMING_CHECK_NONE) {
armed = true; armed = true;
arming_method = NONE;
gcs().send_text(MAV_SEVERITY_INFO, "Throttle armed"); gcs().send_text(MAV_SEVERITY_INFO, "Throttle armed");
return true; return true;
} }
if (pre_arm_checks(true) && arm_checks(method)) { if (pre_arm_checks(true) && arm_checks(method)) {
armed = true; armed = true;
arming_method = method;
gcs().send_text(MAV_SEVERITY_INFO, "Throttle armed"); gcs().send_text(MAV_SEVERITY_INFO, "Throttle armed");
@ -617,7 +612,6 @@ bool AP_Arming::arm(uint8_t method, const bool do_arming_checks)
} else { } else {
armed = false; armed = false;
arming_method = NONE;
} }
return armed; return armed;

View File

@ -79,7 +79,6 @@ protected:
// internal members // internal members
bool armed:1; bool armed:1;
bool logging_available:1; bool logging_available:1;
uint8_t arming_method; // how the vehicle was armed
uint32_t last_accel_pass_ms[INS_MAX_INSTANCES]; uint32_t last_accel_pass_ms[INS_MAX_INSTANCES];
uint32_t last_gyro_pass_ms[INS_MAX_INSTANCES]; uint32_t last_gyro_pass_ms[INS_MAX_INSTANCES];