ArduCopter: position lead filters modified to use lag which varies by gps

This commit is contained in:
rmackay9 2012-09-20 15:49:09 +09:00
parent 50a97f3092
commit b3ff368589
1 changed files with 2 additions and 2 deletions

View File

@ -63,8 +63,8 @@ static void calc_XY_velocity(){
filtered_loc.lng = xLeadFilter.get_position(g_gps->longitude, accels_velocity.x); filtered_loc.lng = xLeadFilter.get_position(g_gps->longitude, accels_velocity.x);
filtered_loc.lat = yLeadFilter.get_position(g_gps->latitude, accels_velocity.y); filtered_loc.lat = yLeadFilter.get_position(g_gps->latitude, accels_velocity.y);
#else #else
filtered_loc.lng = xLeadFilter.get_position(g_gps->longitude, x_actual_speed); filtered_loc.lng = xLeadFilter.get_position(g_gps->longitude, x_actual_speed, g_gps->get_lag());
filtered_loc.lat = yLeadFilter.get_position(g_gps->latitude, y_actual_speed); filtered_loc.lat = yLeadFilter.get_position(g_gps->latitude, y_actual_speed, g_gps->get_lag());
#endif #endif
} }