mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 08:38:36 -04:00
Copter: use magic force arm/disarm definitions
This commit is contained in:
parent
27cd972331
commit
ca8a1ae488
@ -961,12 +961,12 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
||||
case MAV_CMD_COMPONENT_ARM_DISARM:
|
||||
if (is_equal(packet.param1,1.0f)) {
|
||||
// attempt to arm and return success or failure
|
||||
const bool do_arming_checks = !is_equal(packet.param2,2989.0f);
|
||||
const bool do_arming_checks = !is_equal(packet.param2,magic_force_arm_value);
|
||||
if (copter.init_arm_motors(true, do_arming_checks)) {
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
} else if (is_zero(packet.param1)) {
|
||||
if (copter.ap.land_complete || is_equal(packet.param2,21196.0f)) {
|
||||
if (copter.ap.land_complete || is_equal(packet.param2,magic_force_disarm_value)) {
|
||||
// force disarming by setting param2 = 21196 is deprecated
|
||||
copter.init_disarm_motors();
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
|
Loading…
Reference in New Issue
Block a user