Browse Source

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

zr-v5.1
Peter Barker 5 years ago committed by Andrew Tridgell
parent
commit
d6dbdd58d3
  1. 2
      libraries/AC_AttitudeControl/AC_PosControl.cpp
  2. 4
      libraries/AC_AttitudeControl/AC_PosControl.h
  3. 2
      libraries/AC_AttitudeControl/AC_PosControl_Sub.cpp
  4. 2
      libraries/AC_AttitudeControl/AC_PosControl_Sub.h

2
libraries/AC_AttitudeControl/AC_PosControl.cpp

@ -189,7 +189,7 @@ const AP_Param::GroupInfo AC_PosControl::var_info[] = { @@ -189,7 +189,7 @@ const AP_Param::GroupInfo AC_PosControl::var_info[] = {
// Note that the Vector/Matrix constructors already implicitly zero
// 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) :
_ahrs(ahrs),
_inav(inav),

4
libraries/AC_AttitudeControl/AC_PosControl.h

@ -45,7 +45,7 @@ class AC_PosControl @@ -45,7 +45,7 @@ class AC_PosControl
public:
/// 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);
///
@ -379,7 +379,7 @@ protected: @@ -379,7 +379,7 @@ protected:
void check_for_ekf_z_reset();
// references to inertial nav and ahrs libraries
const AP_AHRS_View & _ahrs;
AP_AHRS_View & _ahrs;
const AP_InertialNav& _inav;
const AP_Motors& _motors;
AC_AttitudeControl& _attitude_control;

2
libraries/AC_AttitudeControl/AC_PosControl_Sub.cpp

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
#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) :
AC_PosControl(ahrs, inav, motors, attitude_control),
_alt_max(0.0f),

2
libraries/AC_AttitudeControl/AC_PosControl_Sub.h

@ -4,7 +4,7 @@ @@ -4,7 +4,7 @@
class AC_PosControl_Sub : public AC_PosControl {
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);
/// set_alt_max - sets maximum altitude above the ekf origin in cm

Loading…
Cancel
Save