AC_WPNav: remove unused PID references

This commit is contained in:
Randy Mackay 2014-01-25 22:33:03 +09:00 committed by Andrew Tridgell
parent b1449d59ee
commit d4e4620159
2 changed files with 2 additions and 9 deletions

View File

@ -68,15 +68,11 @@ 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, const AP_AHRS* ahrs, AC_PosControl& pos_control,
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, AC_PosControl& pos_control, APM_PI* pid_pos_lat) :
_inav(inav),
_ahrs(ahrs),
_pos_control(pos_control),
_pid_pos_lat(pid_pos_lat),
_pid_pos_lon(pid_pos_lon),
_pid_rate_lat(pid_rate_lat),
_pid_rate_lon(pid_rate_lon),
_loiter_last_update(0),
_loiter_step(0),
_pilot_accel_fwd_cms(0),

View File

@ -40,7 +40,7 @@ class AC_WPNav
public:
/// Constructor
AC_WPNav(const AP_InertialNav* inav, const AP_AHRS* ahrs, AC_PosControl& pos_control, 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, AC_PosControl& pos_control, APM_PI* pid_pos_lat);
///
/// loiter controller
@ -166,9 +166,6 @@ protected:
// pointers to pid controllers
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