Plane: ensure throttle reverse is obeyed in all states

need to use radio_max for failsafe if reversed
This commit is contained in:
Andrew Tridgell 2015-09-14 09:42:20 +10:00
parent 5c055220f5
commit d43d070e75
4 changed files with 15 additions and 6 deletions

View File

@ -737,6 +737,14 @@ void Plane::set_servos_idle(void)
channel_throttle->output_trim();
}
/*
return minimum throttle, taking account of throttle reversal
*/
uint16_t Plane::throttle_min(void) const
{
return channel_throttle->get_reverse() ? channel_throttle->radio_max : channel_throttle->radio_min;
};
/*****************************************
* Set the flight control servos based on the current calculated values
@ -1004,7 +1012,7 @@ void Plane::set_servos(void)
case AP_Arming::YES_MIN_PWM:
default:
channel_throttle->radio_out = channel_throttle->radio_min;
channel_throttle->radio_out = throttle_min();
break;
}
}

View File

@ -956,7 +956,8 @@ private:
uint32_t micros() const;
void init_capabilities(void);
void dataflash_periodic(void);
uint16_t throttle_min(void) const;
public:
void mavlink_delay_cb();
void failsafe_check(void);

View File

@ -259,7 +259,7 @@ bool Plane::setup_failsafe_mixing(void)
if (old_state == AP_HAL::Util::SAFETY_ARMED) {
// make sure the throttle has a non-zero failsafe value before we
// disable safety. This prevents sending zero PWM during switch over
hal.rcout->set_safety_pwm(1UL<<(rcmap.throttle()-1), channel_throttle->radio_min);
hal.rcout->set_safety_pwm(1UL<<(rcmap.throttle()-1), throttle_min());
}
// we need to force safety on to allow us to load a mixer. We call

View File

@ -28,7 +28,7 @@ void Plane::set_control_channels(void)
channel_throttle->set_range(0, 100);
if (!arming.is_armed() && arming.arming_required() == AP_Arming::YES_MIN_PWM) {
hal.rcout->set_safety_pwm(1UL<<(rcmap.throttle()-1), channel_throttle->radio_min);
hal.rcout->set_safety_pwm(1UL<<(rcmap.throttle()-1), throttle_min());
}
// setup correct scaling for ESCs like the UAVCAN PX4ESC which
@ -63,7 +63,7 @@ void Plane::init_rc_out()
configuration error where the user sets CH3_TRIM incorrectly and
the motor may start on power up
*/
channel_throttle->radio_trim = channel_throttle->get_reverse() ? channel_throttle->radio_max : channel_throttle->radio_min;
channel_throttle->radio_trim = throttle_min();
if (arming.arming_required() != AP_Arming::YES_ZERO_PWM) {
channel_throttle->enable_out();
@ -80,7 +80,7 @@ void Plane::init_rc_out()
// setup PX4 to output the min throttle when safety off if arming
// is setup for min on disarm
if (arming.arming_required() == AP_Arming::YES_MIN_PWM) {
hal.rcout->set_safety_pwm(1UL<<(rcmap.throttle()-1), channel_throttle->radio_min);
hal.rcout->set_safety_pwm(1UL<<(rcmap.throttle()-1), throttle_min());
}
}