mirror of https://github.com/ArduPilot/ardupilot
Copter: Also report distance and bearing to target in Guided_PosVel mode
This commit is contained in:
parent
fa4427fbce
commit
2235b22510
|
@ -41,6 +41,10 @@ void Copter::calc_wp_distance()
|
|||
wp_distance = wp_nav->get_wp_distance_to_destination();
|
||||
break;
|
||||
}
|
||||
if (guided_mode == Guided_PosVel) {
|
||||
wp_distance = pos_control->get_distance_to_target();
|
||||
break;
|
||||
}
|
||||
FALLTHROUGH;
|
||||
default:
|
||||
wp_distance = 0;
|
||||
|
@ -69,6 +73,10 @@ void Copter::calc_wp_bearing()
|
|||
wp_bearing = wp_nav->get_wp_bearing_to_destination();
|
||||
break;
|
||||
}
|
||||
if (guided_mode == Guided_PosVel) {
|
||||
wp_bearing = pos_control->get_bearing_to_target();
|
||||
break;
|
||||
}
|
||||
FALLTHROUGH;
|
||||
default:
|
||||
wp_bearing = 0;
|
||||
|
|
Loading…
Reference in New Issue