Browse Source

Copter: rename get_throttle_surface_tracking to get_surface_tracking_climb_rate

master
Jonathan Challinger 10 years ago committed by Randy Mackay
parent
commit
fddaca4cf7
  1. 4
      ArduCopter/Attitude.pde
  2. 2
      ArduCopter/control_althold.pde
  3. 2
      ArduCopter/control_circle.pde
  4. 2
      ArduCopter/control_loiter.pde
  5. 2
      ArduCopter/control_poshold.pde
  6. 2
      ArduCopter/control_sport.pde

4
ArduCopter/Attitude.pde

@ -225,9 +225,9 @@ static int16_t get_throttle_pre_takeoff(int16_t throttle_control) @@ -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;

2
ArduCopter/control_althold.pde

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

2
ArduCopter/control_circle.pde

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

2
ArduCopter/control_loiter.pde

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

2
ArduCopter/control_poshold.pde

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

2
ArduCopter/control_sport.pde

@ -90,7 +90,7 @@ static void sport_run() @@ -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

Loading…
Cancel
Save