mirror of https://github.com/ArduPilot/ardupilot
APMrover2: log disarm method
This commit is contained in:
parent
347f64264d
commit
98c999d0de
|
@ -135,9 +135,9 @@ bool AP_Arming_Rover::arm(AP_Arming::Method method, const bool do_arming_checks)
|
|||
/*
|
||||
disarm motors
|
||||
*/
|
||||
bool AP_Arming_Rover::disarm(void)
|
||||
bool AP_Arming_Rover::disarm(const AP_Arming::Method method)
|
||||
{
|
||||
if (!AP_Arming::disarm()) {
|
||||
if (!AP_Arming::disarm(method)) {
|
||||
return false;
|
||||
}
|
||||
if (rover.control_mode != &rover.mode_auto) {
|
||||
|
|
|
@ -21,7 +21,7 @@ public:
|
|||
bool rc_calibration_checks(const bool display_failure) override;
|
||||
bool gps_checks(bool display_failure) override;
|
||||
|
||||
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();
|
||||
|
|
|
@ -12,7 +12,7 @@
|
|||
void AP_AdvancedFailsafe_Rover::terminate_vehicle(void)
|
||||
{
|
||||
// disarm as well
|
||||
AP::arming().disarm();
|
||||
AP::arming().disarm(AP_Arming::Method::AFS);
|
||||
|
||||
// Set to HOLD mode
|
||||
rover.set_mode(rover.mode_hold, ModeReason::CRASH_FAILSAFE);
|
||||
|
|
|
@ -51,14 +51,14 @@ void Rover::crash_check()
|
|||
if (is_balancebot()) {
|
||||
// send message to gcs
|
||||
gcs().send_text(MAV_SEVERITY_EMERGENCY, "Crash: Disarming");
|
||||
arming.disarm();
|
||||
arming.disarm(AP_Arming::Method::CRASH);
|
||||
} else {
|
||||
// send message to gcs
|
||||
gcs().send_text(MAV_SEVERITY_EMERGENCY, "Crash: Going to HOLD");
|
||||
// change mode to hold and disarm
|
||||
set_mode(mode_hold, ModeReason::CRASH_FAILSAFE);
|
||||
if (g.fs_crash_check == FS_CRASH_HOLD_AND_DISARM) {
|
||||
arming.disarm();
|
||||
arming.disarm(AP_Arming::Method::CRASH);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -37,7 +37,7 @@ void Rover::failsafe_check()
|
|||
// To-Do: log error
|
||||
if (arming.is_armed()) {
|
||||
// disarm motors
|
||||
arming.disarm();
|
||||
arming.disarm(AP_Arming::Method::CPUFAILSAFE);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -137,7 +137,7 @@ void Rover::handle_battery_failsafe(const char* type_str, const int8_t action)
|
|||
snprintf(battery_type_str, 17, "%s battery", type_str);
|
||||
g2.afs.gcs_terminate(true, battery_type_str);
|
||||
#else
|
||||
arming.disarm();
|
||||
arming.disarm(AP_Arming::Method::BATTERYFAILSAFE);
|
||||
#endif // ADVANCED_FAILSAFE == ENABLED
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -159,7 +159,7 @@ void Rover::motor_test_stop()
|
|||
}
|
||||
|
||||
// disarm motors
|
||||
AP::arming().disarm();
|
||||
AP::arming().disarm(AP_Arming::Method::MOTORTEST);
|
||||
|
||||
// reset timeout
|
||||
motor_test_start_ms = 0;
|
||||
|
|
|
@ -98,7 +98,7 @@ void Rover::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