mirror of https://github.com/ArduPilot/ardupilot
Copter: replace wp_nav.get_target_alt with get_destination_alt
This commit is contained in:
parent
3bfcc3b8d0
commit
4de5f67a91
|
@ -1969,7 +1969,7 @@ void update_throttle_mode(void)
|
|||
case THROTTLE_AUTO:
|
||||
// auto pilot altitude controller with target altitude held in next_WP.alt
|
||||
if(motors.auto_armed() == true) {
|
||||
get_throttle_althold_with_slew(wp_nav.get_target_alt(), g.auto_velocity_z_min, g.auto_velocity_z_max);
|
||||
get_throttle_althold_with_slew(wp_nav.get_destination_alt(), g.auto_velocity_z_min, g.auto_velocity_z_max);
|
||||
}
|
||||
break;
|
||||
|
||||
|
|
|
@ -550,7 +550,7 @@ static void Log_Write_Control_Tuning()
|
|||
throttle_in : g.rc_3.control_in,
|
||||
sonar_alt : sonar_alt,
|
||||
baro_alt : baro_alt,
|
||||
next_wp_alt : wp_nav.get_target_alt(),
|
||||
next_wp_alt : wp_nav.get_destination_alt(),
|
||||
nav_throttle : nav_throttle,
|
||||
angle_boost : angle_boost,
|
||||
climb_rate : climb_rate,
|
||||
|
|
|
@ -190,19 +190,19 @@ static bool check_missed_wp()
|
|||
static void force_new_altitude(float new_alt)
|
||||
{
|
||||
// update new target altitude
|
||||
wp_nav.set_target_alt(new_alt);
|
||||
wp_nav.set_destination_alt(new_alt);
|
||||
set_alt_change(REACHED_ALT);
|
||||
}
|
||||
|
||||
static void set_new_altitude(float new_alt)
|
||||
{
|
||||
// if no change exit immediately
|
||||
if(new_alt == wp_nav.get_target_alt()) {
|
||||
if(new_alt == wp_nav.get_destination_alt()) {
|
||||
return;
|
||||
}
|
||||
|
||||
// update new target altitude
|
||||
wp_nav.set_target_alt(new_alt);
|
||||
wp_nav.set_destination_alt(new_alt);
|
||||
|
||||
if(new_alt > (current_loc.alt + 80)) {
|
||||
// we are below, going up
|
||||
|
@ -223,12 +223,12 @@ static void verify_altitude()
|
|||
{
|
||||
if(alt_change_flag == ASCENDING) {
|
||||
// we are below, going up
|
||||
if(current_loc.alt > wp_nav.get_target_alt() - 50) {
|
||||
if(current_loc.alt > wp_nav.get_destination_alt() - 50) {
|
||||
set_alt_change(REACHED_ALT);
|
||||
}
|
||||
}else if (alt_change_flag == DESCENDING) {
|
||||
// we are above, going down
|
||||
if(current_loc.alt <= wp_nav.get_target_alt() + 50){
|
||||
if(current_loc.alt <= wp_nav.get_destination_alt() + 50){
|
||||
set_alt_change(REACHED_ALT);
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue