mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Common: avoid using AP_Math is_zero() because it is classless
- because it is classless it can not be called like AP_Math::is_zero() and will then conflict with local definition of is_zero()
This commit is contained in:
parent
3edd95b99b
commit
b78255cc25
@ -234,7 +234,8 @@ float Location_Class::get_distance(const struct Location &loc2) const
|
||||
// extrapolate latitude/longitude given distances (in meters) north and east
|
||||
void Location_Class::offset(float ofs_north, float ofs_east)
|
||||
{
|
||||
if (!is_zero(ofs_north) || !is_zero(ofs_east)) {
|
||||
// use is_equal() because is_zero() is a local class conflict and is_zero() in AP_Math does not belong to a class
|
||||
if (!is_equal(ofs_north, 0.0f) || !is_equal(ofs_east, 0.0f)) {
|
||||
int32_t dlat = ofs_north * LOCATION_SCALING_FACTOR_INV;
|
||||
int32_t dlng = (ofs_east * LOCATION_SCALING_FACTOR_INV) / longitude_scale(*this);
|
||||
lat += dlat;
|
||||
|
Loading…
Reference in New Issue
Block a user