mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
ArduPlane: log disarm method
This commit is contained in:
parent
ce5f23810b
commit
74dbcac40e
@ -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) {
|
||||
|
@ -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();
|
||||
|
@ -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");
|
||||
}
|
||||
}
|
||||
|
@ -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)
|
||||
|
@ -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();
|
||||
}
|
||||
}
|
||||
|
@ -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;
|
||||
|
||||
|
@ -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");
|
||||
|
@ -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
|
||||
|
@ -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 {
|
||||
|
Loading…
Reference in New Issue
Block a user