mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-27 10:13:57 -04:00
AC_WPNav: remove unused PID references
This commit is contained in:
parent
b1449d59ee
commit
d4e4620159
@ -68,15 +68,11 @@ const AP_Param::GroupInfo AC_WPNav::var_info[] PROGMEM = {
|
|||||||
// Note that the Vector/Matrix constructors already implicitly zero
|
// Note that the Vector/Matrix constructors already implicitly zero
|
||||||
// their values.
|
// their values.
|
||||||
//
|
//
|
||||||
AC_WPNav::AC_WPNav(const AP_InertialNav* inav, const AP_AHRS* ahrs, AC_PosControl& pos_control,
|
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_lat, APM_PI* pid_pos_lon, AC_PID* pid_rate_lat, AC_PID* pid_rate_lon) :
|
|
||||||
_inav(inav),
|
_inav(inav),
|
||||||
_ahrs(ahrs),
|
_ahrs(ahrs),
|
||||||
_pos_control(pos_control),
|
_pos_control(pos_control),
|
||||||
_pid_pos_lat(pid_pos_lat),
|
_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_last_update(0),
|
||||||
_loiter_step(0),
|
_loiter_step(0),
|
||||||
_pilot_accel_fwd_cms(0),
|
_pilot_accel_fwd_cms(0),
|
||||||
|
@ -40,7 +40,7 @@ class AC_WPNav
|
|||||||
public:
|
public:
|
||||||
|
|
||||||
/// Constructor
|
/// 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
|
/// loiter controller
|
||||||
@ -166,9 +166,6 @@ protected:
|
|||||||
|
|
||||||
// pointers to pid controllers
|
// pointers to pid controllers
|
||||||
APM_PI* const _pid_pos_lat;
|
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
|
// parameters
|
||||||
AP_Float _loiter_speed_cms; // maximum horizontal speed in cm/s while in loiter
|
AP_Float _loiter_speed_cms; // maximum horizontal speed in cm/s while in loiter
|
||||||
|
Loading…
Reference in New Issue
Block a user