ArduSub: get_bearing & get_horizontal_distance use Vector2f

This commit is contained in:
Josh Henderson 2021-09-10 23:44:50 -04:00 committed by Andrew Tridgell
parent 29ebb9be60
commit 5391262900
3 changed files with 3 additions and 3 deletions

View File

@ -64,7 +64,7 @@ float Sub::get_roi_yaw()
roi_yaw_counter++;
if (roi_yaw_counter >= 4) {
roi_yaw_counter = 0;
yaw_look_at_WP_bearing = get_bearing_cd(inertial_nav.get_position(), roi_WP);
yaw_look_at_WP_bearing = get_bearing_cd(inertial_nav.get_position().xy(), roi_WP.xy());
}
return yaw_look_at_WP_bearing;

View File

@ -516,7 +516,7 @@ float Sub::get_auto_heading()
case AUTO_YAW_CORRECT_XTRACK: {
// TODO return current yaw if not in appropriate mode
// Bearing of current track (centidegrees)
float track_bearing = get_bearing_cd(wp_nav.get_wp_origin(), wp_nav.get_wp_destination());
float track_bearing = get_bearing_cd(wp_nav.get_wp_origin().xy(), wp_nav.get_wp_destination().xy());
// Bearing from current position towards intermediate position target (centidegrees)
const Vector2f target_vel_xy{pos_control.get_vel_target_cms().x, pos_control.get_vel_target_cms().y};

View File

@ -551,7 +551,7 @@ bool Sub::guided_limit_check()
// check if we have gone beyond horizontal limit
if (guided_limit.horiz_max_cm > 0.0f) {
float horiz_move = get_horizontal_distance_cm(guided_limit.start_pos, curr_pos);
const float horiz_move = get_horizontal_distance_cm(guided_limit.start_pos.xy(), curr_pos.xy());
if (horiz_move > guided_limit.horiz_max_cm) {
return true;
}