AC_AttitudeControl: adjust for some methods on AP_AHRS become non-const

This commit is contained in:
Peter Barker 2019-12-10 20:31:08 +11:00 committed by Andrew Tridgell
parent 45dc4cf25c
commit d6dbdd58d3
4 changed files with 5 additions and 5 deletions

View File

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

View File

@ -45,7 +45,7 @@ class AC_PosControl
public: public:
/// Constructor /// Constructor
AC_PosControl(const AP_AHRS_View& ahrs, const AP_InertialNav& inav, AC_PosControl(AP_AHRS_View& ahrs, const AP_InertialNav& inav,
const AP_Motors& motors, AC_AttitudeControl& attitude_control); const AP_Motors& motors, AC_AttitudeControl& attitude_control);
/// ///
@ -379,7 +379,7 @@ protected:
void check_for_ekf_z_reset(); void check_for_ekf_z_reset();
// references to inertial nav and ahrs libraries // references to inertial nav and ahrs libraries
const AP_AHRS_View & _ahrs; AP_AHRS_View & _ahrs;
const AP_InertialNav& _inav; const AP_InertialNav& _inav;
const AP_Motors& _motors; const AP_Motors& _motors;
AC_AttitudeControl& _attitude_control; AC_AttitudeControl& _attitude_control;

View File

@ -1,6 +1,6 @@
#include "AC_PosControl_Sub.h" #include "AC_PosControl_Sub.h"
AC_PosControl_Sub::AC_PosControl_Sub(const AP_AHRS_View& ahrs, const AP_InertialNav& inav, AC_PosControl_Sub::AC_PosControl_Sub(AP_AHRS_View& ahrs, const AP_InertialNav& inav,
const AP_Motors& motors, AC_AttitudeControl& attitude_control) : const AP_Motors& motors, AC_AttitudeControl& attitude_control) :
AC_PosControl(ahrs, inav, motors, attitude_control), AC_PosControl(ahrs, inav, motors, attitude_control),
_alt_max(0.0f), _alt_max(0.0f),

View File

@ -4,7 +4,7 @@
class AC_PosControl_Sub : public AC_PosControl { class AC_PosControl_Sub : public AC_PosControl {
public: public:
AC_PosControl_Sub(const AP_AHRS_View & ahrs, const AP_InertialNav& inav, AC_PosControl_Sub(AP_AHRS_View & ahrs, const AP_InertialNav& inav,
const AP_Motors& motors, AC_AttitudeControl& attitude_control); const AP_Motors& motors, AC_AttitudeControl& attitude_control);
/// set_alt_max - sets maximum altitude above the ekf origin in cm /// set_alt_max - sets maximum altitude above the ekf origin in cm