mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
Copter: minor formatting fixes
This commit is contained in:
parent
91bff63267
commit
05fedbf98f
@ -323,12 +323,12 @@ static void auto_land_run()
|
||||
// run loiter controller
|
||||
wp_nav.update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler);
|
||||
|
||||
float cmb_rate = get_land_descent_speed();
|
||||
|
||||
// call z-axis position controller
|
||||
float cmb_rate = get_land_descent_speed();
|
||||
pos_control.set_alt_target_from_climb_rate(cmb_rate, G_Dt, true);
|
||||
pos_control.update_z_controller();
|
||||
|
||||
// record desired climb rate for logging
|
||||
desired_climb_rate = cmb_rate;
|
||||
|
||||
// roll & pitch from waypoint controller, yaw rate from pilot
|
||||
|
@ -111,6 +111,7 @@ static void land_gps_run()
|
||||
cmb_rate = get_land_descent_speed();
|
||||
}
|
||||
|
||||
// record desired climb rate for logging
|
||||
desired_climb_rate = cmb_rate;
|
||||
|
||||
// update altitude target and call position controller
|
||||
@ -171,6 +172,7 @@ static void land_nogps_run()
|
||||
cmb_rate = get_land_descent_speed();
|
||||
}
|
||||
|
||||
// record desired climb rate for logging
|
||||
desired_climb_rate = cmb_rate;
|
||||
|
||||
// call position controller
|
||||
|
@ -380,6 +380,7 @@ static void rtl_land_run()
|
||||
pos_control.set_alt_target_from_climb_rate(cmb_rate, G_Dt, true);
|
||||
pos_control.update_z_controller();
|
||||
|
||||
// record desired climb rate for logging
|
||||
desired_climb_rate = cmb_rate;
|
||||
|
||||
// roll & pitch from waypoint controller, yaw rate from pilot
|
||||
|
Loading…
Reference in New Issue
Block a user