From fddaca4cf7fbd432fdde4449762868a6147ac5dd Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Mon, 13 Apr 2015 11:03:38 -0700 Subject: [PATCH] Copter: rename get_throttle_surface_tracking to get_surface_tracking_climb_rate --- ArduCopter/Attitude.pde | 4 ++-- ArduCopter/control_althold.pde | 2 +- ArduCopter/control_circle.pde | 2 +- ArduCopter/control_loiter.pde | 2 +- ArduCopter/control_poshold.pde | 2 +- ArduCopter/control_sport.pde | 2 +- 6 files changed, 7 insertions(+), 7 deletions(-) diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index 5eecc8c206..ffa83cf095 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -225,9 +225,9 @@ static int16_t get_throttle_pre_takeoff(int16_t throttle_control) return throttle_out; } -// get_throttle_surface_tracking - hold copter at the desired distance above the ground +// get_surface_tracking_climb_rate - hold copter at the desired distance above the ground // returns climb rate (in cm/s) which should be passed to the position controller -static float get_throttle_surface_tracking(int16_t target_rate, float current_alt_target, float dt) +static float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt) { static uint32_t last_call_ms = 0; float distance_error; diff --git a/ArduCopter/control_althold.pde b/ArduCopter/control_althold.pde index 7b6029bc74..88d822343e 100644 --- a/ArduCopter/control_althold.pde +++ b/ArduCopter/control_althold.pde @@ -70,7 +70,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, pos_control.get_alt_target(), G_Dt); + target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate, pos_control.get_alt_target(), G_Dt); } // call position controller diff --git a/ArduCopter/control_circle.pde b/ArduCopter/control_circle.pde index 7e7d13e418..6b34e37e53 100644 --- a/ArduCopter/control_circle.pde +++ b/ArduCopter/control_circle.pde @@ -75,7 +75,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, pos_control.get_alt_target(), G_Dt); + target_climb_rate = get_surface_tracking_climb_rate(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); diff --git a/ArduCopter/control_loiter.pde b/ArduCopter/control_loiter.pde index c624278733..1a5a66cb4e 100644 --- a/ArduCopter/control_loiter.pde +++ b/ArduCopter/control_loiter.pde @@ -93,7 +93,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, pos_control.get_alt_target(), G_Dt); + target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate, pos_control.get_alt_target(), G_Dt); } // update altitude target and call position controller diff --git a/ArduCopter/control_poshold.pde b/ArduCopter/control_poshold.pde index 3659906710..14da97a615 100644 --- a/ArduCopter/control_poshold.pde +++ b/ArduCopter/control_poshold.pde @@ -521,7 +521,7 @@ static void poshold_run() // throttle control 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, pos_control.get_alt_target(), G_Dt); + target_climb_rate = get_surface_tracking_climb_rate(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); diff --git a/ArduCopter/control_sport.pde b/ArduCopter/control_sport.pde index 7626320848..7f1c976ffc 100644 --- a/ArduCopter/control_sport.pde +++ b/ArduCopter/control_sport.pde @@ -90,7 +90,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, pos_control.get_alt_target(), G_Dt); + target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate, pos_control.get_alt_target(), G_Dt); } // call position controller