Browse Source

Copter: fix wp distance and bearing reporting during LOITER_TURNS

mission-4.1.18
Randy Mackay 6 years ago
parent
commit
791b6effdd
  1. 14
      ArduCopter/mode_auto.cpp

14
ArduCopter/mode_auto.cpp

@ -573,13 +573,27 @@ bool Copter::ModeAuto::do_guided(const AP_Mission::Mission_Command& cmd) @@ -573,13 +573,27 @@ bool Copter::ModeAuto::do_guided(const AP_Mission::Mission_Command& cmd)
uint32_t Copter::ModeAuto::wp_distance() const
{
switch (_mode) {
case Auto_Circle:
return copter.circle_nav->get_distance_to_target();
case Auto_WP:
case Auto_CircleMoveToEdge:
default:
return wp_nav->get_wp_distance_to_destination();
}
}
int32_t Copter::ModeAuto::wp_bearing() const
{
switch (_mode) {
case Auto_Circle:
return copter.circle_nav->get_bearing_to_target();
case Auto_WP:
case Auto_CircleMoveToEdge:
default:
return wp_nav->get_wp_bearing_to_destination();
}
}
bool Copter::ModeAuto::get_wp(Location& destination)
{

Loading…
Cancel
Save