Tracker: bug fix re ignoring invalid START_LAT message

This commit is contained in:
Randy Mackay 2016-07-06 11:03:33 +09:00
parent 51bf638ad3
commit a079c7bf4c
1 changed files with 1 additions and 0 deletions

View File

@ -91,6 +91,7 @@ void Tracker::init_tracker()
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;
} else {
gcs_send_text(MAV_SEVERITY_NOTICE, "Ignoring invalid START_LATITUDE or START_LONGITUDE parameter");
}