mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 01:28:29 -04:00
ArduCopter: stop unnecessary updates of target altitude and knock-on effect of too many EV message in dataflash log
This commit is contained in:
parent
1332ed3b5c
commit
c8c13046e3
@ -99,6 +99,13 @@ void set_land_complete(bool b)
|
||||
// ---------------------------------------------
|
||||
|
||||
void set_alt_change(uint8_t flag){
|
||||
|
||||
// if no change, exit immediately
|
||||
if( alt_change_flag == flag ) {
|
||||
return;
|
||||
}
|
||||
|
||||
// update flag
|
||||
alt_change_flag = flag;
|
||||
|
||||
if(flag == REACHED_ALT){
|
||||
|
@ -1010,7 +1010,7 @@ get_throttle_rate_stabilized(int16_t target_rate)
|
||||
// do not let target altitude get too far from current altitude
|
||||
target_alt = constrain(target_alt,current_loc.alt-750,current_loc.alt+750);
|
||||
|
||||
force_new_altitude(target_alt);
|
||||
set_new_altitude(target_alt);
|
||||
|
||||
get_throttle_althold(target_alt, ALTHOLD_MAX_CLIMB_RATE);
|
||||
}
|
||||
|
@ -541,6 +541,12 @@ static void force_new_altitude(int32_t new_alt)
|
||||
|
||||
static void set_new_altitude(int32_t new_alt)
|
||||
{
|
||||
// if no change exit immediately
|
||||
if(new_alt == next_WP.alt) {
|
||||
return;
|
||||
}
|
||||
|
||||
// update new target altitude
|
||||
next_WP.alt = new_alt;
|
||||
|
||||
if(next_WP.alt > (current_loc.alt + 80)) {
|
||||
|
Loading…
Reference in New Issue
Block a user