mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-12 10:58:30 -04:00
Copter: Guided: fix waypoint track reporting
This commit is contained in:
parent
04611f4c98
commit
e6d248f41d
@ -301,7 +301,8 @@ bool ModeGuided::get_wp(Location& destination)
|
|||||||
if (guided_mode != SubMode::WP) {
|
if (guided_mode != SubMode::WP) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
return wp_nav->get_oa_wp_destination(destination);
|
destination = Location(guided_pos_target_cm.tofloat(), guided_pos_terrain_alt ? Location::AltFrame::ABOVE_TERRAIN : Location::AltFrame::ABOVE_ORIGIN);
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// sets guided mode's target from a Location object
|
// sets guided mode's target from a Location object
|
||||||
|
Loading…
Reference in New Issue
Block a user