mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: position lead filters modified to use lag which varies by gps
This commit is contained in:
parent
c6ee948d60
commit
5e6951d3f4
|
@ -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
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue