mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tracker: sanity check home location parameters
This commit is contained in:
parent
84252405c3
commit
a9c6d34a9e
@ -94,8 +94,12 @@ void Tracker::init_tracker()
|
|||||||
|
|
||||||
// use given start positions - useful for indoor testing, and
|
// use given start positions - useful for indoor testing, and
|
||||||
// while waiting for GPS lock
|
// while waiting for GPS lock
|
||||||
current_loc.lat = g.start_latitude * 1.0e7f;
|
// sanity check location
|
||||||
current_loc.lng = g.start_longitude * 1.0e7f;
|
if (fabsf(current_loc.lat) <= 90.0f && fabsf(current_loc.lng) <= 180.0f) {
|
||||||
|
current_loc.lat = g.start_latitude * 1.0e7f;
|
||||||
|
current_loc.lng = g.start_longitude * 1.0e7f;
|
||||||
|
gcs_send_text_P(MAV_SEVERITY_WARNING, PSTR("ignoring invalid START_LATITUDE or START_LONGITUDE parameter"));
|
||||||
|
}
|
||||||
|
|
||||||
// see if EEPROM has a default location as well
|
// see if EEPROM has a default location as well
|
||||||
if (current_loc.lat == 0 && current_loc.lng == 0) {
|
if (current_loc.lat == 0 && current_loc.lng == 0) {
|
||||||
|
Loading…
Reference in New Issue
Block a user