@ -185,12 +185,19 @@ void Plane::update_loiter(uint16_t radius)
loiter . start_time_ms = 0 ;
loiter . start_time_ms = 0 ;
quadplane . guided_start ( ) ;
quadplane . guided_start ( ) ;
}
}
} else if ( loiter . start_time_ms = = 0 & &
} else if ( ( loiter . start_time_ms = = 0 & &
control_mode = = AUTO & &
control_mode = = AUTO & &
! auto_state . no_crosstrack & &
! auto_state . no_crosstrack & &
get_distance ( current_loc , next_WP_loc ) > radius * 3 ) {
get_distance ( current_loc , next_WP_loc ) > radius * 3 ) | |
// if never reached loiter point and using crosstrack and somewhat far away from loiter point
( quadplane . available ( ) & & quadplane . rtl_mode = = 1 ) ) {
// navigate to it like in auto-mode for normal crosstrack behavior
/*
if never reached loiter point and using crosstrack and somewhat far away from loiter point
navigate to it like in auto - mode for normal crosstrack behavior
we also use direct waypoint navigation if we are a quadplane
that is going to be switching to QRTL when it gets within
RTL_RADIUS
*/
nav_controller - > update_waypoint ( prev_WP_loc , next_WP_loc ) ;
nav_controller - > update_waypoint ( prev_WP_loc , next_WP_loc ) ;
} else {
} else {
nav_controller - > update_loiter ( next_WP_loc , radius , loiter . direction ) ;
nav_controller - > update_loiter ( next_WP_loc , radius , loiter . direction ) ;