Skip to content

Commit

Permalink
Copter: Use GRAVITY_MSS
Browse files Browse the repository at this point in the history
  • Loading branch information
muramura authored and rmackay9 committed Nov 11, 2024
1 parent 8a5556c commit da69e22
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion ArduCopter/mode_poshold.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -588,7 +588,7 @@ void ModePosHold::update_wind_comp_estimate()
}

// 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();
if (!is_zero(accel_lim_cmss) && (wind_comp_ef_len > accel_lim_cmss)) {
wind_comp_ef *= accel_lim_cmss / wind_comp_ef_len;
Expand Down

0 comments on commit da69e22

Please sign in to comment.