mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
AC_PosControl: default z-axis controller to 400hz
No functional change as vehicle code always sets it explicitely
This commit is contained in:
parent
916d63412e
commit
54cc2d884c
@ -37,7 +37,7 @@ AC_PosControl::AC_PosControl(const AP_AHRS& ahrs, const AP_InertialNav& inav,
|
|||||||
_pid_accel_z(pid_accel_z),
|
_pid_accel_z(pid_accel_z),
|
||||||
_p_pos_xy(p_pos_xy),
|
_p_pos_xy(p_pos_xy),
|
||||||
_pi_vel_xy(pi_vel_xy),
|
_pi_vel_xy(pi_vel_xy),
|
||||||
_dt(POSCONTROL_DT_10HZ),
|
_dt(POSCONTROL_DT_400HZ),
|
||||||
_dt_xy(POSCONTROL_DT_50HZ),
|
_dt_xy(POSCONTROL_DT_50HZ),
|
||||||
_last_update_xy_ms(0),
|
_last_update_xy_ms(0),
|
||||||
_last_update_z_ms(0),
|
_last_update_z_ms(0),
|
||||||
|
@ -32,8 +32,8 @@
|
|||||||
|
|
||||||
#define POSCONTROL_LEASH_LENGTH_MIN 100.0f // minimum leash lengths in cm
|
#define POSCONTROL_LEASH_LENGTH_MIN 100.0f // minimum leash lengths in cm
|
||||||
|
|
||||||
#define POSCONTROL_DT_10HZ 0.10f // time difference in seconds for 10hz update rate
|
|
||||||
#define POSCONTROL_DT_50HZ 0.02f // time difference in seconds for 50hz update rate
|
#define POSCONTROL_DT_50HZ 0.02f // time difference in seconds for 50hz update rate
|
||||||
|
#define POSCONTROL_DT_400HZ 0.0025f // time difference in seconds for 400hz update rate
|
||||||
|
|
||||||
#define POSCONTROL_ACTIVE_TIMEOUT_MS 200 // position controller is considered active if it has been called within the past 0.2 seconds
|
#define POSCONTROL_ACTIVE_TIMEOUT_MS 200 // position controller is considered active if it has been called within the past 0.2 seconds
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user