AP_Devo_Telem: Change division to multiplication

This commit is contained in:
muramura 2024-04-20 19:15:16 +09:00 committed by Peter Barker
parent 8513837445
commit ee1cb4d35b

View File

@ -56,7 +56,7 @@ uint32_t AP_DEVO_Telem::gpsDdToDmsFormat(int32_t ddm)
int32_t deg = (int32_t)(ddm * 1e-7);
float mm = (ddm * 1.0e-7 - deg) * 60.0f;
mm = ((float)deg * 100.0f + mm) /100.0f;
mm = ((float)deg * 100.0f + mm) *0.01f;
if ((mm < -180.0f) || (mm > 180.0f)) {
mm = 0.0f;