Copter: current alt is alt above-ekf-origin until home set

This commit is contained in:
Randy Mackay 2015-05-13 15:24:52 +09:00
parent 3f8b832075
commit 2a1a105462
1 changed files with 12 additions and 4 deletions

View File

@ -10,13 +10,21 @@ 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)) {
// exit immediately if we do not have an altitude estimate
if (!inertial_nav.get_filter_status().flags.vert_pos) {
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());
// without home return alt above the EKF origin
if (ap.home_state == HOME_UNSET) {
// with inertial nav we can update the altitude and climb rate at 50hz
current_loc.alt = inertial_nav.get_altitude();
} else {
// with inertial nav we can update the altitude and climb rate at 50hz
current_loc.alt = pv_alt_above_home(inertial_nav.get_altitude());
}
// set flags and get velocity
current_loc.flags.relative_alt = true;
climb_rate = inertial_nav.get_velocity_z();
}