mirror of https://github.com/ArduPilot/ardupilot
Copter: update inertial alt only after home is set
This commit is contained in:
parent
2bec00e1c5
commit
c3bdb9a13e
|
@ -10,6 +10,11 @@ static void read_inertia()
|
|||
// read_inertial_altitude - pull altitude and climb rate from inertial nav library
|
||||
static void read_inertial_altitude()
|
||||
{
|
||||
// exit immediately if we do not have an altitude estimate or home is not set
|
||||
if (!inertial_nav.get_filter_status().flags.vert_pos || (ap.home_state == HOME_UNSET)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// with inertial nav we can update the altitude and climb rate at 50hz
|
||||
current_loc.alt = pv_alt_above_home(inertial_nav.get_altitude());
|
||||
current_loc.flags.relative_alt = true;
|
||||
|
|
Loading…
Reference in New Issue