mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
GCS_MAVLink: allow Copter to disallow mavlink disarm
This commit is contained in:
parent
84b16ea3dd
commit
75ae6b59b0
@ -643,6 +643,8 @@ protected:
|
||||
static constexpr const float magic_force_arm_value = 2989.0f;
|
||||
static constexpr const float magic_force_disarm_value = 21196.0f;
|
||||
|
||||
virtual bool allow_disarm() const { return true; }
|
||||
|
||||
void manual_override(RC_Channel *c, int16_t value_in, uint16_t offset, float scaler, const uint32_t tnow, bool reversed = false);
|
||||
|
||||
private:
|
||||
|
@ -3976,6 +3976,12 @@ MAV_RESULT GCS_MAVLINK::handle_command_long_packet(const mavlink_command_long_t
|
||||
if (!AP::arming().is_armed()) {
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
// allow vehicle to disallow disarm. Copter does this if
|
||||
// the vehicle isn't considered landed.
|
||||
if (!allow_disarm() &&
|
||||
!is_equal(packet.param2, magic_force_disarm_value)) {
|
||||
return MAV_RESULT_FAILED;
|
||||
}
|
||||
if (AP::arming().disarm()) {
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user