Browse Source

AC_WPNav: make more member pointers const

mission-4.1.18
Tobias 12 years ago committed by Randy Mackay
parent
commit
c3309d909c
  1. 2
      libraries/AC_WPNav/AC_WPNav.cpp
  2. 12
      libraries/AC_WPNav/AC_WPNav.h

2
libraries/AC_WPNav/AC_WPNav.cpp

@ -68,7 +68,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] PROGMEM = { @@ -68,7 +68,7 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] PROGMEM = {
// Note that the Vector/Matrix constructors already implicitly zero
// their values.
//
AC_WPNav::AC_WPNav(const AP_InertialNav* inav, AP_AHRS* ahrs, APM_PI* pid_pos_lat, APM_PI* pid_pos_lon, AC_PID* pid_rate_lat, AC_PID* pid_rate_lon) :
AC_WPNav::AC_WPNav(const AP_InertialNav* inav, const AP_AHRS* ahrs, APM_PI* pid_pos_lat, APM_PI* pid_pos_lon, AC_PID* pid_rate_lat, AC_PID* pid_rate_lon) :
_inav(inav),
_ahrs(ahrs),
_pid_pos_lat(pid_pos_lat),

12
libraries/AC_WPNav/AC_WPNav.h

@ -40,7 +40,7 @@ class AC_WPNav @@ -40,7 +40,7 @@ class AC_WPNav
public:
/// Constructor
AC_WPNav(const AP_InertialNav* inav, AP_AHRS* ahrs, APM_PI* pid_pos_lat, APM_PI* pid_pos_lon, AC_PID* pid_rate_lat, AC_PID* pid_rate_lon);
AC_WPNav(const AP_InertialNav* inav, const AP_AHRS* ahrs, APM_PI* pid_pos_lat, APM_PI* pid_pos_lon, AC_PID* pid_rate_lat, AC_PID* pid_rate_lon);
///
/// simple loiter controller
@ -185,13 +185,13 @@ protected: @@ -185,13 +185,13 @@ protected:
// references to inertial nav and ahrs libraries
const AP_InertialNav* const _inav;
AP_AHRS* _ahrs;
const AP_AHRS* const _ahrs;
// pointers to pid controllers
APM_PI* _pid_pos_lat;
APM_PI* _pid_pos_lon;
AC_PID* _pid_rate_lat;
AC_PID* _pid_rate_lon;
APM_PI* const _pid_pos_lat;
APM_PI* const _pid_pos_lon;
AC_PID* const _pid_rate_lat;
AC_PID* const _pid_rate_lon;
// parameters
AP_Float _loiter_speed_cms; // maximum horizontal speed in cm/s while in loiter

Loading…
Cancel
Save