Arducopter:

Loiter unlimited can now travel to a WP and then loiter.
set_altitude for landing now set to 0
This commit is contained in:
Jason Short 2012-07-18 22:41:45 -07:00
parent aa645afe2b
commit a88d69e40e
1 changed files with 7 additions and 4 deletions

View File

@ -291,8 +291,8 @@ static void do_land()
// hold at our current location
set_next_WP(&current_loc);
// Set a new target altitude very low, incase we are landing on a hill!
set_new_altitude(-1000);
// Set a new target altitude
set_new_altitude(0);
}
static void do_loiter_unlimited()
@ -300,10 +300,13 @@ static void do_loiter_unlimited()
wp_control = LOITER_MODE;
//Serial.println("dloi ");
if(command_nav_queue.lat == 0)
if(command_nav_queue.lat == 0){
set_next_WP(&current_loc);
else
wp_control = LOITER_MODE;
}else{
set_next_WP(&command_nav_queue);
wp_control = WP_MODE;
}
}
static void do_loiter_turns()