mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_AHRS: add sanity checks for home location being set
This commit is contained in:
parent
a722fd1323
commit
ab9c084179
@ -1033,6 +1033,14 @@ bool AP_AHRS_DCM::airspeed_estimate(float *airspeed_ret) const
|
|||||||
|
|
||||||
bool AP_AHRS_DCM::set_home(const Location &loc)
|
bool AP_AHRS_DCM::set_home(const Location &loc)
|
||||||
{
|
{
|
||||||
|
// check location is valid
|
||||||
|
if (loc.lat == 0 && loc.lng == 0 && loc.alt == 0) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
if (!check_latlng(loc)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
_home = loc;
|
_home = loc;
|
||||||
_home_is_set = true;
|
_home_is_set = true;
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user