mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: integrate surface_tracking to control_althold
This commit is contained in:
parent
3824f528ea
commit
22280e1c57
@ -62,7 +62,7 @@ static void althold_run()
|
||||
// call throttle controller
|
||||
if (sonar_alt_health >= SONAR_ALT_HEALTH_MAX) {
|
||||
// if sonar is ok, use surface tracking
|
||||
target_climb_rate = get_throttle_surface_tracking(target_climb_rate, G_Dt);
|
||||
target_climb_rate = get_throttle_surface_tracking(target_climb_rate, pos_control.get_alt_target(), G_Dt);
|
||||
}
|
||||
|
||||
// call position controller
|
||||
|
@ -64,7 +64,7 @@ static void circle_run()
|
||||
// run altitude controller
|
||||
if (sonar_alt_health >= SONAR_ALT_HEALTH_MAX) {
|
||||
// if sonar is ok, use surface tracking
|
||||
target_climb_rate = get_throttle_surface_tracking(target_climb_rate,G_Dt);
|
||||
target_climb_rate = get_throttle_surface_tracking(target_climb_rate, pos_control.get_alt_target(), G_Dt);
|
||||
}
|
||||
// update altitude target and call position controller
|
||||
pos_control.set_alt_target_from_climb_rate(target_climb_rate, G_Dt);
|
||||
|
@ -74,7 +74,7 @@ static void loiter_run()
|
||||
// run altitude controller
|
||||
if (sonar_alt_health >= SONAR_ALT_HEALTH_MAX) {
|
||||
// if sonar is ok, use surface tracking
|
||||
target_climb_rate = get_throttle_surface_tracking(target_climb_rate,G_Dt);
|
||||
target_climb_rate = get_throttle_surface_tracking(target_climb_rate, pos_control.get_alt_target(), G_Dt);
|
||||
}
|
||||
|
||||
// update altitude target and call position controller
|
||||
|
@ -71,7 +71,7 @@ static void ofloiter_run()
|
||||
// run altitude controller
|
||||
if (sonar_alt_health >= SONAR_ALT_HEALTH_MAX) {
|
||||
// if sonar is ok, use surface tracking
|
||||
target_climb_rate = get_throttle_surface_tracking(target_climb_rate,G_Dt);
|
||||
target_climb_rate = get_throttle_surface_tracking(target_climb_rate, pos_control.get_alt_target(), G_Dt);
|
||||
}
|
||||
|
||||
// update altitude target and call position controller
|
||||
|
@ -57,7 +57,7 @@ static void sport_run()
|
||||
// call throttle controller
|
||||
if (sonar_alt_health >= SONAR_ALT_HEALTH_MAX) {
|
||||
// if sonar is ok, use surface tracking
|
||||
target_climb_rate = get_throttle_surface_tracking(target_climb_rate, G_Dt);
|
||||
target_climb_rate = get_throttle_surface_tracking(target_climb_rate, pos_control.get_alt_target(), G_Dt);
|
||||
}
|
||||
|
||||
// call position controller
|
||||
|
Loading…
Reference in New Issue
Block a user