AC_WPNav: use PosControl accessor

Saves 2bytes of RAM
This commit is contained in:
Randy Mackay 2014-02-10 23:40:05 +09:00 committed by Andrew Tridgell
parent 78c12eaebf
commit 9e31f0b985
2 changed files with 3 additions and 7 deletions

View File

@ -68,11 +68,10 @@ 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) :
AC_WPNav::AC_WPNav(const AP_InertialNav* inav, const AP_AHRS* ahrs, AC_PosControl& pos_control) :
_inav(inav),
_ahrs(ahrs),
_pos_control(pos_control),
_pid_pos_lat(pid_pos_lat),
_loiter_last_update(0),
_loiter_step(0),
_pilot_accel_fwd_cms(0),
@ -348,7 +347,7 @@ void AC_WPNav::advance_wp_target_along_track(float dt)
// calculate point at which velocity switches from linear to sqrt
float linear_velocity = _wp_speed_cms;
float kP = _pid_pos_lat->kP();
float kP = _pos_control.get_pos_xy_kP();
if (kP >= 0.0f) { // avoid divide by zero
linear_velocity = _track_accel/kP;
}

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);
AC_WPNav(const AP_InertialNav* inav, const AP_AHRS* ahrs, AC_PosControl& pos_control);
///
/// loiter controller
@ -163,9 +163,6 @@ protected:
const AP_AHRS* const _ahrs;
AC_PosControl& _pos_control;
// pointers to pid controllers
APM_PI* const _pid_pos_lat;
// parameters
AP_Float _loiter_speed_cms; // maximum horizontal speed in cm/s while in loiter
AP_Float _wp_speed_cms; // maximum horizontal speed in cm/s during missions