mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: Use GRAVITY_MSS
This commit is contained in:
parent
8a5556cb4e
commit
da69e22673
@ -588,7 +588,7 @@ void ModePosHold::update_wind_comp_estimate()
|
|||||||
}
|
}
|
||||||
|
|
||||||
// limit acceleration
|
// limit acceleration
|
||||||
const float accel_lim_cmss = tanf(radians(POSHOLD_WIND_COMP_LEAN_PCT_MAX * copter.aparm.angle_max * 0.01f)) * 981.0f;
|
const float accel_lim_cmss = tanf(radians(POSHOLD_WIND_COMP_LEAN_PCT_MAX * copter.aparm.angle_max * 0.01f)) * (GRAVITY_MSS*100);
|
||||||
const float wind_comp_ef_len = wind_comp_ef.length();
|
const float wind_comp_ef_len = wind_comp_ef.length();
|
||||||
if (!is_zero(accel_lim_cmss) && (wind_comp_ef_len > accel_lim_cmss)) {
|
if (!is_zero(accel_lim_cmss) && (wind_comp_ef_len > accel_lim_cmss)) {
|
||||||
wind_comp_ef *= accel_lim_cmss / wind_comp_ef_len;
|
wind_comp_ef *= accel_lim_cmss / wind_comp_ef_len;
|
||||||
|
Loading…
Reference in New Issue
Block a user