mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 09:08:30 -04:00
Copter: remove pid_nav_lat, pid_nav_lon
This commit is contained in:
parent
bffe4fa412
commit
b58c26bcd5
@ -233,8 +233,8 @@ public:
|
||||
k_param_pi_loiter_lon,
|
||||
k_param_pid_loiter_rate_lat,
|
||||
k_param_pid_loiter_rate_lon,
|
||||
k_param_pid_nav_lat,
|
||||
k_param_pid_nav_lon,
|
||||
k_param_pid_nav_lat, // 233 - remove
|
||||
k_param_pid_nav_lon, // 234 - remove
|
||||
k_param_pi_alt_hold,
|
||||
k_param_pid_throttle,
|
||||
k_param_pid_optflow_roll,
|
||||
@ -370,8 +370,6 @@ public:
|
||||
AC_PID pid_rate_yaw;
|
||||
AC_PID pid_loiter_rate_lat;
|
||||
AC_PID pid_loiter_rate_lon;
|
||||
AC_PID pid_nav_lat;
|
||||
AC_PID pid_nav_lon;
|
||||
|
||||
AC_PID pid_throttle;
|
||||
AC_PID pid_throttle_accel;
|
||||
@ -419,9 +417,6 @@ public:
|
||||
pid_loiter_rate_lat (LOITER_RATE_P, LOITER_RATE_I, LOITER_RATE_D, LOITER_RATE_IMAX * 100),
|
||||
pid_loiter_rate_lon (LOITER_RATE_P, LOITER_RATE_I, LOITER_RATE_D, LOITER_RATE_IMAX * 100),
|
||||
|
||||
pid_nav_lat (NAV_P, NAV_I, NAV_D, NAV_IMAX * 100),
|
||||
pid_nav_lon (NAV_P, NAV_I, NAV_D, NAV_IMAX * 100),
|
||||
|
||||
pid_throttle (THROTTLE_P, THROTTLE_I, THROTTLE_D, THROTTLE_IMAX),
|
||||
pid_throttle_accel (THROTTLE_ACCEL_P, THROTTLE_ACCEL_I, THROTTLE_ACCEL_D, THROTTLE_ACCEL_IMAX),
|
||||
pid_optflow_roll (OPTFLOW_ROLL_P, OPTFLOW_ROLL_I, OPTFLOW_ROLL_D, OPTFLOW_IMAX * 100),
|
||||
|
Loading…
Reference in New Issue
Block a user