ACM: made target bearing the lead filtered location

Had some major nav trouble from crosstrack if I used the laggy position.
This commit is contained in:
Jason Short 2012-08-16 15:38:25 -07:00
parent bd91215770
commit bdc1c41e62
1 changed files with 2 additions and 2 deletions

View File

@ -12,7 +12,7 @@ static void navigate()
// target_bearing is where we should be heading
// --------------------------------------------
target_bearing = get_bearing_cd(&current_loc, &next_WP);
target_bearing = get_bearing_cd(&filtered_loc, &next_WP);
home_to_copter_bearing = get_bearing_cd(&home, &current_loc);
}
@ -185,7 +185,7 @@ static void calc_nav_rate(int16_t max_speed)
int16_t cross_speed = crosstrack_error * -g.crosstrack_gain; // scale down crosstrack_error in cm
// XXX replace above with crosstrack gain.
cross_speed = constrain(cross_speed, -200, 200);
cross_speed = constrain(cross_speed, -150, 150);
// rotate by 90 to deal with trig functions
temp = (9000l - target_bearing) * RADX100;