mirror of https://github.com/ArduPilot/ardupilot
GCS_MAVLink: accept mavlink standard force arm/disarm value for forced arming
the mavlink standard specifies just one value to do either arm or disarm. Conform to that standard
This commit is contained in:
parent
6354a8b912
commit
9049aeaff6
|
@ -732,7 +732,7 @@ protected:
|
|||
#endif // HAL_HIGH_LATENCY2_ENABLED
|
||||
|
||||
static constexpr const float magic_force_arm_value = 2989.0f;
|
||||
static constexpr const float magic_force_disarm_value = 21196.0f;
|
||||
static constexpr const float magic_force_arm_disarm_value = 21196.0f;
|
||||
|
||||
void manual_override(class RC_Channel *c, int16_t value_in, uint16_t offset, float scaler, const uint32_t tnow, bool reversed = false);
|
||||
|
||||
|
|
|
@ -4925,7 +4925,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_component_arm_disarm(const mavlink_comman
|
|||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
// run pre_arm_checks and arm_checks and display failures
|
||||
const bool do_arming_checks = !is_equal(packet.param2,magic_force_arm_value);
|
||||
const bool do_arming_checks = !is_equal(packet.param2,magic_force_arm_value) && !is_equal(packet.param2,magic_force_arm_disarm_value);
|
||||
if (AP::arming().arm(AP_Arming::Method::MAVLINK, do_arming_checks)) {
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
|
@ -4935,7 +4935,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_component_arm_disarm(const mavlink_comman
|
|||
if (!AP::arming().is_armed()) {
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
}
|
||||
const bool forced = is_equal(packet.param2, magic_force_disarm_value);
|
||||
const bool forced = is_equal(packet.param2, magic_force_arm_disarm_value);
|
||||
// note disarm()'s second parameter is "do_disarm_checks"
|
||||
if (AP::arming().disarm(AP_Arming::Method::MAVLINK, !forced)) {
|
||||
return MAV_RESULT_ACCEPTED;
|
||||
|
|
Loading…
Reference in New Issue