AP_Devo_Telem: fix gpsDdToDmsFormat method

This fixes gpsDdToDmsFormat method to correctly convert decimal degrees to degrees minutes with less precision loss
This commit is contained in:
Shiv Tyagi 2021-11-11 21:59:26 +05:30 committed by Peter Barker
parent 8ae1a58eae
commit a747a4a19a
2 changed files with 5 additions and 5 deletions

View File

@ -48,10 +48,10 @@ void AP_DEVO_Telem::init()
}
uint32_t AP_DEVO_Telem::gpsDdToDmsFormat(float ddm)
uint32_t AP_DEVO_Telem::gpsDdToDmsFormat(int32_t ddm)
{
int32_t deg = (int32_t)ddm;
float mm = (ddm - deg) * 60.0f;
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;

View File

@ -31,7 +31,7 @@ public:
private:
uint32_t gpsDdToDmsFormat(float ddm);
uint32_t gpsDdToDmsFormat(int32_t ddm);
// tick - main call to send updates to transmitter
void tick(void);