Plane: cope with the changed semantics if airspeed.use()

This commit is contained in:
Andrew Tridgell 2015-01-20 11:28:35 +11:00
parent e8017a5079
commit 059c3769f3
4 changed files with 6 additions and 6 deletions

View File

@ -1215,7 +1215,7 @@ static void handle_auto_mode(void)
// allowed for level flight
nav_roll_cd = constrain_int32(nav_roll_cd, -g.level_roll_limit*100UL, g.level_roll_limit*100UL);
} else {
if (!airspeed.use()) {
if (!ahrs.airspeed_sensor_enabled()) {
// when not under airspeed control, don't allow
// down pitch in landing
nav_pitch_cd = constrain_int32(nav_pitch_cd, 0, nav_pitch_cd);

View File

@ -558,7 +558,7 @@ static bool is_flying(void)
bool gpsMovement = (gps.status() < AP_GPS::GPS_OK_FIX_2D ||
gps.ground_speed() >= 5);
bool airspeedMovement = !airspeed.use() || airspeed.get_airspeed() >= 5;
bool airspeedMovement = (!ahrs.airspeed_sensor_enabled()) || airspeed.get_airspeed() >= 5;
// we're more than 5m from the home altitude
bool inAir = relative_altitude_abs_cm() > 500;
@ -614,7 +614,7 @@ static bool suppress_throttle(void)
// if we have an airspeed sensor, then check it too, and
// require 5m/s. This prevents throttle up due to spiky GPS
// groundspeed with bad GPS reception
if (!airspeed.use() || airspeed.get_airspeed() >= 5) {
if ((!ahrs.airspeed_sensor_enabled()) || airspeed.get_airspeed() >= 5) {
// we're moving at more than 5 m/s
throttle_suppressed = false;
return false;
@ -869,7 +869,7 @@ static void set_servos(void)
if (auto_throttle_mode) {
int16_t flapSpeedSource = 0;
if (airspeed.use()) {
if (ahrs.airspeed_sensor_enabled()) {
flapSpeedSource = target_airspeed_cm * 0.01f;
} else {
flapSpeedSource = aparm.throttle_cruise;

View File

@ -163,7 +163,7 @@ static void read_radio()
if (g.throttle_nudge && channel_throttle->servo_out > 50) {
float nudge = (channel_throttle->servo_out - 50) * 0.02f;
if (airspeed.use()) {
if (ahrs.airspeed_sensor_enabled()) {
airspeed_nudge_cm = (aparm.airspeed_max * 100 - g.airspeed_cruise_cm) * nudge;
} else {
throttle_nudge = (aparm.throttle_max - aparm.throttle_cruise) * nudge;

View File

@ -115,7 +115,7 @@ static void takeoff_calc_pitch(void)
return;
}
if (airspeed.use()) {
if (ahrs.airspeed_sensor_enabled()) {
calc_nav_pitch();
if (nav_pitch_cd < auto_state.takeoff_pitch_cd) {
nav_pitch_cd = auto_state.takeoff_pitch_cd;