mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-02 19:53:57 -04:00
AP_Arming: remove unused arming_method member
This commit is contained in:
parent
1dece80c88
commit
6979f0d3a0
@ -76,10 +76,7 @@ const AP_Param::GroupInfo AP_Arming::var_info[] = {
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
//The function point is particularly hacky, hacky, tacky
|
||||
//but I don't want to reimplement messaging to GCS at the moment:
|
||||
AP_Arming::AP_Arming() :
|
||||
arming_method(NONE)
|
||||
AP_Arming::AP_Arming()
|
||||
{
|
||||
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?
|
||||
if (!do_arming_checks || checks_to_perform == ARMING_CHECK_NONE) {
|
||||
armed = true;
|
||||
arming_method = NONE;
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Throttle armed");
|
||||
return true;
|
||||
}
|
||||
|
||||
if (pre_arm_checks(true) && arm_checks(method)) {
|
||||
armed = true;
|
||||
arming_method = method;
|
||||
|
||||
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 {
|
||||
armed = false;
|
||||
arming_method = NONE;
|
||||
}
|
||||
|
||||
return armed;
|
||||
|
@ -79,7 +79,6 @@ protected:
|
||||
// internal members
|
||||
bool armed: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_gyro_pass_ms[INS_MAX_INSTANCES];
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user