mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed longitude wrap in verify_nav_wp
thanks to @Khancyr
This commit is contained in:
parent
7e60b7f117
commit
51a3bc170b
|
@ -592,7 +592,7 @@ bool Plane::verify_nav_wp(const AP_Mission::Mission_Command& cmd)
|
|||
float factor = (dist + cmd_passby) / dist;
|
||||
|
||||
flex_next_WP_loc.lat = flex_next_WP_loc.lat + (flex_next_WP_loc.lat - prev_WP_loc.lat) * (factor - 1.0f);
|
||||
flex_next_WP_loc.lng = flex_next_WP_loc.lng + (flex_next_WP_loc.lng - prev_WP_loc.lng) * (factor - 1.0f);
|
||||
flex_next_WP_loc.lng = flex_next_WP_loc.lng + Location::diff_longitude(flex_next_WP_loc.lng,prev_WP_loc.lng) * (factor - 1.0f);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue