void DeclarativeWebContainer::setForeground(bool active)
{
    if (m_foreground != active) {
        m_foreground = active;

        if (!m_foreground) {
            // Respect content height when browser brought back from home
            resetHeight(true);
        }
        emit foregroundChanged();
    }
}
DeclarativeWebContainer::DeclarativeWebContainer(QQuickItem *parent)
    : QQuickItem(parent)
    , m_webPage(0)
    , m_model(0)
    , m_webPageComponent(0)
    , m_settingManager(SettingManager::instance())
    , m_foreground(true)
    , m_allowHiding(true)
    , m_popupActive(false)
    , m_portrait(true)
    , m_fullScreenMode(false)
    , m_fullScreenHeight(0.0)
    , m_inputPanelVisible(false)
    , m_inputPanelHeight(0.0)
    , m_inputPanelOpenHeight(0.0)
    , m_toolbarHeight(0.0)
    , m_tabId(0)
    , m_loading(false)
    , m_loadProgress(0)
    , m_canGoForward(false)
    , m_canGoBack(false)
    , m_realNavigation(false)
    , m_completed(false)
    , m_initialized(false)
{
    m_webPages.reset(new WebPages(this));
    setFlag(QQuickItem::ItemHasContents, true);
    connect(DownloadManager::instance(), SIGNAL(downloadStarted()), this, SLOT(onDownloadStarted()));
    connect(QMozContext::GetInstance(), SIGNAL(onInitialized()), this, SLOT(initialize()));
    connect(this, SIGNAL(portraitChanged()), this, SLOT(resetHeight()));
    connect(this, SIGNAL(enabledChanged()), this, SLOT(handleEnabledChanged()));

    QString cacheLocation = QStandardPaths::writableLocation(QStandardPaths::CacheLocation);
    QDir dir(cacheLocation);
    if(!dir.exists() && !dir.mkpath(cacheLocation)) {
        qWarning() << "Can't create directory "+ cacheLocation;
        return;
    }

    connect(this, SIGNAL(heightChanged()), this, SLOT(sendVkbOpenCompositionMetrics()));
    connect(this, SIGNAL(widthChanged()), this, SLOT(sendVkbOpenCompositionMetrics()));

    qApp->installEventFilter(this);
}
Exemplo n.º 3
0
void Ekf::controlExternalVisionFusion()
{
	// Check for new exernal vision data
	if (_ev_data_ready) {

		// external vision position aiding selection logic
		if ((_params.fusion_mode & MASK_USE_EVPOS) && !_control_status.flags.ev_pos && _control_status.flags.tilt_align && _control_status.flags.yaw_align) {
			// check for a exernal vision measurement that has fallen behind the fusion time horizon
			if (_time_last_imu - _time_last_ext_vision < 2 * EV_MAX_INTERVAL) {
				// turn on use of external vision measurements for position and height
				_control_status.flags.ev_pos = true;
				ECL_INFO("EKF switching to external vision position fusion");
				// turn off other forms of height aiding
				_control_status.flags.baro_hgt = false;
				_control_status.flags.gps_hgt = false;
				_control_status.flags.rng_hgt = false;
				// reset the position, height and velocity
				resetPosition();
				resetVelocity();
				resetHeight();
			}
		}

		// external vision yaw aiding selection logic
		if ((_params.fusion_mode & MASK_USE_EVYAW) && !_control_status.flags.ev_yaw && _control_status.flags.tilt_align) {
			// check for a exernal vision measurement that has fallen behind the fusion time horizon
			if (_time_last_imu - _time_last_ext_vision < 2 * EV_MAX_INTERVAL) {
				// reset the yaw angle to the value from the observaton quaternion
				// get the roll, pitch, yaw estimates from the quaternion states
				matrix::Quaternion<float> q_init(_state.quat_nominal(0), _state.quat_nominal(1), _state.quat_nominal(2),
							    _state.quat_nominal(3));
				matrix::Euler<float> euler_init(q_init);

				// get initial yaw from the observation quaternion
				extVisionSample ev_newest = _ext_vision_buffer.get_newest();
				matrix::Quaternion<float> q_obs(ev_newest.quat(0), ev_newest.quat(1), ev_newest.quat(2), ev_newest.quat(3));
				matrix::Euler<float> euler_obs(q_obs);
				euler_init(2) = euler_obs(2);

				// save a copy of the quaternion state for later use in calculating the amount of reset change
				Quaternion quat_before_reset = _state.quat_nominal;

				// calculate initial quaternion states for the ekf
				_state.quat_nominal = Quaternion(euler_init);

				// calculate the amount that the quaternion has changed by
				_state_reset_status.quat_change = _state.quat_nominal * quat_before_reset.inversed();

				// add the reset amount to the output observer buffered data
				outputSample output_states;
				unsigned output_length = _output_buffer.get_length();
				for (unsigned i=0; i < output_length; i++) {
					output_states = _output_buffer.get_from_index(i);
					output_states.quat_nominal *= _state_reset_status.quat_change;
					_output_buffer.push_to_index(i,output_states);
				}

				// capture the reset event
				_state_reset_status.quat_counter++;

				// flag the yaw as aligned
				_control_status.flags.yaw_align = true;

				// turn on fusion of external vision yaw measurements and disable all magnetoemter fusion
				_control_status.flags.ev_yaw = true;
				_control_status.flags.mag_hdg = false;
				_control_status.flags.mag_3D = false;
				_control_status.flags.mag_dec = false;

				ECL_INFO("EKF switching to external vision yaw fusion");
			}
		}

		// determine if we should use the height observation
		if (_params.vdist_sensor_type == VDIST_SENSOR_EV) {
			_control_status.flags.baro_hgt = false;
			_control_status.flags.gps_hgt = false;
			_control_status.flags.rng_hgt = false;
			_control_status.flags.ev_hgt = true;
			_fuse_height = true;

		}

		// determine if we should use the horizontal position observations
		if (_control_status.flags.ev_pos) {
			_fuse_pos = true;

			// correct position and height for offset relative to IMU
			Vector3f pos_offset_body = _params.ev_pos_body - _params.imu_pos_body;
			Vector3f pos_offset_earth = _R_to_earth * pos_offset_body;
			_ev_sample_delayed.posNED(0) -= pos_offset_earth(0);
			_ev_sample_delayed.posNED(1) -= pos_offset_earth(1);
			_ev_sample_delayed.posNED(2) -= pos_offset_earth(2);
		}

		// determine if we should use the yaw observation
		if (_control_status.flags.ev_yaw) {
			fuseHeading();
		}
	}
}
Exemplo n.º 4
0
void Ekf::controlHeightSensorTimeouts()
{
	/*
	 * Handle the case where we have not fused height measurements recently and
	 * uncertainty exceeds the max allowable. Reset using the best available height
	 * measurement source, continue using it after the reset and declare the current
	 * source failed if we have switched.
	*/

	// check for inertial sensing errors as evidenced by the vertical innovations having the same sign and not stale
	bool bad_vert_accel = (_control_status.flags.baro_hgt && // we can only run this check if vertical position and velocity observations are indepedant
			(_vel_pos_innov[5] * _vel_pos_innov[2] > 0.0f) && // vertical position and velocity sensors are in agreement
			((_imu_sample_delayed.time_us - _baro_sample_delayed.time_us) < 2 * BARO_MAX_INTERVAL) && // vertical position data is fresh
			((_imu_sample_delayed.time_us - _gps_sample_delayed.time_us) < 2 * GPS_MAX_INTERVAL) &&  // vertical velocity data is freshs
			_vel_pos_test_ratio[2] > 1.0f && // vertical velocty innovations have failed innovation consistency checks
			_vel_pos_test_ratio[5] > 1.0f); // vertical position innovations have failed innovation consistency checks

	// record time of last bad vert accel
	if (bad_vert_accel) {
		_time_bad_vert_accel =  _time_last_imu;
	}

	if ((P[9][9] > sq(_params.hgt_reset_lim)) && ((_time_last_imu - _time_last_hgt_fuse) > 5e6)) {
		// boolean that indicates we will do a height reset
		bool reset_height = false;

		// handle the case where we are using baro for height
		if (_control_status.flags.baro_hgt) {
			// check if GPS height is available
			gpsSample gps_init = _gps_buffer.get_newest();
			bool gps_hgt_available = ((_time_last_imu - gps_init.time_us) < 2 * GPS_MAX_INTERVAL);
			bool gps_hgt_accurate = (gps_init.vacc < _params.req_vacc);
			baroSample baro_init = _baro_buffer.get_newest();
			bool baro_hgt_available = ((_time_last_imu - baro_init.time_us) < 2 * BARO_MAX_INTERVAL);

			// check for inertial sensing errors in the last 10 seconds
			bool prev_bad_vert_accel = (_time_last_imu - _time_bad_vert_accel < 10E6);

			// reset to GPS if adequate GPS data is available and the timeout cannot be blamed on IMU data
			bool reset_to_gps = gps_hgt_available && gps_hgt_accurate && !_gps_hgt_faulty && !prev_bad_vert_accel;

			// reset to GPS if GPS data is available and there is no Baro data
			reset_to_gps = reset_to_gps || (gps_hgt_available && !baro_hgt_available);

			// reset to Baro if we are not doing a GPS reset and baro data is available
			bool reset_to_baro = !reset_to_gps && baro_hgt_available;

			if (reset_to_gps) {
				// set height sensor health
				_baro_hgt_faulty = true;
				_gps_hgt_faulty = false;

				// declare the GPS height healthy
				_gps_hgt_faulty = false;

				// reset the height mode
				_control_status.flags.baro_hgt = false;
				_control_status.flags.gps_hgt = true;
				_control_status.flags.rng_hgt = false;
				_control_status.flags.ev_hgt = false;

				// request a reset
				reset_height = true;
				ECL_INFO("EKF baro hgt timeout - reset to GPS");

			} else if (reset_to_baro){
				// set height sensor health
				_baro_hgt_faulty = false;

				// reset the height mode
				_control_status.flags.baro_hgt = true;
				_control_status.flags.gps_hgt = false;
				_control_status.flags.rng_hgt = false;
				_control_status.flags.ev_hgt = false;

				// request a reset
				reset_height = true;
				ECL_INFO("EKF baro hgt timeout - reset to baro");

			} else {
				// we have nothing we can reset to
				// deny a reset
				reset_height = false;

			}
		}

		// handle the case we are using GPS for height
		if (_control_status.flags.gps_hgt) {
			// check if GPS height is available
			gpsSample gps_init = _gps_buffer.get_newest();
			bool gps_hgt_available = ((_time_last_imu - gps_init.time_us) < 2 * GPS_MAX_INTERVAL);
			bool gps_hgt_accurate = (gps_init.vacc < _params.req_vacc);

			// check the baro height source for consistency and freshness
			baroSample baro_init = _baro_buffer.get_newest();
			bool baro_data_fresh = ((_time_last_imu - baro_init.time_us) < 2 * BARO_MAX_INTERVAL);
			float baro_innov = _state.pos(2) - (_hgt_sensor_offset - baro_init.hgt + _baro_hgt_offset);
			bool baro_data_consistent = fabsf(baro_innov) < (sq(_params.baro_noise) + P[8][8]) * sq(_params.baro_innov_gate);

			// if baro data is acceptable and GPS data is inaccurate, reset height to baro
			bool reset_to_baro = baro_data_consistent && baro_data_fresh && !_baro_hgt_faulty && !gps_hgt_accurate;

			// if GPS height is unavailable and baro data is available, reset height to baro
			reset_to_baro = reset_to_baro || (!gps_hgt_available && baro_data_fresh);

			// if we cannot switch to baro and GPS data is available, reset height to GPS
			bool reset_to_gps = !reset_to_baro && gps_hgt_available;

			if (reset_to_baro) {
				// set height sensor health
				_gps_hgt_faulty = true;
				_baro_hgt_faulty = false;

				// reset the height mode
				_control_status.flags.baro_hgt = true;
				_control_status.flags.gps_hgt = false;
				_control_status.flags.rng_hgt = false;
				_control_status.flags.ev_hgt = false;

				// request a reset
				reset_height = true;
				ECL_INFO("EKF gps hgt timeout - reset to baro");

			} else if (reset_to_gps) {
				// set height sensor health
				_gps_hgt_faulty = false;

				// reset the height mode
				_control_status.flags.baro_hgt = false;
				_control_status.flags.gps_hgt = true;
				_control_status.flags.rng_hgt = false;
				_control_status.flags.ev_hgt = false;

				// request a reset
				reset_height = true;
				ECL_INFO("EKF gps hgt timeout - reset to GPS");

			} else {
				// we have nothing to reset to
				reset_height = false;

			}
		}

		// handle the case we are using range finder for height
		if (_control_status.flags.rng_hgt) {
			// check if range finder data is available
			rangeSample rng_init = _range_buffer.get_newest();
			bool rng_data_available = ((_time_last_imu - rng_init.time_us) < 2 * RNG_MAX_INTERVAL);

			// check if baro data is available
			baroSample baro_init = _baro_buffer.get_newest();
			bool baro_data_available = ((_time_last_imu - baro_init.time_us) < 2 * BARO_MAX_INTERVAL);

			// reset to baro if we have no range data and baro data is available
			bool reset_to_baro = !rng_data_available && baro_data_available;

			// reset to range data if it is available
			bool reset_to_rng = rng_data_available;

			if (reset_to_baro) {
				// set height sensor health
				_rng_hgt_faulty = true;
				_baro_hgt_faulty = false;

				// reset the height mode
				_control_status.flags.baro_hgt = true;
				_control_status.flags.gps_hgt = false;
				_control_status.flags.rng_hgt = false;
				_control_status.flags.ev_hgt = false;

				// request a reset
				reset_height = true;
				ECL_INFO("EKF rng hgt timeout - reset to baro");

			} else if (reset_to_rng) {
				// set height sensor health
				_rng_hgt_faulty = false;

				// reset the height mode
				_control_status.flags.baro_hgt = false;
				_control_status.flags.gps_hgt = false;
				_control_status.flags.rng_hgt = true;
				_control_status.flags.ev_hgt = false;

				// request a reset
				reset_height = true;
				ECL_INFO("EKF rng hgt timeout - reset to rng hgt");

			} else {
				// we have nothing to reset to
				reset_height = false;

			}
		}

		// handle the case where we are using external vision data for height
		if (_control_status.flags.ev_hgt) {
			// check if vision data is available
			extVisionSample ev_init = _ext_vision_buffer.get_newest();
			bool ev_data_available = ((_time_last_imu - ev_init.time_us) < 2 * EV_MAX_INTERVAL);

			// check if baro data is available
			baroSample baro_init = _baro_buffer.get_newest();
			bool baro_data_available = ((_time_last_imu - baro_init.time_us) < 2 * BARO_MAX_INTERVAL);

			// reset to baro if we have no vision data and baro data is available
			bool reset_to_baro = !ev_data_available && baro_data_available;

			// reset to ev data if it is available
			bool reset_to_ev = ev_data_available;

			if (reset_to_baro) {
				// set height sensor health
				_rng_hgt_faulty = true;
				_baro_hgt_faulty = false;

				// reset the height mode
				_control_status.flags.baro_hgt = true;
				_control_status.flags.gps_hgt = false;
				_control_status.flags.rng_hgt = false;
				_control_status.flags.ev_hgt = false;

				// request a reset
				reset_height = true;
				ECL_INFO("EKF ev hgt timeout - reset to baro");

			} else if (reset_to_ev) {
				// reset the height mode
				_control_status.flags.baro_hgt = false;
				_control_status.flags.gps_hgt = false;
				_control_status.flags.rng_hgt = false;
				_control_status.flags.ev_hgt = true;

				// request a reset
				reset_height = true;
				ECL_INFO("EKF ev hgt timeout - reset to ev hgt");

			} else {
				// we have nothing to reset to
				reset_height = false;

			}
		}

		// Reset vertical position and velocity states to the last measurement
		if (reset_height) {
			resetHeight();
			// Reset the timout timer
			_time_last_hgt_fuse = _time_last_imu;

		}

	}
}
Exemplo n.º 5
0
void Ekf::controlExternalVisionAiding()
{
	// external vision position aiding selection logic
	if ((_params.fusion_mode & MASK_USE_EVPOS) && !_control_status.flags.ev_pos && _control_status.flags.tilt_align && _control_status.flags.yaw_align) {
		// check for a exernal vision measurement that has fallen behind the fusion time horizon
		if (_time_last_imu - _time_last_ext_vision < 2 * EV_MAX_INTERVAL) {
			// turn on use of external vision measurements for position and height
			_control_status.flags.ev_pos = true;
			printf("EKF switching to external vision position fusion\n");
			// turn off other forms of height aiding
			_control_status.flags.baro_hgt = false;
			_control_status.flags.gps_hgt = false;
			_control_status.flags.rng_hgt = false;
			// reset the position, height and velocity
			resetPosition();
			resetVelocity();
			resetHeight();
		}
	}

	// external vision yaw aiding selection logic
	if ((_params.fusion_mode & MASK_USE_EVYAW) && !_control_status.flags.ev_yaw && _control_status.flags.tilt_align) {
		// check for a exernal vision measurement that has fallen behind the fusion time horizon
		if (_time_last_imu - _time_last_ext_vision < 2 * EV_MAX_INTERVAL) {
			// reset the yaw angle to the value from the observaton quaternion
			// get the roll, pitch, yaw estimates from the quaternion states
			matrix::Quaternion<float> q_init(_state.quat_nominal(0), _state.quat_nominal(1), _state.quat_nominal(2),
						    _state.quat_nominal(3));
			matrix::Euler<float> euler_init(q_init);

			// get initial yaw from the observation quaternion
			extVisionSample ev_newest = _ext_vision_buffer.get_newest();
			matrix::Quaternion<float> q_obs(ev_newest.quat(0), ev_newest.quat(1), ev_newest.quat(2), ev_newest.quat(3));
			matrix::Euler<float> euler_obs(q_obs);
			euler_init(2) = euler_obs(2);

			// save a copy of the quaternion state for later use in calculating the amount of reset change
			Quaternion quat_before_reset = _state.quat_nominal;

			// calculate initial quaternion states for the ekf
			_state.quat_nominal = Quaternion(euler_init);

			// calculate the amount that the quaternion has changed by
			_state_reset_status.quat_change = _state.quat_nominal * quat_before_reset.inversed();

			// add the reset amount to the output observer buffered data
			outputSample output_states;
			unsigned output_length = _output_buffer.get_length();
			for (unsigned i=0; i < output_length; i++) {
				output_states = _output_buffer.get_from_index(i);
				output_states.quat_nominal *= _state_reset_status.quat_change;
				_output_buffer.push_to_index(i,output_states);
			}

			// capture the reset event
			_state_reset_status.quat_counter++;

			// flag the yaw as aligned
			_control_status.flags.yaw_align = true;

			// turn on fusion of external vision yaw measurements and disable all magnetoemter fusion
			_control_status.flags.ev_yaw = true;
			_control_status.flags.mag_hdg = false;
			_control_status.flags.mag_3D = false;
			_control_status.flags.mag_dec = false;

			printf("EKF switching to external vision yaw fusion\n");
		}
	}

}
Exemplo n.º 6
0
void Ekf::controlFusionModes()
{
	// Determine the vehicle status
	calculateVehicleStatus();

	// Get the magnetic declination
	calcMagDeclination();

	// Check for tilt convergence during initial alignment
	// filter the tilt error vector using a 1 sec time constant LPF
	float filt_coef = 1.0f * _imu_sample_delayed.delta_ang_dt;
	_tilt_err_length_filt = filt_coef * _tilt_err_vec.norm() + (1.0f - filt_coef) * _tilt_err_length_filt;

	// Once the tilt error has reduced sufficiently, initialise the yaw and magnetic field states
	if (_tilt_err_length_filt < 0.005f && !_control_status.flags.tilt_align) {
		_control_status.flags.tilt_align = true;
		_control_status.flags.yaw_align = resetMagHeading(_mag_sample_delayed.mag);
	}

	// optical flow fusion mode selection logic
	// to start using optical flow data we need angular alignment complete, and fresh optical flow and height above terrain data
	if ((_params.fusion_mode & MASK_USE_OF) && !_control_status.flags.opt_flow && _control_status.flags.tilt_align
	    && (_time_last_imu - _time_last_optflow) < 5e5 && (_time_last_imu - _time_last_hagl_fuse) < 5e5) {
		// If the heading is not aligned, reset the yaw and magnetic field states
		if (!_control_status.flags.yaw_align) {
			_control_status.flags.yaw_align = resetMagHeading(_mag_sample_delayed.mag);
		}

		// If the heading is valid, start using optical flow aiding
		if (_control_status.flags.yaw_align) {
			// set the flag and reset the fusion timeout
			_control_status.flags.opt_flow = true;
			_time_last_of_fuse = _time_last_imu;

			// if we are not using GPS and are in air, then we need to reset the velocity to be consistent with the optical flow reading
			if (!_control_status.flags.gps) {
				// calculate the rotation matrix from body to earth frame
				matrix::Dcm<float> body_to_earth(_state.quat_nominal);

				// constrain height above ground to be above minimum possible
				float heightAboveGndEst = fmaxf((_terrain_vpos - _state.pos(2)), _params.rng_gnd_clearance);

				// calculate absolute distance from focal point to centre of frame assuming a flat earth
				float range = heightAboveGndEst / body_to_earth(2, 2);

				if (_in_air && (range - _params.rng_gnd_clearance) > 0.3f && _flow_sample_delayed.dt > 0.05f) {
					// calculate X and Y body relative velocities from OF measurements
					Vector3f vel_optflow_body;
					vel_optflow_body(0) = - range * _flow_sample_delayed.flowRadXYcomp(1) / _flow_sample_delayed.dt;
					vel_optflow_body(1) =   range * _flow_sample_delayed.flowRadXYcomp(0) / _flow_sample_delayed.dt;
					vel_optflow_body(2) = 0.0f;

					// rotate from body to earth frame
					Vector3f vel_optflow_earth;
					vel_optflow_earth = body_to_earth * vel_optflow_body;

					// take x and Y components
					_state.vel(0) = vel_optflow_earth(0);
					_state.vel(1) = vel_optflow_earth(1);

				} else {
					_state.vel.setZero();
				}
			}
		}

	} else if (!(_params.fusion_mode & MASK_USE_OF)) {
		_control_status.flags.opt_flow = false;
	}

	// GPS fusion mode selection logic
	// To start use GPS we need angular alignment completed, the local NED origin set and fresh GPS data
	if ((_params.fusion_mode & MASK_USE_GPS) && !_control_status.flags.gps) {
		if (_control_status.flags.tilt_align && (_time_last_imu - _time_last_gps) < 5e5 && _NED_origin_initialised
		    && (_time_last_imu - _last_gps_fail_us > 5e6)) {
			// If the heading is not aligned, reset the yaw and magnetic field states
			if (!_control_status.flags.yaw_align) {
				_control_status.flags.yaw_align = resetMagHeading(_mag_sample_delayed.mag);
			}

			// If the heading is valid start using gps aiding
			if (_control_status.flags.yaw_align) {
				_control_status.flags.gps = true;
				_time_last_gps = _time_last_imu;

				// if we are not already aiding with optical flow, then we need to reset the position and velocity
				if (!_control_status.flags.opt_flow) {
					_control_status.flags.gps = resetPosition();
					_control_status.flags.gps = resetVelocity();
				}
			}
		}

	}  else if (!(_params.fusion_mode & MASK_USE_GPS)) {
		_control_status.flags.gps = false;
	}

	// handle the case when we are relying on GPS fusion and lose it
	if (_control_status.flags.gps && !_control_status.flags.opt_flow) {
		// We are relying on GPS aiding to constrain attitude drift so after 10 seconds without aiding we need to do something
		if ((_time_last_imu - _time_last_pos_fuse > 10e6) && (_time_last_imu - _time_last_vel_fuse > 10e6)) {
			if (_time_last_imu - _time_last_gps > 5e5) {
				// if we don't have gps then we need to switch to the non-aiding mode, zero the veloity states
				// and set the synthetic GPS position to the current estimate
				_control_status.flags.gps = false;
				_last_known_posNE(0) = _state.pos(0);
				_last_known_posNE(1) = _state.pos(1);
				_state.vel.setZero();

			} else {
				// Reset states to the last GPS measurement
				resetPosition();
				resetVelocity();
			}
		}
	}

	/*
	 * Handle the case where we have not fused height measurements recently and
	 * uncertainty exceeds the max allowable. Reset using the best available height
	 * measurement source, continue using it after the reset and declare the current
	 * source failed if we have switched.
	*/
	if ((P[8][8] > sq(_params.hgt_reset_lim)) && ((_time_last_imu - _time_last_hgt_fuse) > 5e6)) {
		// handle the case where we are using baro for height
		if (_control_status.flags.baro_hgt) {
			// check if GPS height is available
			gpsSample gps_init = _gps_buffer.get_newest();
			bool gps_hgt_available = ((_time_last_imu - gps_init.time_us) < 2 * GPS_MAX_INTERVAL);
			bool gps_hgt_accurate = (gps_init.vacc < _params.req_vacc);
			baroSample baro_init = _baro_buffer.get_newest();
			bool baro_hgt_available = ((_time_last_imu - baro_init.time_us) < 2 * BARO_MAX_INTERVAL);

			// use the gps if it is accurate or there is no baro data available
			if (gps_hgt_available && (gps_hgt_accurate || !baro_hgt_available)) {
				// declare the baro as unhealthy
				_baro_hgt_faulty = true;
				// set the height mode to the GPS
				_control_status.flags.baro_hgt = false;
				_control_status.flags.gps_hgt = true;
				_control_status.flags.rng_hgt = false;
				// adjust the height offset so we can use the GPS
				_hgt_sensor_offset = _state.pos(2) + gps_init.hgt - _gps_alt_ref;
				if (!baro_hgt_available) {
					printf("EKF baro hgt timeout - switching to gps\n");
				}
			}
		}

		// handle the case we are using GPS for height
		if (_control_status.flags.gps_hgt) {
			// check if GPS height is available
			gpsSample gps_init = _gps_buffer.get_newest();
			bool gps_hgt_available = ((_time_last_imu - gps_init.time_us) < 2 * GPS_MAX_INTERVAL);
			bool gps_hgt_accurate = (gps_init.vacc < _params.req_vacc);
			// check the baro height source for consistency and freshness
			baroSample baro_init = _baro_buffer.get_newest();
			bool baro_data_fresh = ((_time_last_imu - baro_init.time_us) < 2 * BARO_MAX_INTERVAL);
			float baro_innov = _state.pos(2) - (_hgt_sensor_offset - baro_init.hgt + _baro_hgt_offset);
			bool baro_data_consistent = fabsf(baro_innov) < (sq(_params.baro_noise) + P[8][8]) * sq(_params.baro_innov_gate);

			// if baro data is consistent and fresh or GPS height is unavailable or inaccurate, we switch to baro for height
			if ((baro_data_consistent && baro_data_fresh) || !gps_hgt_available || !gps_hgt_accurate) {
				// declare the GPS height unhealthy
				_gps_hgt_faulty = true;
				// set the height mode to the baro
				_control_status.flags.baro_hgt = true;
				_control_status.flags.gps_hgt = false;
				_control_status.flags.rng_hgt = false;
				printf("EKF gps hgt timeout - switching to baro\n");
			}
		}

		// handle the case we are using range finder for height
		if (_control_status.flags.rng_hgt) {
			// check if range finder data is available
			rangeSample rng_init = _range_buffer.get_newest();
			bool rng_data_available = ((_time_last_imu - rng_init.time_us) < 2 * RNG_MAX_INTERVAL);
			// check if baro data is available
			baroSample baro_init = _baro_buffer.get_newest();
			bool baro_data_available = ((_time_last_imu - baro_init.time_us) < 2 * BARO_MAX_INTERVAL);
			// check if baro data is consistent
			float baro_innov = _state.pos(2) - (_hgt_sensor_offset - baro_init.hgt + _baro_hgt_offset);
			bool baro_data_consistent = sq(baro_innov) < (sq(_params.baro_noise) + P[8][8]) * sq(_params.baro_innov_gate);
			// switch to baro if necessary or preferable
			bool switch_to_baro = (!rng_data_available && baro_data_available) || (baro_data_consistent && baro_data_available);

			if (switch_to_baro) {
				// declare the range finder height unhealthy
				_rng_hgt_faulty = true;
				// set the height mode to the baro
				_control_status.flags.baro_hgt = true;
				_control_status.flags.gps_hgt = false;
				_control_status.flags.rng_hgt = false;
				printf("EKF rng hgt timeout - switching to baro\n");
			}
		}

		// Reset vertical position and velocity states to the last measurement
		resetHeight();
	}

	// handle the case when we are relying on optical flow fusion and lose it
	if (_control_status.flags.opt_flow && !_control_status.flags.gps) {
		// We are relying on flow aiding to constrain attitude drift so after 5s without aiding we need to do something
		if ((_time_last_imu - _time_last_of_fuse > 5e6)) {
			// Switch to the non-aiding mode, zero the veloity states
			// and set the synthetic position to the current estimate
			_control_status.flags.opt_flow = false;
			_last_known_posNE(0) = _state.pos(0);
			_last_known_posNE(1) = _state.pos(1);
			_state.vel.setZero();
		}
	}

	// Determine if we should use simple magnetic heading fusion which works better when there are large external disturbances
	// or the more accurate 3-axis fusion
	if (_params.mag_fusion_type == MAG_FUSE_TYPE_AUTO) {
		if (!_control_status.flags.armed) {
			// use heading fusion for initial startup
			_control_status.flags.mag_hdg = true;
			_control_status.flags.mag_2D = false;
			_control_status.flags.mag_3D = false;

		} else {
			if (_control_status.flags.in_air) {
				// if transitioning into 3-axis fusion mode, we need to initialise the yaw angle and field states
				if (!_control_status.flags.mag_3D) {
					_control_status.flags.yaw_align = resetMagHeading(_mag_sample_delayed.mag);
				}

				// use 3D mag fusion when airborne
				_control_status.flags.mag_hdg = false;
				_control_status.flags.mag_2D = false;
				_control_status.flags.mag_3D = true;

			} else {
				// use heading fusion when on the ground
				_control_status.flags.mag_hdg = true;
				_control_status.flags.mag_2D = false;
				_control_status.flags.mag_3D = false;
			}
		}

	} else if (_params.mag_fusion_type == MAG_FUSE_TYPE_HEADING) {
		// always use heading fusion
		_control_status.flags.mag_hdg = true;
		_control_status.flags.mag_2D = false;
		_control_status.flags.mag_3D = false;

	} else if (_params.mag_fusion_type == MAG_FUSE_TYPE_2D) {
		// always use 2D mag fusion
		_control_status.flags.mag_hdg = false;
		_control_status.flags.mag_2D = true;
		_control_status.flags.mag_3D = false;

	} else if (_params.mag_fusion_type == MAG_FUSE_TYPE_3D) {
		// if transitioning into 3-axis fusion mode, we need to initialise the yaw angle and field states
		if (!_control_status.flags.mag_3D) {
			_control_status.flags.yaw_align = resetMagHeading(_mag_sample_delayed.mag);
		}

		// always use 3-axis mag fusion
		_control_status.flags.mag_hdg = false;
		_control_status.flags.mag_2D = false;
		_control_status.flags.mag_3D = true;

	} else {
		// do no magnetometer fusion at all
		_control_status.flags.mag_hdg = false;
		_control_status.flags.mag_2D = false;
		_control_status.flags.mag_3D = false;
	}

	// if we are using 3-axis magnetometer fusion, but without external aiding, then the declination must be fused as an observation to prevent long term heading drift
	// fusing declination when gps aiding is available is optional, but recommneded to prevent problem if the vehicle is static for extended periods of time
	if (_control_status.flags.mag_3D && (!_control_status.flags.gps || (_params.mag_declination_source & MASK_FUSE_DECL))) {
		_control_status.flags.mag_dec = true;

	} else {
		_control_status.flags.mag_dec = false;
	}

	// Control the soure of height measurements for the main filter
	if ((_params.vdist_sensor_type == VDIST_SENSOR_BARO && !_baro_hgt_faulty) || _control_status.flags.baro_hgt) {
		_control_status.flags.baro_hgt = true;
		_control_status.flags.gps_hgt = false;
		_control_status.flags.rng_hgt = false;

	} else if ((_params.vdist_sensor_type == VDIST_SENSOR_GPS && !_gps_hgt_faulty) || _control_status.flags.gps_hgt) {
		_control_status.flags.baro_hgt = false;
		_control_status.flags.gps_hgt = true;
		_control_status.flags.rng_hgt = false;

	} else if (_params.vdist_sensor_type == VDIST_SENSOR_RANGE && !_rng_hgt_faulty) {
		_control_status.flags.baro_hgt = false;
		_control_status.flags.gps_hgt = false;
		_control_status.flags.rng_hgt = true;
	}

	// Placeholder for control of wind velocity states estimation
	// TODO add methods for true airspeed and/or sidelsip fusion or some type of drag force measurement
	if (false) {
		_control_status.flags.wind = false;
	}

	// Store the status to enable change detection
	_control_status_prev.value = _control_status.value;
}