mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
ArduCopter: add do_disarm_checks boolean to disarm call
this creates symmetry between arming and disarming, at least as far as the top-level arm() and disarm() calls are concerned.
This commit is contained in:
parent
3d577d94e8
commit
65adf5b4a9
@ -872,14 +872,21 @@ bool AP_Arming_Copter::arm(const AP_Arming::Method method, const bool do_arming_
|
||||
}
|
||||
|
||||
// arming.disarm - disarm motors
|
||||
bool AP_Arming_Copter::disarm(const AP_Arming::Method method)
|
||||
bool AP_Arming_Copter::disarm(const AP_Arming::Method method, bool do_disarm_checks)
|
||||
{
|
||||
// return immediately if we are already disarmed
|
||||
if (!copter.motors->armed()) {
|
||||
return true;
|
||||
}
|
||||
|
||||
if (!AP_Arming::disarm(method)) {
|
||||
// do not allow disarm via mavlink if we think we are flying:
|
||||
if (do_disarm_checks &&
|
||||
method == AP_Arming::Method::MAVLINK &&
|
||||
!copter.ap.land_complete) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (!AP_Arming::disarm(method, do_disarm_checks)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -23,7 +23,7 @@ public:
|
||||
|
||||
bool rc_calibration_checks(bool display_failure) override;
|
||||
|
||||
bool disarm(AP_Arming::Method method) override;
|
||||
bool disarm(AP_Arming::Method method, bool do_disarm_checks=true) override;
|
||||
bool arm(AP_Arming::Method method, bool do_arming_checks=true) override;
|
||||
|
||||
protected:
|
||||
|
@ -689,11 +689,6 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_mount(const mavlink_command_long_t
|
||||
return GCS_MAVLINK::handle_command_mount(packet);
|
||||
}
|
||||
|
||||
bool GCS_MAVLINK_Copter::allow_disarm() const
|
||||
{
|
||||
return copter.ap.land_complete;
|
||||
}
|
||||
|
||||
MAV_RESULT GCS_MAVLINK_Copter::handle_command_long_packet(const mavlink_command_long_t &packet)
|
||||
{
|
||||
switch(packet.command) {
|
||||
|
@ -43,8 +43,6 @@ protected:
|
||||
virtual MAV_VTOL_STATE vtol_state() const override { return MAV_VTOL_STATE_MC; };
|
||||
virtual MAV_LANDED_STATE landed_state() const override;
|
||||
|
||||
bool allow_disarm() const override;
|
||||
|
||||
private:
|
||||
|
||||
void handleMessage(const mavlink_message_t &msg) override;
|
||||
|
Loading…
Reference in New Issue
Block a user