mirror of https://github.com/ArduPilot/ardupilot
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:
parent
8ae1a58eae
commit
a747a4a19a
|
@ -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;
|
||||
|
||||
|
|
|
@ -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);
|
||||
|
|
Loading…
Reference in New Issue