mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
SITL: parse home coordinates as double (not float) to avoid precision loss
This commit is contained in:
parent
1755f5b6c7
commit
8ff9923e07
@ -126,9 +126,9 @@ bool Aircraft::parse_home(const char *home_str, Location &loc, float &yaw_degree
|
||||
}
|
||||
|
||||
memset(&loc, 0, sizeof(loc));
|
||||
loc.lat = static_cast<int32_t>(strtof(lat_s, nullptr) * 1.0e7f);
|
||||
loc.lng = static_cast<int32_t>(strtof(lon_s, nullptr) * 1.0e7f);
|
||||
loc.alt = static_cast<int32_t>(strtof(alt_s, nullptr) * 1.0e2f);
|
||||
loc.lat = static_cast<int32_t>(strtod(lat_s, nullptr) * 1.0e7);
|
||||
loc.lng = static_cast<int32_t>(strtod(lon_s, nullptr) * 1.0e7);
|
||||
loc.alt = static_cast<int32_t>(strtod(alt_s, nullptr) * 1.0e2);
|
||||
|
||||
if (loc.lat == 0 && loc.lng == 0) {
|
||||
// default to CMAC instead of middle of the ocean. This makes
|
||||
|
Loading…
Reference in New Issue
Block a user