Tracker: fix start lat, lon sanity check

This commit is contained in:
ggregory8 2015-10-27 12:50:29 +09:00 committed by Randy Mackay
parent ca942f39dd
commit 76871ef0cd
1 changed files with 1 additions and 1 deletions

View File

@ -95,7 +95,7 @@ void Tracker::init_tracker()
// use given start positions - useful for indoor testing, and
// while waiting for GPS lock
// sanity check location
if (fabsf(current_loc.lat) <= 90.0f && fabsf(current_loc.lng) <= 180.0f) {
if (fabsf(g.start_latitude) <= 90.0f && fabsf(g.start_longitude) <= 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"));