mirror of https://github.com/ArduPilot/ardupilot
Tracker: bug fix re ignoring invalid START_LAT message
This commit is contained in:
parent
51bf638ad3
commit
a079c7bf4c
|
@ -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");
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue