Copter: Add velocity gain scaler to interfaces

Allows nav gain to be scaled to compensate for optical flow noise
This commit is contained in:
priseborough 2014-11-16 14:06:05 +11:00 committed by Andrew Tridgell
parent e80b1c67cd
commit 963cc4d60a
6 changed files with 8 additions and 8 deletions

View File

@ -321,7 +321,7 @@ static void auto_land_run()
wp_nav.set_pilot_desired_acceleration(roll_control, pitch_control);
// run loiter controller
wp_nav.update_loiter(ekfGndSpdLimit);
wp_nav.update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler);
// call z-axis position controller
pos_control.set_alt_target_from_climb_rate(get_throttle_land(), G_Dt, true);

View File

@ -256,7 +256,7 @@ static void guided_vel_control_run()
}
// call velocity controller which includes z axis controller
pos_control.update_vel_controller_xyz();
pos_control.update_vel_controller_xyz(ekfNavVelGainScaler);
// call attitude controller
if (auto_yaw_mode == AUTO_YAW_HOLD) {

View File

@ -97,7 +97,7 @@ static void land_gps_run()
wp_nav.set_pilot_desired_acceleration(roll_control, pitch_control);
// run loiter controller
wp_nav.update_loiter(ekfGndSpdLimit);
wp_nav.update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler);
// call attitude controller
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);

View File

@ -83,7 +83,7 @@ static void loiter_run()
pos_control.set_alt_target_to_current_alt();
}else{
// run loiter controller
wp_nav.update_loiter(ekfGndSpdLimit);
wp_nav.update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler);
// call attitude controller
attitude_control.angle_ef_roll_pitch_rate_ef_yaw(wp_nav.get_roll(), wp_nav.get_pitch(), target_yaw_rate);

View File

@ -441,7 +441,7 @@ static void poshold_run()
poshold_update_brake_angle_from_velocity(poshold.brake_pitch, -vel_fw);
// run loiter controller
wp_nav.update_loiter(ekfGndSpdLimit);
wp_nav.update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler);
// calculate final roll and pitch output by mixing loiter and brake controls
poshold.roll = poshold_mix_controls(brake_to_loiter_mix, poshold.brake_roll + poshold.wind_comp_roll, wp_nav.get_roll());
@ -472,7 +472,7 @@ static void poshold_run()
case POSHOLD_LOITER:
// run loiter controller
wp_nav.update_loiter(ekfGndSpdLimit);
wp_nav.update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler);
// set roll angle based on loiter controller outputs
poshold.roll = wp_nav.get_roll();

View File

@ -289,7 +289,7 @@ static void rtl_descent_run()
wp_nav.set_pilot_desired_acceleration(roll_control, pitch_control);
// run loiter controller
wp_nav.update_loiter(ekfGndSpdLimit);
wp_nav.update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler);
// call z-axis position controller
pos_control.set_alt_target_with_slew(g.rtl_alt_final, G_Dt);
@ -373,7 +373,7 @@ static void rtl_land_run()
wp_nav.set_pilot_desired_acceleration(roll_control, pitch_control);
// run loiter controller
wp_nav.update_loiter(ekfGndSpdLimit);
wp_nav.update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler);
// call z-axis position controller
float cmb_rate = get_throttle_land();