InertialNav: use AP_Math's longitude_scale

This commit is contained in:
Randy Mackay 2013-05-05 14:32:25 +09:00
parent 7c9d9b9800
commit 30faf87715

View File

@ -211,9 +211,11 @@ void AP_InertialNav::set_current_position(int32_t lon, int32_t lat)
_base_lon = lon; _base_lon = lon;
_base_lat = lat; _base_lat = lat;
// set longitude->meters scaling // set longitude to meters scaling to offset the shrinking longitude as we go towards the poles
// this is used to offset the shrinking longitude as we go towards the poles Location temp_loc;
_lon_to_m_scaling = cosf((fabsf((float)lat)*1.0e-7f) * DEG_TO_RAD) * LATLON_TO_CM; temp_loc.lat = lat;
temp_loc.lng = lon;
_lon_to_m_scaling = longitude_scale(&temp_loc) * LATLON_TO_CM;
// reset corrections to base position to zero // reset corrections to base position to zero
_position_base.x = 0; _position_base.x = 0;