mirror of https://github.com/ArduPilot/ardupilot
Allows user to specify just an altitude for Circle Mode
This commit is contained in:
parent
05e921f5d0
commit
4b52b61563
|
@ -301,10 +301,15 @@ static void do_loiter_turns()
|
|||
{
|
||||
wp_control = CIRCLE_MODE;
|
||||
|
||||
if(command_nav_queue.lat == 0)
|
||||
if(command_nav_queue.lat == 0){
|
||||
// allow user to specify just the altitude
|
||||
if(command_nav_queue.alt > 0){
|
||||
current_loc.alt = command_nav_queue.alt;
|
||||
}
|
||||
set_next_WP(¤t_loc);
|
||||
else
|
||||
}else{
|
||||
set_next_WP(&command_nav_queue);
|
||||
}
|
||||
|
||||
loiter_total = command_nav_queue.p1 * 360;
|
||||
loiter_sum = 0;
|
||||
|
@ -367,7 +372,7 @@ static bool verify_land()
|
|||
if(sonar_alt < 40){
|
||||
land_complete = true;
|
||||
//Serial.println("Y");
|
||||
//return true;
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue