mirror of https://github.com/ArduPilot/ardupilot
Fixed navigation bug
This commit is contained in:
parent
f3b3350d25
commit
104f93cef5
|
@ -30,9 +30,7 @@ static bool check_missed_wp()
|
||||||
{
|
{
|
||||||
int32_t temp = target_bearing - original_target_bearing;
|
int32_t temp = target_bearing - original_target_bearing;
|
||||||
temp = wrap_180(temp);
|
temp = wrap_180(temp);
|
||||||
//return (abs(temp) > 10000); //we pased the waypoint by 10 °
|
return (abs(temp) > 10000); //we pased the waypoint by 10 °
|
||||||
// temp testing
|
|
||||||
return false;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// ------------------------------
|
// ------------------------------
|
||||||
|
|
Loading…
Reference in New Issue