From 6c24a5ff37f8f88290cd3435d44389f13eb5781d Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Tue, 19 Apr 2022 23:45:39 +0100 Subject: [PATCH] AP_AHRS: add method to get view --- libraries/AP_AHRS/AP_AHRS.cpp | 8 -------- libraries/AP_AHRS/AP_AHRS.h | 4 ++-- 2 files changed, 2 insertions(+), 10 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index cacf7591e3bd5..d086f815b2337 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -3207,14 +3207,6 @@ void AP_AHRS::set_alt_measurement_noise(float noise) #endif } -/* - get the current view's rotation, or ROTATION_NONE - */ -enum Rotation AP_AHRS::get_view_rotation(void) const -{ - return _view?_view->get_rotation():ROTATION_NONE; -} - // check if non-compass sensor is providing yaw. Allows compass pre-arm checks to be bypassed const EKFGSF_yaw *AP_AHRS::get_yaw_estimator(void) const { diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index a58ab57df7af8..26bbc5b504583 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -609,8 +609,8 @@ class AP_AHRS { _vehicle_class = vclass; } - // get the view's rotation, or ROTATION_NONE - enum Rotation get_view_rotation(void) const; + // get the view + AP_AHRS_View *get_view(void) const { return _view; }; // get access to an EKFGSF_yaw estimator const EKFGSF_yaw *get_yaw_estimator(void) const;