diff --git a/ArduPlane/AP_Arming.cpp b/ArduPlane/AP_Arming.cpp index 957416813c..938fc317be 100644 --- a/ArduPlane/AP_Arming.cpp +++ b/ArduPlane/AP_Arming.cpp @@ -189,9 +189,9 @@ bool AP_Arming_Plane::arm(const AP_Arming::Method method, const bool do_arming_c /* disarm motors */ -bool AP_Arming_Plane::disarm(void) +bool AP_Arming_Plane::disarm(const AP_Arming::Method method) { - if (!AP_Arming::disarm()) { + if (!AP_Arming::disarm(method)) { return false; } if (plane.control_mode != &plane.mode_auto) { diff --git a/ArduPlane/AP_Arming.h b/ArduPlane/AP_Arming.h index 14c9ebed64..1bb12213cc 100644 --- a/ArduPlane/AP_Arming.h +++ b/ArduPlane/AP_Arming.h @@ -24,7 +24,7 @@ public: // var_info for holding Parameter information static const struct AP_Param::GroupInfo var_info[]; - bool disarm() override; + bool disarm(AP_Arming::Method method) override; bool arm(AP_Arming::Method method, bool do_arming_checks=true) override; void update_soft_armed(); diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 455700fda5..f14c03dcee 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -653,7 +653,7 @@ void Plane::disarm_if_autoland_complete() arming.is_armed()) { /* we have auto disarm enabled. See if enough time has passed */ if (millis() - auto_state.last_flying_ms >= landing.get_disarm_delay()*1000UL) { - if (arming.disarm()) { + if (arming.disarm(AP_Arming::Method::AUTOLANDED)) { gcs().send_text(MAV_SEVERITY_INFO,"Auto disarmed"); } } diff --git a/ArduPlane/afs_plane.cpp b/ArduPlane/afs_plane.cpp index 59cf2b9a36..04c12c2ab1 100644 --- a/ArduPlane/afs_plane.cpp +++ b/ArduPlane/afs_plane.cpp @@ -53,7 +53,7 @@ void AP_AdvancedFailsafe_Plane::terminate_vehicle(void) plane.quadplane.afs_terminate(); // also disarm to ensure that ignition is cut - plane.arming.disarm(); + plane.arming.disarm(AP_Arming::Method::AFS); } void AP_AdvancedFailsafe_Plane::setup_IO_failsafe(void) diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index 679398ead3..7abf93f75d 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -559,7 +559,7 @@ bool Plane::verify_takeoff() uint32_t now = AP_HAL::millis(); if (now - takeoff_state.start_time_ms > (uint32_t)(1000U * g2.takeoff_timeout)) { gcs().send_text(MAV_SEVERITY_INFO, "Takeoff timeout at %.1f m/s", ground_speed); - plane.arming.disarm(); + plane.arming.disarm(AP_Arming::Method::TAKEOFFTIMEOUT); mission.reset(); } } diff --git a/ArduPlane/events.cpp b/ArduPlane/events.cpp index ed0f4f5c3d..4164bb1ae4 100644 --- a/ArduPlane/events.cpp +++ b/ArduPlane/events.cpp @@ -194,7 +194,7 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action) snprintf(battery_type_str, 17, "%s battery", type_str); afs.gcs_terminate(true, battery_type_str); #else - arming.disarm(); + arming.disarm(AP_Arming::Method::FAILSAFE_ACTION_TERMINATE); #endif break; diff --git a/ArduPlane/is_flying.cpp b/ArduPlane/is_flying.cpp index 7a65725a3d..9d40ade53d 100644 --- a/ArduPlane/is_flying.cpp +++ b/ArduPlane/is_flying.cpp @@ -305,7 +305,7 @@ void Plane::crash_detection_update(void) } else { if (aparm.crash_detection_enable & CRASH_DETECT_ACTION_BITMASK_DISARM) { - arming.disarm(); + arming.disarm(AP_Arming::Method::CRASH); } if (crashed_near_land_waypoint) { gcs().send_text(MAV_SEVERITY_CRITICAL, "Hard landing detected"); diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 7f22fd52c1..331997d05e 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -2729,7 +2729,7 @@ void QuadPlane::check_land_complete(void) return; } if (land_detector(4000)) { - plane.arming.disarm(); + plane.arming.disarm(AP_Arming::Method::LANDED); poscontrol.state = QPOS_LAND_COMPLETE; gcs().send_text(MAV_SEVERITY_INFO,"Land complete"); // reload target airspeed which could have been modified by the mission diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index 8f4df73dfb..558b778b83 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -165,7 +165,7 @@ void Plane::rudder_arm_disarm_check() } } else { //time to disarm! - arming.disarm(); + arming.disarm(AP_Arming::Method::RUDDER); rudder_arm_timer = 0; } } else {