mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
AP_GPS: fixed build of new MTK code
This commit is contained in:
parent
661d1500d2
commit
37d3affe3b
@ -135,7 +135,8 @@ restart:
|
||||
break;
|
||||
}
|
||||
|
||||
fix = ((_buffer.msg.fix_type == FIX_3D) || (_buffer.msg.fix_type == FIX_3D_SBAS);
|
||||
fix = ((_buffer.msg.fix_type == FIX_3D) ||
|
||||
(_buffer.msg.fix_type == FIX_3D_SBAS));
|
||||
latitude = _swapl(&_buffer.msg.latitude) * 10;
|
||||
longitude = _swapl(&_buffer.msg.longitude) * 10;
|
||||
altitude = _swapl(&_buffer.msg.altitude);
|
||||
|
@ -41,8 +41,8 @@ private:
|
||||
FIX_NONE = 1,
|
||||
FIX_2D = 2,
|
||||
FIX_3D = 3,
|
||||
FIX_3D_SBAS = 6,
|
||||
FIX_3D_SBAS =7
|
||||
FIX_2D_SBAS = 6,
|
||||
FIX_3D_SBAS = 7
|
||||
};
|
||||
|
||||
enum diyd_mtk_protocol_bytes {
|
||||
|
@ -131,7 +131,8 @@ restart:
|
||||
break;
|
||||
}
|
||||
|
||||
fix = ((_buffer.msg.fix_type == FIX_3D) || (_buffer.msg.fix_type == FIX_3D_SBAS);
|
||||
fix = ((_buffer.msg.fix_type == FIX_3D) ||
|
||||
(_buffer.msg.fix_type == FIX_3D_SBAS));
|
||||
latitude = _buffer.msg.latitude * 10; // XXX doc says *10e7 but device says otherwise
|
||||
longitude = _buffer.msg.longitude * 10; // XXX doc says *10e7 but device says otherwise
|
||||
altitude = _buffer.msg.altitude;
|
||||
|
@ -40,7 +40,8 @@ private:
|
||||
enum diyd_mtk_fix_type {
|
||||
FIX_NONE = 1,
|
||||
FIX_2D = 2,
|
||||
FIX_3D = 3
|
||||
FIX_3D = 3,
|
||||
FIX_3D_SBAS = 7
|
||||
};
|
||||
|
||||
enum diyd_mtk_protocol_bytes {
|
||||
|
Loading…
Reference in New Issue
Block a user