mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
ArduSub: get_bearing & get_horizontal_distance use Vector2f
This commit is contained in:
parent
29ebb9be60
commit
5391262900
@ -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;
|
||||
|
@ -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};
|
||||
|
@ -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;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user