Browse Source

AC_WPNav: make member pointer to AP_InertialNav object const since it's

never modified
mission-4.1.18
Tobias 12 years ago committed by Randy Mackay
parent
commit
bb5cf4a311
  1. 2
      libraries/AC_WPNav/AC_WPNav.cpp
  2. 6
      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(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, 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),

6
libraries/AC_WPNav/AC_WPNav.h

@ -40,7 +40,7 @@ class AC_WPNav @@ -40,7 +40,7 @@ class AC_WPNav
public:
/// Constructor
AC_WPNav(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, 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
@ -183,8 +183,8 @@ protected: @@ -183,8 +183,8 @@ protected:
/// set climb param to true if track climbs vertically, false if descending
void calculate_wp_leash_length(bool climb);
// pointers to inertial nav and ahrs libraries
AP_InertialNav* _inav;
// references to inertial nav and ahrs libraries
const AP_InertialNav* const _inav;
AP_AHRS* _ahrs;
// pointers to pid controllers

Loading…
Cancel
Save