Plane: option to force arm, bypassing checks

This commit is contained in:
Peter Barker 2016-09-26 23:03:06 +10:00
parent 4d6408857f
commit f5e241af01
3 changed files with 5 additions and 4 deletions

View File

@ -975,7 +975,8 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
case MAV_CMD_COMPONENT_ARM_DISARM:
if (is_equal(packet.param1,1.0f)) {
// run pre_arm_checks and arm_checks and display failures
if (plane.arm_motors(AP_Arming::MAVLINK)) {
const bool do_arming_checks = !is_equal(packet.param2,2989.0f);
if (plane.arm_motors(AP_Arming::MAVLINK, do_arming_checks)) {
result = MAV_RESULT_ACCEPTED;
} else {
result = MAV_RESULT_FAILED;

View File

@ -927,7 +927,7 @@ private:
int8_t throttle_percentage(void);
void change_arm_state(void);
bool disarm_motors(void);
bool arm_motors(AP_Arming::ArmingMethod method);
bool arm_motors(AP_Arming::ArmingMethod method, bool do_arming_checks=true);
bool auto_takeoff_check(void);
void takeoff_calc_roll(void);
void takeoff_calc_pitch(void);

View File

@ -728,9 +728,9 @@ void Plane::change_arm_state(void)
/*
arm motors
*/
bool Plane::arm_motors(AP_Arming::ArmingMethod method)
bool Plane::arm_motors(const AP_Arming::ArmingMethod method, const bool do_arming_checks)
{
if (!arming.arm(method)) {
if (!arming.arm(method, do_arming_checks)) {
return false;
}