Browse Source

Copter: option to force arm, bypassing checks

master
Peter Barker 8 years ago
parent
commit
fd9ce90b8e
  1. 2
      ArduCopter/Copter.h
  2. 3
      ArduCopter/GCS_Mavlink.cpp
  3. 4
      ArduCopter/motors.cpp

2
ArduCopter/Copter.h

@ -834,7 +834,7 @@ private: @@ -834,7 +834,7 @@ private:
// motors.cpp
void arm_motors_check();
void auto_disarm_check();
bool init_arm_motors(bool arming_from_gcs);
bool init_arm_motors(bool arming_from_gcs, bool do_arming_checks=true);
void init_disarm_motors();
void motors_output();
void lost_vehicle_check();

3
ArduCopter/GCS_Mavlink.cpp

@ -961,7 +961,8 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg) @@ -961,7 +961,8 @@ 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
if (copter.init_arm_motors(true)) {
const bool do_arming_checks = !is_equal(packet.param2,2989.0f);
if (copter.init_arm_motors(true, do_arming_checks)) {
result = MAV_RESULT_ACCEPTED;
}
} else if (is_zero(packet.param1)) {

4
ArduCopter/motors.cpp

@ -127,7 +127,7 @@ void Copter::auto_disarm_check() @@ -127,7 +127,7 @@ void Copter::auto_disarm_check()
// init_arm_motors - performs arming process including initialisation of barometer and gyros
// returns false if arming failed because of pre-arm checks, arming checks or a gyro calibration failure
bool Copter::init_arm_motors(bool arming_from_gcs)
bool Copter::init_arm_motors(const bool arming_from_gcs, const bool do_arming_checks)
{
static bool in_arm_motors = false;
@ -144,7 +144,7 @@ bool Copter::init_arm_motors(bool arming_from_gcs) @@ -144,7 +144,7 @@ bool Copter::init_arm_motors(bool arming_from_gcs)
}
// run pre-arm-checks and display failures
if (!arming.all_checks_passing(arming_from_gcs)) {
if (do_arming_checks && !arming.all_checks_passing(arming_from_gcs)) {
AP_Notify::events.arming_failed = true;
in_arm_motors = false;
return false;

Loading…
Cancel
Save