ACM: Switched to filtered loc

This commit is contained in:
Jason Short 2012-08-14 14:08:33 -07:00
parent 5d64942f01
commit 2cc27b9804
1 changed files with 6 additions and 6 deletions

View File

@ -7,8 +7,8 @@ static void navigate()
{ {
// waypoint distance from plane in cm // waypoint distance from plane in cm
// --------------------------------------- // ---------------------------------------
wp_distance = get_distance_cm(&current_loc, &next_WP); wp_distance = get_distance_cm(&filtered_loc, &next_WP);
home_distance = get_distance_cm(&current_loc, &home); home_distance = get_distance_cm(&filtered_loc, &home);
// target_bearing is where we should be heading // target_bearing is where we should be heading
// -------------------------------------------- // --------------------------------------------
@ -60,11 +60,11 @@ static void calc_XY_velocity(){
#if INERTIAL_NAV == ENABLED #if INERTIAL_NAV == ENABLED
// inertial_nav // inertial_nav
xy_error_correction(); xy_error_correction();
current_loc.lng = xLeadFilter.get_position(g_gps->longitude, accels_velocity.x); filtered_loc.lng = xLeadFilter.get_position(g_gps->longitude, accels_velocity.x);
current_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
current_loc.lng = xLeadFilter.get_position(g_gps->longitude, x_actual_speed); filtered_loc.lng = xLeadFilter.get_position(g_gps->longitude, x_actual_speed);
current_loc.lat = yLeadFilter.get_position(g_gps->latitude, y_actual_speed); filtered_loc.lat = yLeadFilter.get_position(g_gps->latitude, y_actual_speed);
#endif #endif
} }