AC_WPNav: converted to use AP_AHRS_View

for use in quadplane tailsitters
This commit is contained in:
Andrew Tridgell 2017-02-12 09:33:43 +11:00
parent 94fb390bda
commit 17e1329068
4 changed files with 6 additions and 6 deletions

View File

@ -30,7 +30,7 @@ const AP_Param::GroupInfo AC_Circle::var_info[] = {
// Note that the Vector/Matrix constructors already implicitly zero
// their values.
//
AC_Circle::AC_Circle(const AP_InertialNav& inav, const AP_AHRS& ahrs, AC_PosControl& pos_control) :
AC_Circle::AC_Circle(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control) :
_inav(inav),
_ahrs(ahrs),
_pos_control(pos_control),

View File

@ -18,7 +18,7 @@ class AC_Circle
public:
/// Constructor
AC_Circle(const AP_InertialNav& inav, const AP_AHRS& ahrs, AC_PosControl& pos_control);
AC_Circle(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control);
/// init - initialise circle controller setting center specifically
/// caller should set the position controller's x,y and z speeds and accelerations before calling this
@ -82,7 +82,7 @@ private:
// references to inertial nav and ahrs libraries
const AP_InertialNav& _inav;
const AP_AHRS& _ahrs;
const AP_AHRS_View& _ahrs;
AC_PosControl& _pos_control;
// parameters

View File

@ -110,7 +110,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] = {
// Note that the Vector/Matrix constructors already implicitly zero
// their values.
//
AC_WPNav::AC_WPNav(const AP_InertialNav& inav, const AP_AHRS& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control) :
AC_WPNav::AC_WPNav(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control) :
_inav(inav),
_ahrs(ahrs),
_pos_control(pos_control),

View File

@ -54,7 +54,7 @@ public:
};
/// Constructor
AC_WPNav(const AP_InertialNav& inav, const AP_AHRS& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control);
AC_WPNav(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosControl& pos_control, const AC_AttitudeControl& attitude_control);
/// provide pointer to terrain database
void set_terrain(AP_Terrain* terrain_ptr) { _terrain = terrain_ptr; }
@ -308,7 +308,7 @@ protected:
// references and pointers to external libraries
const AP_InertialNav& _inav;
const AP_AHRS& _ahrs;
const AP_AHRS_View& _ahrs;
AC_PosControl& _pos_control;
const AC_AttitudeControl& _attitude_control;
AP_Terrain *_terrain = nullptr;