Browse Source

Plane: fixed ARMING_REQUIRED=2 on APM2 to disable rc output on throttle

mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
89366a1ee1
  1. 4
      ArduPlane/GCS_Mavlink.pde
  2. 5
      ArduPlane/radio.pde

4
ArduPlane/GCS_Mavlink.pde

@ -1259,6 +1259,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) @@ -1259,6 +1259,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
// run pre_arm_checks and arm_checks and display failures
if (arming.arm(AP_Arming::MAVLINK)) {
//only log if arming was successful
channel_throttle->enable_out();
Log_Arm_Disarm();
result = MAV_RESULT_ACCEPTED;
} else {
@ -1267,6 +1268,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) @@ -1267,6 +1268,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
} else if (packet.param1 == 0.0f) {
if (arming.disarm()) {
//only log if disarming was successful
if (arming.arming_required() != AP_Arming::YES_ZERO_PWM) {
channel_throttle->disable_out();
}
Log_Arm_Disarm();
result = MAV_RESULT_ACCEPTED;
} else {

5
ArduPlane/radio.pde

@ -41,7 +41,9 @@ static void init_rc_out() @@ -41,7 +41,9 @@ static void init_rc_out()
{
channel_roll->enable_out();
channel_pitch->enable_out();
channel_throttle->enable_out();
if (arming.arming_required() != AP_Arming::YES_ZERO_PWM) {
channel_throttle->enable_out();
}
channel_rudder->enable_out();
enable_aux_servos();
@ -105,6 +107,7 @@ static void rudder_arm_check() @@ -105,6 +107,7 @@ static void rudder_arm_check()
} else {
//time to arm!
if (arming.arm(AP_Arming::RUDDER)) {
channel_throttle->enable_out();
//only log if arming was successful
Log_Arm_Disarm();
}

Loading…
Cancel
Save