|
|
|
@ -18,6 +18,7 @@
@@ -18,6 +18,7 @@
|
|
|
|
|
#include "AP_AHRS_View.h" |
|
|
|
|
#include <AP_HAL/AP_HAL.h> |
|
|
|
|
#include <AP_Logger/AP_Logger.h> |
|
|
|
|
#include <AP_NMEA_Output/AP_NMEA_Output.h> |
|
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal; |
|
|
|
|
|
|
|
|
@ -159,6 +160,16 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] = {
@@ -159,6 +160,16 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] = {
|
|
|
|
|
AP_GROUPEND |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
// init sets up INS board orientation
|
|
|
|
|
void AP_AHRS::init() |
|
|
|
|
{ |
|
|
|
|
update_orientation(); |
|
|
|
|
|
|
|
|
|
#if !HAL_MINIMIZE_FEATURES && AP_AHRS_NAVEKF_AVAILABLE |
|
|
|
|
_nmea_out = AP_NMEA_Output::probe(); |
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// return a smoothed and corrected gyro vector using the latest ins data (which may not have been consumed by the EKF yet)
|
|
|
|
|
Vector3f AP_AHRS::get_gyro_latest(void) const |
|
|
|
|
{ |
|
|
|
@ -492,6 +503,15 @@ void AP_AHRS::Log_Write_Home_And_Origin()
@@ -492,6 +503,15 @@ void AP_AHRS::Log_Write_Home_And_Origin()
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
void AP_AHRS::update_nmea_out() |
|
|
|
|
{ |
|
|
|
|
#if !HAL_MINIMIZE_FEATURES && AP_AHRS_NAVEKF_AVAILABLE |
|
|
|
|
if (_nmea_out != nullptr) { |
|
|
|
|
_nmea_out->update(); |
|
|
|
|
} |
|
|
|
|
#endif |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// singleton instance
|
|
|
|
|
AP_AHRS *AP_AHRS::_singleton; |
|
|
|
|
|
|
|
|
|