Browse Source

Plane: Remove some redundant code/state resets

master
Michael du Breuil 6 years ago committed by Andrew Tridgell
parent
commit
843c92ced5
  1. 3
      ArduPlane/ArduPlane.cpp
  2. 4
      ArduPlane/Attitude.cpp
  3. 2
      ArduPlane/commands.cpp

3
ArduPlane/ArduPlane.cpp

@ -562,7 +562,6 @@ void Plane::update_flight_mode(void) @@ -562,7 +562,6 @@ void Plane::update_flight_mode(void)
case FLY_BY_WIRE_A: {
// set nav_roll and nav_pitch using sticks
nav_roll_cd = channel_roll->norm_input() * roll_limit_cd;
nav_roll_cd = constrain_int32(nav_roll_cd, -roll_limit_cd, roll_limit_cd);
update_load_factor();
float pitch_input = channel_pitch->norm_input();
if (pitch_input > 0) {
@ -597,7 +596,6 @@ void Plane::update_flight_mode(void) @@ -597,7 +596,6 @@ void Plane::update_flight_mode(void)
case FLY_BY_WIRE_B:
// Thanks to Yury MonZon for the altitude limit code!
nav_roll_cd = channel_roll->norm_input() * roll_limit_cd;
nav_roll_cd = constrain_int32(nav_roll_cd, -roll_limit_cd, roll_limit_cd);
update_load_factor();
update_fbwb_speed_height();
break;
@ -615,7 +613,6 @@ void Plane::update_flight_mode(void) @@ -615,7 +613,6 @@ void Plane::update_flight_mode(void)
if (!cruise_state.locked_heading) {
nav_roll_cd = channel_roll->norm_input() * roll_limit_cd;
nav_roll_cd = constrain_int32(nav_roll_cd, -roll_limit_cd, roll_limit_cd);
update_load_factor();
} else {
calc_nav_roll();

4
ArduPlane/Attitude.cpp

@ -643,7 +643,7 @@ void Plane::update_load_factor(void) @@ -643,7 +643,7 @@ void Plane::update_load_factor(void)
// our airspeed is below the minimum airspeed. Limit roll to
// 25 degrees
nav_roll_cd = constrain_int32(nav_roll_cd, -2500, 2500);
roll_limit_cd = constrain_int32(roll_limit_cd, -2500, 2500);
roll_limit_cd = MIN(roll_limit_cd, 2500);
} else if (max_load_factor < aerodynamic_load_factor) {
// the demanded nav_roll would take us past the aerodymamic
// load limit. Limit our roll to a bank angle that will keep
@ -656,6 +656,6 @@ void Plane::update_load_factor(void) @@ -656,6 +656,6 @@ void Plane::update_load_factor(void)
roll_limit = 2500;
}
nav_roll_cd = constrain_int32(nav_roll_cd, -roll_limit, roll_limit);
roll_limit_cd = constrain_int32(roll_limit_cd, -roll_limit, roll_limit);
roll_limit_cd = MIN(roll_limit_cd, roll_limit);
}
}

2
ArduPlane/commands.cpp

@ -64,8 +64,6 @@ void Plane::set_next_WP(const struct Location &loc) @@ -64,8 +64,6 @@ void Plane::set_next_WP(const struct Location &loc)
setup_glide_slope();
setup_turn_angle();
loiter_angle_reset();
}
void Plane::set_guided_WP(void)

Loading…
Cancel
Save