mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Copter: leave old_loc check instead of changing alt frame.
This commit is contained in:
parent
8346203d43
commit
a95b5bc0dc
@ -457,11 +457,13 @@ bool Copter::get_target_location(Location& target_loc)
|
|||||||
*/
|
*/
|
||||||
bool Copter::update_target_location(const Location &old_loc, const Location &new_loc)
|
bool Copter::update_target_location(const Location &old_loc, const Location &new_loc)
|
||||||
{
|
{
|
||||||
Location next_wp_loc;
|
Location next_WP_loc;
|
||||||
next_wp_loc = new_loc;
|
flightmode->get_wp(next_WP_loc);
|
||||||
next_wp_loc.change_alt_frame(old_loc.get_alt_frame());
|
if (!old_loc.same_loc_as(next_WP_loc)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
return set_target_location(next_wp_loc);
|
return set_target_location(new_loc);
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // AP_SCRIPTING_ENABLED
|
#endif // AP_SCRIPTING_ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user