123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102 |
- #include <AP_HAL/AP_HAL.h>
- #include "AP_InertialNav.h"
- #if AP_AHRS_NAVEKF_AVAILABLE
- void AP_InertialNav_NavEKF::update()
- {
-
- Vector2f posNE;
- if (_ahrs_ekf.get_relative_position_NE_origin(posNE)) {
- _relpos_cm.x = posNE.x * 100;
- _relpos_cm.y = posNE.y * 100;
- }
-
- float posD;
- if (_ahrs_ekf.get_relative_position_D_origin(posD)) {
- _relpos_cm.z = - posD * 100;
- }
-
- Vector3f velNED;
- if (_ahrs_ekf.get_velocity_NED(velNED)) {
- _velocity_cm = velNED * 100;
- _velocity_cm.z = -_velocity_cm.z;
- }
- }
- nav_filter_status AP_InertialNav_NavEKF::get_filter_status() const
- {
- nav_filter_status status;
- _ahrs_ekf.get_filter_status(status);
- return status;
- }
- const Vector3f &AP_InertialNav_NavEKF::get_position(void) const
- {
- return _relpos_cm;
- }
- const Vector3f &AP_InertialNav_NavEKF::get_velocity() const
- {
- return _velocity_cm;
- }
- float AP_InertialNav_NavEKF::get_speed_xy() const
- {
- return norm(_velocity_cm.x, _velocity_cm.y);
- }
- float AP_InertialNav_NavEKF::get_altitude() const
- {
- return _relpos_cm.z;
- }
- float AP_InertialNav_NavEKF::get_velocity_z() const
- {
- return _velocity_cm.z;
- }
- #endif
|