mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: circle mode uses AC_Circle get_distance_to_target
This commit is contained in:
parent
9de73a994f
commit
acfc3a606a
@ -97,12 +97,12 @@ void Copter::ModeCircle::run()
|
|||||||
|
|
||||||
uint32_t Copter::ModeCircle::wp_distance() const
|
uint32_t Copter::ModeCircle::wp_distance() const
|
||||||
{
|
{
|
||||||
return wp_nav->get_loiter_distance_to_target();
|
return copter.circle_nav->get_distance_to_target();
|
||||||
}
|
}
|
||||||
|
|
||||||
int32_t Copter::ModeCircle::wp_bearing() const
|
int32_t Copter::ModeCircle::wp_bearing() const
|
||||||
{
|
{
|
||||||
return wp_nav->get_loiter_bearing_to_target();
|
return copter.circle_nav->get_bearing_to_target();
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user