Browse Source

Copter: integrate surface_tracking to control_althold

master
Randy Mackay 11 years ago committed by Andrew Tridgell
parent
commit
22280e1c57
  1. 2
      ArduCopter/control_althold.pde
  2. 2
      ArduCopter/control_circle.pde
  3. 2
      ArduCopter/control_loiter.pde
  4. 2
      ArduCopter/control_ofloiter.pde
  5. 2
      ArduCopter/control_sport.pde

2
ArduCopter/control_althold.pde

@ -62,7 +62,7 @@ static void althold_run() @@ -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

2
ArduCopter/control_circle.pde

@ -64,7 +64,7 @@ static void circle_run() @@ -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);

2
ArduCopter/control_loiter.pde

@ -74,7 +74,7 @@ static void loiter_run() @@ -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

2
ArduCopter/control_ofloiter.pde

@ -71,7 +71,7 @@ static void ofloiter_run() @@ -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

2
ArduCopter/control_sport.pde

@ -57,7 +57,7 @@ static void sport_run() @@ -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…
Cancel
Save