AC_WPNav: OA gets minor format fix

This commit is contained in:
Randy Mackay 2021-03-15 17:37:35 +09:00
parent da52e5d08c
commit da580bd1ea

View File

@ -112,7 +112,8 @@ bool AC_WPNav_OA::update_wpnav()
// convert Location to offset from EKF origin
Vector3f dest_NEU;
if (_oa_destination.get_vector_from_origin_NEU(dest_NEU)) {
if (oa_ptr -> get_bendy_type() == AP_OABendyRuler::OABendyType::OA_BENDY_HORIZONTAL || oa_ptr -> get_bendy_type() == AP_OABendyRuler::OABendyType::OA_BENDY_DISABLED) {
if ((oa_ptr->get_bendy_type() == AP_OABendyRuler::OABendyType::OA_BENDY_HORIZONTAL) ||
(oa_ptr->get_bendy_type() == AP_OABendyRuler::OABendyType::OA_BENDY_DISABLED)) {
// calculate target altitude by calculating OA adjusted destination's distance along the original track
// and then linear interpolate using the original track's origin and destination altitude
const float dist_along_path = constrain_float(oa_destination_new.line_path_proportion(origin_loc, destination_loc), 0.0f, 1.0f);