Arducopter: Fix circle_WP

This commit is contained in:
Jason Short 2012-07-12 09:22:20 -07:00
parent a28070e0e0
commit d8ff5dcfab
2 changed files with 7 additions and 5 deletions

View File

@ -2404,8 +2404,11 @@ static void update_auto_yaw()
if(wp_control == LOITER_MODE)
return;
// this tracks a location so the copter is always pointing towards it.
if(yaw_tracking == MAV_ROI_LOCATION){
if(control_mode == CIRCLE_MODE){
auto_yaw = get_bearing(&current_loc, &circle_WP);
}else if(yaw_tracking == MAV_ROI_LOCATION){
// this tracks a location so the copter is always pointing towards it.
auto_yaw = get_bearing(&current_loc, &target_WP);
}else if(yaw_tracking == MAV_ROI_WPNEXT){

View File

@ -310,9 +310,6 @@ static void do_loiter_turns()
{
wp_control = CIRCLE_MODE;
// reset desired location
if(command_nav_queue.lat == 0){
// allow user to specify just the altitude
if(command_nav_queue.alt > 0){
@ -323,6 +320,8 @@ static void do_loiter_turns()
set_next_WP(&command_nav_queue);
}
circle_WP = next_WP;
loiter_total = command_nav_queue.p1 * 360;
loiter_sum = 0;
old_target_bearing = target_bearing;