Skip to content

Commit

Permalink
AP_AHRS: add method to get view
Browse files Browse the repository at this point in the history
  • Loading branch information
IamPete1 authored and tridge committed Apr 26, 2022
1 parent 04fdfea commit 6c24a5f
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 10 deletions.
8 changes: 0 additions & 8 deletions libraries/AP_AHRS/AP_AHRS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand Down
4 changes: 2 additions & 2 deletions libraries/AP_AHRS/AP_AHRS.h
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down

0 comments on commit 6c24a5f

Please sign in to comment.