AC_AttitudeControl: get_bearing & get_horizontal_distance use Vector2f

This commit is contained in:
Josh Henderson 2021-09-10 23:51:24 -04:00 committed by Andrew Tridgell
parent 2a15cf86ad
commit 6243532e69
1 changed files with 1 additions and 1 deletions

View File

@ -1111,7 +1111,7 @@ void AC_PosControl::get_stopping_point_z_cm(postype_t &stopping_point) const
/// get_bearing_to_target_cd - get bearing to target position in centi-degrees
int32_t AC_PosControl::get_bearing_to_target_cd() const
{
return get_bearing_cd(_inav.get_position(), _pos_target.tofloat());
return get_bearing_cd(_inav.get_position().xy(), _pos_target.tofloat().xy());
}