VectorNav C Library
upack.h
1 #ifndef VNUPACK_H_INCLUDED
2 #define VNUPACK_H_INCLUDED
3 
4 #include <stdarg.h>
5 
6 #include "vn/int.h"
7 #include "vn/bool.h"
8 #include "vn/enum.h"
9 #include "vn/error.h"
10 #include "vn/error_detection.h"
11 #include "vn/math/matrix.h"
12 #include "vn/math/vector.h"
13 #include "vn/protocol/common.h"
14 
15 #ifndef VNUART_PROTOCOL_BUFFER_SIZE
16 
17  #define VNUART_PROTOCOL_BUFFER_SIZE 256
18 #endif
19 
20 #define VN_BINARY_START_CHAR 0xFA
21 #define VN_ASCII_START_CHAR '$'
22 
23 #ifdef __cplusplus
24 extern "C" {
25 #endif
26 
30 typedef void(*vnuart_sensor_error_received)(VnError error);
31 
34 typedef struct
35 {
37  size_t curExtractLoc;
38 
40  size_t length;
41 
43  uint8_t* data;
44 
45 } VnUartPacket;
46 
52 void VnUartPacket_initialize(VnUartPacket* packet, uint8_t* data, size_t len);
53 
58 void VnUartPacket_initializeFromStr(VnUartPacket* packet, char* data);
59 
69 bool VnUartPacket_isValid(VnUartPacket *packet);
70 
77 bool VnUartPacket_isAsciiAsync(VnUartPacket *packet);
78 
86 bool VnUartPacket_isResponse(VnUartPacket *packet);
87 
93 bool VnUartPacket_isError(VnUartPacket *packet);
94 
100 bool VnUartPacket_isErrorRaw(uint8_t *packet);
101 
106 PacketType VnUartPacket_type(VnUartPacket *packet);
107 
115 VnError VnUartPacket_finalizeCommand(VnErrorDetectionMode errorDetectionMode, uint8_t *packet, size_t *length);
116 
121 uint8_t VnUartPacket_groups(VnUartPacket* packet);
122 
128 uint16_t VnUartPacket_groupField(VnUartPacket* packet, size_t groupIndex);
129 
141 size_t VnUartPacket_computeBinaryPacketLength(uint8_t const *startOfPossibleBinaryPacket);
142 
149 size_t VnUartPacket_computeNumOfBytesForBinaryGroupPayload(BinaryGroupType groupType, uint16_t groupField);
150 
164 bool VnUartPacket_isCompatible(
165  VnUartPacket *packet,
166  CommonGroup commonGroup,
167  TimeGroup timeGroup,
168  ImuGroup imuGroup,
169  GpsGroup gpsGroup,
170  AttitudeGroup attitudeGroup,
171  InsGroup insGroup);
172 
185 uint8_t VnUartPacket_extractUint8(VnUartPacket *packet);
186 
193 int8_t VnUartPacket_extractInt8(VnUartPacket *packet);
194 
201 uint16_t VnUartPacket_extractUint16(VnUartPacket *packet);
202 
209 uint32_t VnUartPacket_extractUint32(VnUartPacket *packet);
210 
217 uint64_t VnUartPacket_extractUint64(VnUartPacket *packet);
218 
225 
233 
241 
249 
256 
264 VnAsciiAsync VnUartPacket_determineAsciiAsyncType(VnUartPacket* packet);
265 
283 void VnUartPacket_parseVNYPR(VnUartPacket* packet, vec3f *yawPitchRoll);
284 
290 void VnUartPacket_parseVNQTN(VnUartPacket* packet, vec4f *quaternion);
291 
292 #ifdef EXTRA
293 
300 void VnUartPacket_parseVNQTM(VnUartPacket* packet, vec4f *quaternion, vec3f *magnetic);
301 
308 void VnUartPacket_parseVNQTA(VnUartPacket* packet, vec4f *quaternion, vec3f *acceleration);
309 
316 void VnUartPacket_parseVNQTR(VnUartPacket* packet, vec4f *quaternion, vec3f *angularRate);
317 
325 void VnUartPacket_parseVNQMA(VnUartPacket* packet, vec4f *quaternion, vec3f *magnetic, vec3f *acceleration);
326 
334 void VnUartPacket_parseVNQAR(VnUartPacket* packet, vec4f *quaternion, vec3f *acceleration, vec3f *angularRate);
335 
336 #endif
337 
346 void VnUartPacket_parseVNQMR(VnUartPacket* packet, vec4f *quaternion, vec3f *magnetic, vec3f *acceleration, vec3f *angularRate);
347 
348 #ifdef EXTRA
349 
355 void VnUartPacket_parseVNDCM(VnUartPacket* packet, mat3f *dcm);
356 
357 #endif
358 
364 void VnUartPacket_parseVNMAG(VnUartPacket* packet, vec3f *magnetic);
365 
371 void VnUartPacket_parseVNACC(VnUartPacket* packet, vec3f *acceleration);
372 
378 void VnUartPacket_parseVNGYR(VnUartPacket* packet, vec3f *angularRate);
379 
387 void VnUartPacket_parseVNMAR(VnUartPacket* packet, vec3f *magnetic, vec3f *acceleration, vec3f *angularRate);
388 
397  VnUartPacket* packet,
398  vec3f *yawPitchRoll,
399  vec3f *magnetic,
400  vec3f *acceleration,
401  vec3f *angularRate);
402 
411 /*VnError VnUartPacket_parseVNYMR(
412  uint8_t* packetBuf,
413  size_t packetLen,
414  vec3f *yawPitchRoll,
415  vec3f *magnetic,
416  vec3f *acceleration,
417  vec3f *angularRate);*/
418 
419 
420 #ifdef EXTRA
421 
431 void VnUartPacket_parseVNYCM(VnUartPacket* packet, vec3f *yawPitchRoll, vec3f *magnetic, vec3f *acceleration, vec3f *angularRate, float *temperature);
432 
433 #endif
434 
442 void VnUartPacket_parseVNYBA(VnUartPacket* packet, vec3f *yawPitchRoll, vec3f *accelerationBody, vec3f *angularRate);
443 
451 void VnUartPacket_parseVNYIA(VnUartPacket* packet, vec3f *yawPitchRoll, vec3f *accelerationInertial, vec3f *angularRate);
452 
453 #ifdef EXTRA
454 
463 void VnUartPacket_parseVNICM(VnUartPacket* packet, vec3f *yawPitchRoll, vec3f *magnetic, vec3f *accelerationInertial, vec3f *angularRate);
464 
465 #endif
466 
476 void VnUartPacket_parseVNIMU(VnUartPacket* packet, vec3f *magneticUncompensated, vec3f *accelerationUncompensated, vec3f *angularRateUncompensated, float *temperature, float *pressure);
477 
491 void VnUartPacket_parseVNGPS(VnUartPacket* packet, double *time, uint16_t *week, uint8_t *gpsFix, uint8_t *numSats, vec3d *lla, vec3f *nedVel, vec3f *nedAcc, float *speedAcc, float *timeAcc);
492 
506 void VnUartPacket_parseVNINS(VnUartPacket* packet, double *time, uint16_t *week, uint16_t *status, vec3f *yawPitchRoll, vec3d *lla, vec3f *nedVel, float *attUncertainty, float *posUncertainty, float *velUncertainty);
507 
520 void VnUartPacket_parseVNINE(VnUartPacket* packet, double *time, uint16_t *week, uint16_t *status, vec3f *yawPitchRoll, vec3d *position, vec3f *velocity, float *attUncertainty, float *posUncertainty, float *velUncertainty);
521 
530 void VnUartPacket_parseVNISL(VnUartPacket* packet, vec3f* ypr, vec3d* lla, vec3f* velocity, vec3f* acceleration, vec3f* angularRate);
531 
540 void VnUartPacket_parseVNISE(VnUartPacket* packet, vec3f* ypr, vec3d* position, vec3f* velocity, vec3f* acceleration, vec3f* angularRate);
541 
542 #ifdef EXTRA
543 
552 void VnUartPacket_parseVNRAW(VnUartPacket* packet, vec3f *magneticVoltage, vec3f *accelerationVoltage, vec3f *angularRateVoltage, float *temperatureVoltage);
553 
562 void VnUartPacket_parseVNCMV(VnUartPacket* packet, vec3f *magneticUncompensated, vec3f *accelerationUncompensated, vec3f *angularRateUncompensated, float *temperature);
563 
570 void VnUartPacket_parseVNSTV(VnUartPacket* packet, vec4f *quaternion, vec3f *angularRateBias);
571 
578 void VnUartPacket_parseVNCOV(VnUartPacket* packet, vec3f *attitudeVariance, vec3f *angularRateBiasVariance);
579 
580 #endif
581 
595 void VnUartPacket_parseVNGPE(VnUartPacket* packet, double *tow, uint16_t *week, uint8_t *gpsFix, uint8_t *numSats, vec3d *position, vec3f *velocity, vec3f *posAcc, float *speedAcc, float *timeAcc);
596 
604 void VnUartPacket_parseVNDTV(VnUartPacket* packet, float *deltaTime, vec3f *deltaTheta, vec3f *deltaVelocity);
605 
618 VnError vnuart_genread(
619  uint8_t *buffer,
620  size_t bufferSize,
621  VnErrorDetectionMode errorDetectionMode,
622  uint16_t registerId,
623  size_t *cmdSize);
624 
650  uint8_t *buffer,
651  size_t bufferSize,
652  VnErrorDetectionMode errorDetectionMode,
653  size_t *cmdSize);
654 
664  uint8_t *buffer,
665  size_t bufferSize,
666  VnErrorDetectionMode errorDetectionMode,
667  size_t *cmdSize);
668 
678  uint8_t *buffer,
679  size_t bufferSize,
680  VnErrorDetectionMode errorDetectionMode,
681  size_t *cmdSize);
682 
683 #ifdef EXTRA
684 
693 VnError VnUartPacket_genReadBinaryOutput4(
694  uint8_t *buffer,
695  size_t bufferSize,
696  VnErrorDetectionMode errorDetectionMode,
697  size_t *cmdSize);
698 
707 VnError VnUartPacket_genReadBinaryOutput5(
708  uint8_t *buffer,
709  size_t bufferSize,
710  VnErrorDetectionMode errorDetectionMode,
711  size_t *cmdSize);
712 
713 #endif
714 
724  uint8_t *buffer,
725  size_t bufferSize,
726  VnErrorDetectionMode errorDetectionMode,
727  size_t *cmdSize);
728 
738  uint8_t *buffer,
739  size_t bufferSize,
740  VnErrorDetectionMode errorDetectionMode,
741  size_t *cmdSize);
742 
752  uint8_t *buffer,
753  size_t bufferSize,
754  VnErrorDetectionMode errorDetectionMode,
755  size_t *cmdSize);
756 
766  uint8_t *buffer,
767  size_t bufferSize,
768  VnErrorDetectionMode errorDetectionMode,
769  size_t *cmdSize);
770 
780  uint8_t *buffer,
781  size_t bufferSize,
782  VnErrorDetectionMode errorDetectionMode,
783  size_t *cmdSize);
784 
795  uint8_t *buffer,
796  size_t bufferSize,
797  VnErrorDetectionMode errorDetectionMode,
798  bool disturbancePresent,
799  size_t *cmdSize);
800 
811  uint8_t *buffer,
812  size_t bufferSize,
813  VnErrorDetectionMode errorDetectionMode,
814  bool disturbancePresent,
815  size_t *cmdSize);
816 
826  char *buffer,
827  size_t bufferSize,
828  VnErrorDetectionMode errorDetectionMode,
829  size_t *cmdSize);
830 
840  char *buffer,
841  size_t bufferSize,
842  VnErrorDetectionMode errorDetectionMode,
843  size_t *cmdSize);
844 
854  char *buffer,
855  size_t bufferSize,
856  VnErrorDetectionMode errorDetectionMode,
857  size_t *cmdSize);
858 
868  char *buffer,
869  size_t bufferSize,
870  VnErrorDetectionMode errorDetectionMode,
871  size_t *cmdSize);
872 
882  char *buffer,
883  size_t bufferSize,
884  VnErrorDetectionMode errorDetectionMode,
885  size_t *cmdSize);
886 
896  char *buffer,
897  size_t bufferSize,
898  VnErrorDetectionMode errorDetectionMode,
899  size_t *cmdSize);
900 
910  char *buffer,
911  size_t bufferSize,
912  VnErrorDetectionMode errorDetectionMode,
913  size_t *cmdSize);
914 
924  char *buffer,
925  size_t bufferSize,
926  VnErrorDetectionMode errorDetectionMode,
927  size_t *cmdSize);
928 
938  char *buffer,
939  size_t bufferSize,
940  VnErrorDetectionMode errorDetectionMode,
941  size_t *cmdSize);
942 
952  char *buffer,
953  size_t bufferSize,
954  VnErrorDetectionMode errorDetectionMode,
955  size_t *cmdSize);
956 
966  char *buffer,
967  size_t bufferSize,
968  VnErrorDetectionMode errorDetectionMode,
969  size_t *cmdSize);
970 
980  char *buffer,
981  size_t bufferSize,
982  VnErrorDetectionMode errorDetectionMode,
983  size_t *cmdSize);
984 
994  char *buffer,
995  size_t bufferSize,
996  VnErrorDetectionMode errorDetectionMode,
997  size_t *cmdSize);
998 
1008  char *buffer,
1009  size_t bufferSize,
1010  VnErrorDetectionMode errorDetectionMode,
1011  size_t *cmdSize);
1012 
1022  char *buffer,
1023  size_t bufferSize,
1024  VnErrorDetectionMode errorDetectionMode,
1025  size_t *cmdSize);
1026 
1036  char *buffer,
1037  size_t bufferSize,
1038  VnErrorDetectionMode errorDetectionMode,
1039  size_t *cmdSize);
1040 
1050  char *buffer,
1051  size_t bufferSize,
1052  VnErrorDetectionMode errorDetectionMode,
1053  size_t *cmdSize);
1054 
1064  char *buffer,
1065  size_t bufferSize,
1066  VnErrorDetectionMode errorDetectionMode,
1067  size_t *cmdSize);
1068 
1078  char *buffer,
1079  size_t bufferSize,
1080  VnErrorDetectionMode errorDetectionMode,
1081  size_t *cmdSize);
1082 
1092  char *buffer,
1093  size_t bufferSize,
1094  VnErrorDetectionMode errorDetectionMode,
1095  size_t *cmdSize);
1096 
1106  char *buffer,
1107  size_t bufferSize,
1108  VnErrorDetectionMode errorDetectionMode,
1109  size_t *cmdSize);
1110 
1120  char *buffer,
1121  size_t bufferSize,
1122  VnErrorDetectionMode errorDetectionMode,
1123  size_t *cmdSize);
1124 
1134  char *buffer,
1135  size_t bufferSize,
1136  VnErrorDetectionMode errorDetectionMode,
1137  size_t *cmdSize);
1138 
1148  char *buffer,
1149  size_t bufferSize,
1150  VnErrorDetectionMode errorDetectionMode,
1151  size_t *cmdSize);
1152 
1162  char *buffer,
1163  size_t bufferSize,
1164  VnErrorDetectionMode errorDetectionMode,
1165  size_t *cmdSize);
1166 
1176  char *buffer,
1177  size_t bufferSize,
1178  VnErrorDetectionMode errorDetectionMode,
1179  size_t *cmdSize);
1180 
1190  char *buffer,
1191  size_t bufferSize,
1192  VnErrorDetectionMode errorDetectionMode,
1193  size_t *cmdSize);
1194 
1204  char *buffer,
1205  size_t bufferSize,
1206  VnErrorDetectionMode errorDetectionMode,
1207  size_t *cmdSize);
1208 
1218  char *buffer,
1219  size_t bufferSize,
1220  VnErrorDetectionMode errorDetectionMode,
1221  size_t *cmdSize);
1222 
1232  char *buffer,
1233  size_t bufferSize,
1234  VnErrorDetectionMode errorDetectionMode,
1235  size_t *cmdSize);
1236 
1246  char *buffer,
1247  size_t bufferSize,
1248  VnErrorDetectionMode errorDetectionMode,
1249  size_t *cmdSize);
1250 
1260  char *buffer,
1261  size_t bufferSize,
1262  VnErrorDetectionMode errorDetectionMode,
1263  size_t *cmdSize);
1264 
1274  char *buffer,
1275  size_t bufferSize,
1276  VnErrorDetectionMode errorDetectionMode,
1277  size_t *cmdSize);
1278 
1288  char *buffer,
1289  size_t bufferSize,
1290  VnErrorDetectionMode errorDetectionMode,
1291  size_t *cmdSize);
1292 
1302  char *buffer,
1303  size_t bufferSize,
1304  VnErrorDetectionMode errorDetectionMode,
1305  size_t *cmdSize);
1306 
1316  char *buffer,
1317  size_t bufferSize,
1318  VnErrorDetectionMode errorDetectionMode,
1319  size_t *cmdSize);
1320 
1330  char *buffer,
1331  size_t bufferSize,
1332  VnErrorDetectionMode errorDetectionMode,
1333  size_t *cmdSize);
1334 
1344  char *buffer,
1345  size_t bufferSize,
1346  VnErrorDetectionMode errorDetectionMode,
1347  size_t *cmdSize);
1348 
1358  char *buffer,
1359  size_t bufferSize,
1360  VnErrorDetectionMode errorDetectionMode,
1361  size_t *cmdSize);
1362 
1372  char *buffer,
1373  size_t bufferSize,
1374  VnErrorDetectionMode errorDetectionMode,
1375  size_t *cmdSize);
1376 
1386  char *buffer,
1387  size_t bufferSize,
1388  VnErrorDetectionMode errorDetectionMode,
1389  size_t *cmdSize);
1390 
1400  char *buffer,
1401  size_t bufferSize,
1402  VnErrorDetectionMode errorDetectionMode,
1403  size_t *cmdSize);
1404 
1414  char *buffer,
1415  size_t bufferSize,
1416  VnErrorDetectionMode errorDetectionMode,
1417  size_t *cmdSize);
1418 
1428  char *buffer,
1429  size_t bufferSize,
1430  VnErrorDetectionMode errorDetectionMode,
1431  size_t *cmdSize);
1432 
1442  char *buffer,
1443  size_t bufferSize,
1444  VnErrorDetectionMode errorDetectionMode,
1445  size_t *cmdSize);
1446 
1456  char *buffer,
1457  size_t bufferSize,
1458  VnErrorDetectionMode errorDetectionMode,
1459  size_t *cmdSize);
1460 
1470  char *buffer,
1471  size_t bufferSize,
1472  VnErrorDetectionMode errorDetectionMode,
1473  size_t *cmdSize);
1474 
1484  char *buffer,
1485  size_t bufferSize,
1486  VnErrorDetectionMode errorDetectionMode,
1487  size_t *cmdSize);
1488 
1498  char *buffer,
1499  size_t bufferSize,
1500  VnErrorDetectionMode errorDetectionMode,
1501  size_t *cmdSize);
1502 
1512  char *buffer,
1513  size_t bufferSize,
1514  VnErrorDetectionMode errorDetectionMode,
1515  size_t *cmdSize);
1516 
1526  char *buffer,
1527  size_t bufferSize,
1528  VnErrorDetectionMode errorDetectionMode,
1529  size_t *cmdSize);
1530 
1578 VnError VnUartPacket_genWrite(
1579  uint8_t *buffer,
1580  size_t bufferSize,
1581  VnErrorDetectionMode errorDetectionMode,
1582  uint16_t registerId,
1583  size_t *cmdSize,
1584  char const *format,
1585  ...);
1586 
1628  uint8_t *buffer,
1629  size_t bufferSize,
1630  VnErrorDetectionMode errorDetectionMode,
1631  size_t *cmdSize,
1632  uint16_t asyncMode,
1633  uint16_t rateDivisor,
1634  uint16_t commonField,
1635  uint16_t timeField,
1636  uint16_t imuField,
1637  uint16_t gpsField,
1638  uint16_t attitudeField,
1639  uint16_t insField);
1640 
1658  uint8_t *buffer,
1659  size_t bufferSize,
1660  VnErrorDetectionMode errorDetectionMode,
1661  size_t *cmdSize,
1662  uint16_t asyncMode,
1663  uint16_t rateDivisor,
1664  uint16_t commonField,
1665  uint16_t timeField,
1666  uint16_t imuField,
1667  uint16_t gpsField,
1668  uint16_t attitudeField,
1669  uint16_t insField);
1670 
1688  uint8_t *buffer,
1689  size_t bufferSize,
1690  VnErrorDetectionMode errorDetectionMode,
1691  size_t *cmdSize,
1692  uint16_t asyncMode,
1693  uint16_t rateDivisor,
1694  uint16_t commonField,
1695  uint16_t timeField,
1696  uint16_t imuField,
1697  uint16_t gpsField,
1698  uint16_t attitudeField,
1699  uint16_t insField);
1700 
1701 #ifdef EXTRA
1702 
1719 VnError VnUartPacket_genWriteBinaryOutput4(
1720  uint8_t *buffer,
1721  size_t bufferSize,
1722  VnErrorDetectionMode errorDetectionMode,
1723  size_t *cmdSize,
1724  uint16_t asyncMode,
1725  uint16_t rateDivisor,
1726  uint16_t commonField,
1727  uint16_t timeField,
1728  uint16_t imuField,
1729  uint16_t gpsField,
1730  uint16_t attitudeField,
1731  uint16_t insField);
1732 
1749 VnError VnUartPacket_genWriteBinaryOutput5(
1750  uint8_t *buffer,
1751  size_t bufferSize,
1752  VnErrorDetectionMode errorDetectionMode,
1753  size_t *cmdSize,
1754  uint16_t asyncMode,
1755  uint16_t rateDivisor,
1756  uint16_t commonField,
1757  uint16_t timeField,
1758  uint16_t imuField,
1759  uint16_t gpsField,
1760  uint16_t attitudeField,
1761  uint16_t insField);
1762 
1763 #endif
1764 
1774  char *buffer,
1775  size_t bufferSize,
1776  VnErrorDetectionMode errorDetectionMode,
1777  size_t *cmdSize,
1778  char* tag);
1779 
1789  char *buffer,
1790  size_t bufferSize,
1791  VnErrorDetectionMode errorDetectionMode,
1792  size_t *cmdSize,
1793  uint32_t baudrate);
1794 
1804  char *buffer,
1805  size_t bufferSize,
1806  VnErrorDetectionMode errorDetectionMode,
1807  size_t *cmdSize,
1808  uint32_t baudrate);
1809 
1819  char *buffer,
1820  size_t bufferSize,
1821  VnErrorDetectionMode errorDetectionMode,
1822  size_t *cmdSize,
1823  uint32_t ador);
1824 
1834  char *buffer,
1835  size_t bufferSize,
1836  VnErrorDetectionMode errorDetectionMode,
1837  size_t *cmdSize,
1838  uint32_t ador);
1839 
1849  char *buffer,
1850  size_t bufferSize,
1851  VnErrorDetectionMode errorDetectionMode,
1852  size_t *cmdSize,
1853  uint32_t adof);
1854 
1864  char *buffer,
1865  size_t bufferSize,
1866  VnErrorDetectionMode errorDetectionMode,
1867  size_t *cmdSize,
1868  uint32_t adof);
1869 
1880  char *buffer,
1881  size_t bufferSize,
1882  VnErrorDetectionMode errorDetectionMode,
1883  size_t *cmdSize,
1884  vec3f magRef,
1885  vec3f accRef);
1886 
1897  char *buffer,
1898  size_t bufferSize,
1899  VnErrorDetectionMode errorDetectionMode,
1900  size_t *cmdSize,
1901  mat3f c,
1902  vec3f b);
1903 
1914  char *buffer,
1915  size_t bufferSize,
1916  VnErrorDetectionMode errorDetectionMode,
1917  size_t *cmdSize,
1918  mat3f c,
1919  vec3f b);
1920 
1930  char *buffer,
1931  size_t bufferSize,
1932  VnErrorDetectionMode errorDetectionMode,
1933  size_t *cmdSize,
1934  mat3f c);
1935 
1951  char *buffer,
1952  size_t bufferSize,
1953  VnErrorDetectionMode errorDetectionMode,
1954  size_t *cmdSize,
1955  uint8_t serialCount,
1956  uint8_t serialStatus,
1957  uint8_t spiCount,
1958  uint8_t spiStatus,
1959  uint8_t serialChecksum,
1960  uint8_t spiChecksum,
1961  uint8_t errorMode);
1962 
1980  char *buffer,
1981  size_t bufferSize,
1982  VnErrorDetectionMode errorDetectionMode,
1983  size_t *cmdSize,
1984  uint8_t syncInMode,
1985  uint8_t syncInEdge,
1986  uint16_t syncInSkipFactor,
1987  uint32_t reserved1,
1988  uint8_t syncOutMode,
1989  uint8_t syncOutPolarity,
1990  uint16_t syncOutSkipFactor,
1991  uint32_t syncOutPulseWidth,
1992  uint32_t reserved2);
1993 
2005  char *buffer,
2006  size_t bufferSize,
2007  VnErrorDetectionMode errorDetectionMode,
2008  size_t *cmdSize,
2009  uint32_t syncInCount,
2010  uint32_t syncInTime,
2011  uint32_t syncOutCount);
2012 
2025  char *buffer,
2026  size_t bufferSize,
2027  VnErrorDetectionMode errorDetectionMode,
2028  size_t *cmdSize,
2029  uint8_t enable,
2030  uint8_t headingMode,
2031  uint8_t filteringMode,
2032  uint8_t tuningMode);
2033 
2045  char *buffer,
2046  size_t bufferSize,
2047  VnErrorDetectionMode errorDetectionMode,
2048  size_t *cmdSize,
2049  vec3f baseTuning,
2050  vec3f adaptiveTuning,
2051  vec3f adaptiveFiltering);
2052 
2064  char *buffer,
2065  size_t bufferSize,
2066  VnErrorDetectionMode errorDetectionMode,
2067  size_t *cmdSize,
2068  vec3f baseTuning,
2069  vec3f adaptiveTuning,
2070  vec3f adaptiveFiltering);
2071 
2083  char *buffer,
2084  size_t bufferSize,
2085  VnErrorDetectionMode errorDetectionMode,
2086  size_t *cmdSize,
2087  uint8_t hsiMode,
2088  uint8_t hsiOutput,
2089  uint8_t convergeRate);
2090 
2100  char *buffer,
2101  size_t bufferSize,
2102  VnErrorDetectionMode errorDetectionMode,
2103  size_t *cmdSize,
2104  vec3f velocity);
2105 
2117  char *buffer,
2118  size_t bufferSize,
2119  VnErrorDetectionMode errorDetectionMode,
2120  size_t *cmdSize,
2121  uint8_t mode,
2122  float velocityTuning,
2123  float rateTuning);
2124 
2138  char *buffer,
2139  size_t bufferSize,
2140  VnErrorDetectionMode errorDetectionMode,
2141  size_t *cmdSize,
2142  uint8_t mode,
2143  uint8_t ppsSource,
2144  uint8_t reserved1,
2145  uint8_t reserved2,
2146  uint8_t reserved3);
2147 
2157  char *buffer,
2158  size_t bufferSize,
2159  VnErrorDetectionMode errorDetectionMode,
2160  size_t *cmdSize,
2161  vec3f position);
2162 
2175  char *buffer,
2176  size_t bufferSize,
2177  VnErrorDetectionMode errorDetectionMode,
2178  size_t *cmdSize,
2179  uint8_t scenario,
2180  uint8_t ahrsAiding,
2181  uint8_t estBaseline,
2182  uint8_t resv2);
2183 
2195  char *buffer,
2196  size_t bufferSize,
2197  VnErrorDetectionMode errorDetectionMode,
2198  size_t *cmdSize,
2199  vec3f gyroBias,
2200  vec3f accelBias,
2201  float pressureBias);
2202 
2216  char *buffer,
2217  size_t bufferSize,
2218  VnErrorDetectionMode errorDetectionMode,
2219  size_t *cmdSize,
2220  uint8_t integrationFrame,
2221  uint8_t gyroCompensation,
2222  uint8_t accelCompensation,
2223  uint8_t reserved1,
2224  uint16_t reserved2);
2225 
2241  char *buffer,
2242  size_t bufferSize,
2243  VnErrorDetectionMode errorDetectionMode,
2244  size_t *cmdSize,
2245  uint8_t useMagModel,
2246  uint8_t useGravityModel,
2247  uint8_t resv1,
2248  uint8_t resv2,
2249  uint32_t recalcThreshold,
2250  float year,
2251  vec3d position);
2252 
2263  char *buffer,
2264  size_t bufferSize,
2265  VnErrorDetectionMode errorDetectionMode,
2266  size_t *cmdSize,
2267  mat3f c,
2268  vec3f b);
2269 
2288  char *buffer,
2289  size_t bufferSize,
2290  VnErrorDetectionMode errorDetectionMode,
2291  size_t *cmdSize,
2292  uint16_t magWindowSize,
2293  uint16_t accelWindowSize,
2294  uint16_t gyroWindowSize,
2295  uint16_t tempWindowSize,
2296  uint16_t presWindowSize,
2297  uint8_t magFilterMode,
2298  uint8_t accelFilterMode,
2299  uint8_t gyroFilterMode,
2300  uint8_t tempFilterMode,
2301  uint8_t presFilterMode);
2302 
2313  char *buffer,
2314  size_t bufferSize,
2315  VnErrorDetectionMode errorDetectionMode,
2316  size_t *cmdSize,
2317  vec3f position,
2318  vec3f uncertainty);
2319 
2325 void VnUartPacket_parseError(VnUartPacket *packet, uint8_t *error);
2326 
2332 void VnUartPacket_parseErrorRaw(uint8_t *packet, uint8_t *error);
2333 
2348  VnUartPacket *packet,
2349  uint16_t* asyncMode,
2350  uint16_t* rateDivisor,
2351  uint16_t* outputGroup,
2352  uint16_t* commonField,
2353  uint16_t* timeField,
2354  uint16_t* imuField,
2355  uint16_t* gpsField,
2356  uint16_t* attitudeField,
2357  uint16_t* insField);
2358 
2373  uint8_t *packet,
2374  uint16_t* asyncMode,
2375  uint16_t* rateDivisor,
2376  uint16_t* outputGroup,
2377  uint16_t* commonField,
2378  uint16_t* timeField,
2379  uint16_t* imuField,
2380  uint16_t* gpsField,
2381  uint16_t* attitudeField,
2382  uint16_t* insField);
2383 
2389 void VnUartPacket_parseUserTag(VnUartPacket *packet, char* tag);
2390 
2396 void VnUartPacket_parseUserTagRaw(char *packet, char* tag);
2397 
2403 void VnUartPacket_parseModelNumber(VnUartPacket *packet, char* productName);
2404 
2410 void VnUartPacket_parseModelNumberRaw(char *packet, char* productName);
2411 
2417 void VnUartPacket_parseHardwareRevision(VnUartPacket *packet, uint32_t* revision);
2418 
2424 void VnUartPacket_parseHardwareRevisionRaw(char *packet, uint32_t* revision);
2425 
2431 void VnUartPacket_parseSerialNumber(VnUartPacket *packet, uint32_t* serialNum);
2432 
2438 void VnUartPacket_parseSerialNumberRaw(char *packet, uint32_t* serialNum);
2439 
2445 void VnUartPacket_parseFirmwareVersion(VnUartPacket *packet, char* firmwareVersion);
2446 
2452 void VnUartPacket_parseFirmwareVersionRaw(char *packet, char* firmwareVersion);
2453 
2459 void VnUartPacket_parseSerialBaudRate(VnUartPacket *packet, uint32_t* baudrate);
2460 
2466 void VnUartPacket_parseSerialBaudRateRaw(char *packet, uint32_t* baudrate);
2467 
2473 void VnUartPacket_parseAsyncDataOutputType(VnUartPacket *packet, uint32_t* ador);
2474 
2480 void VnUartPacket_parseAsyncDataOutputTypeRaw(char *packet, uint32_t* ador);
2481 
2487 void VnUartPacket_parseAsyncDataOutputFrequency(VnUartPacket *packet, uint32_t* adof);
2488 
2494 void VnUartPacket_parseAsyncDataOutputFrequencyRaw(char *packet, uint32_t* adof);
2495 
2501 void VnUartPacket_parseYawPitchRoll(VnUartPacket *packet, vec3f* yawPitchRoll);
2502 
2508 void VnUartPacket_parseYawPitchRollRaw(char *packet, vec3f* yawPitchRoll);
2509 
2516 
2522 void VnUartPacket_parseAttitudeQuaternionRaw(char *packet, vec4f* quat);
2523 
2533 
2542 void VnUartPacket_parseQuaternionMagneticAccelerationAndAngularRatesRaw(char *packet, vec4f* quat, vec3f* mag, vec3f* accel, vec3f* gyro);
2543 
2550 
2556 void VnUartPacket_parseMagneticMeasurementsRaw(char *packet, vec3f* mag);
2557 
2564 
2570 void VnUartPacket_parseAccelerationMeasurementsRaw(char *packet, vec3f* accel);
2571 
2578 
2584 void VnUartPacket_parseAngularRateMeasurementsRaw(char *packet, vec3f* gyro);
2585 
2594 
2602 void VnUartPacket_parseMagneticAccelerationAndAngularRatesRaw(char *packet, vec3f* mag, vec3f* accel, vec3f* gyro);
2603 
2611 
2618 void VnUartPacket_parseMagneticAndGravityReferenceVectorsRaw(char *packet, vec3f* magRef, vec3f* accRef);
2619 
2628 void VnUartPacket_parseFilterMeasurementsVarianceParameters(VnUartPacket *packet, float* angularWalkVariance, vec3f* angularRateVariance, vec3f* magneticVariance, vec3f* accelerationVariance);
2629 
2638 void VnUartPacket_parseFilterMeasurementsVarianceParametersRaw(char *packet, float* angularWalkVariance, vec3f* angularRateVariance, vec3f* magneticVariance, vec3f* accelerationVariance);
2639 
2647 
2654 void VnUartPacket_parseMagnetometerCompensationRaw(char *packet, mat3f* c, vec3f* b);
2655 
2664 void VnUartPacket_parseFilterActiveTuningParameters(VnUartPacket *packet, float* magneticDisturbanceGain, float* accelerationDisturbanceGain, float* magneticDisturbanceMemory, float* accelerationDisturbanceMemory);
2665 
2674 void VnUartPacket_parseFilterActiveTuningParametersRaw(char *packet, float* magneticDisturbanceGain, float* accelerationDisturbanceGain, float* magneticDisturbanceMemory, float* accelerationDisturbanceMemory);
2675 
2683 
2690 void VnUartPacket_parseAccelerationCompensationRaw(char *packet, mat3f* c, vec3f* b);
2691 
2698 
2704 void VnUartPacket_parseReferenceFrameRotationRaw(char *packet, mat3f* c);
2705 
2715 
2724 void VnUartPacket_parseYawPitchRollMagneticAccelerationAndAngularRatesRaw(char *packet, vec3f* yawPitchRoll, vec3f* mag, vec3f* accel, vec3f* gyro);
2725 
2737 void VnUartPacket_parseCommunicationProtocolControl(VnUartPacket *packet, uint8_t* serialCount, uint8_t* serialStatus, uint8_t* spiCount, uint8_t* spiStatus, uint8_t* serialChecksum, uint8_t* spiChecksum, uint8_t* errorMode);
2738 
2750 void VnUartPacket_parseCommunicationProtocolControlRaw(char *packet, uint8_t* serialCount, uint8_t* serialStatus, uint8_t* spiCount, uint8_t* spiStatus, uint8_t* serialChecksum, uint8_t* spiChecksum, uint8_t* errorMode);
2751 
2765 void VnUartPacket_parseSynchronizationControl(VnUartPacket *packet, uint8_t* syncInMode, uint8_t* syncInEdge, uint16_t* syncInSkipFactor, uint32_t* reserved1, uint8_t* syncOutMode, uint8_t* syncOutPolarity, uint16_t* syncOutSkipFactor, uint32_t* syncOutPulseWidth, uint32_t* reserved2);
2766 
2780 void VnUartPacket_parseSynchronizationControlRaw(char *packet, uint8_t* syncInMode, uint8_t* syncInEdge, uint16_t* syncInSkipFactor, uint32_t* reserved1, uint8_t* syncOutMode, uint8_t* syncOutPolarity, uint16_t* syncOutSkipFactor, uint32_t* syncOutPulseWidth, uint32_t* reserved2);
2781 
2789 void VnUartPacket_parseSynchronizationStatus(VnUartPacket *packet, uint32_t* syncInCount, uint32_t* syncInTime, uint32_t* syncOutCount);
2790 
2798 void VnUartPacket_parseSynchronizationStatusRaw(char *packet, uint32_t* syncInCount, uint32_t* syncInTime, uint32_t* syncOutCount);
2799 
2809 void VnUartPacket_parseFilterBasicControl(VnUartPacket *packet, uint8_t* magMode, uint8_t* extMagMode, uint8_t* extAccMode, uint8_t* extGyroMode, vec3f* gyroLimit);
2810 
2820 void VnUartPacket_parseFilterBasicControlRaw(char *packet, uint8_t* magMode, uint8_t* extMagMode, uint8_t* extAccMode, uint8_t* extGyroMode, vec3f* gyroLimit);
2821 
2830 void VnUartPacket_parseVpeBasicControl(VnUartPacket *packet, uint8_t* enable, uint8_t* headingMode, uint8_t* filteringMode, uint8_t* tuningMode);
2831 
2840 void VnUartPacket_parseVpeBasicControlRaw(char *packet, uint8_t* enable, uint8_t* headingMode, uint8_t* filteringMode, uint8_t* tuningMode);
2841 
2849 void VnUartPacket_parseVpeMagnetometerBasicTuning(VnUartPacket *packet, vec3f* baseTuning, vec3f* adaptiveTuning, vec3f* adaptiveFiltering);
2850 
2858 void VnUartPacket_parseVpeMagnetometerBasicTuningRaw(char *packet, vec3f* baseTuning, vec3f* adaptiveTuning, vec3f* adaptiveFiltering);
2859 
2869 void VnUartPacket_parseVpeMagnetometerAdvancedTuning(VnUartPacket *packet, vec3f* minFiltering, vec3f* maxFiltering, float* maxAdaptRate, float* disturbanceWindow, float* maxTuning);
2870 
2880 void VnUartPacket_parseVpeMagnetometerAdvancedTuningRaw(char *packet, vec3f* minFiltering, vec3f* maxFiltering, float* maxAdaptRate, float* disturbanceWindow, float* maxTuning);
2881 
2889 void VnUartPacket_parseVpeAccelerometerBasicTuning(VnUartPacket *packet, vec3f* baseTuning, vec3f* adaptiveTuning, vec3f* adaptiveFiltering);
2890 
2898 void VnUartPacket_parseVpeAccelerometerBasicTuningRaw(char *packet, vec3f* baseTuning, vec3f* adaptiveTuning, vec3f* adaptiveFiltering);
2899 
2909 void VnUartPacket_parseVpeAccelerometerAdvancedTuning(VnUartPacket *packet, vec3f* minFiltering, vec3f* maxFiltering, float* maxAdaptRate, float* disturbanceWindow, float* maxTuning);
2910 
2920 void VnUartPacket_parseVpeAccelerometerAdvancedTuningRaw(char *packet, vec3f* minFiltering, vec3f* maxFiltering, float* maxAdaptRate, float* disturbanceWindow, float* maxTuning);
2921 
2929 void VnUartPacket_parseVpeGyroBasicTuning(VnUartPacket *packet, vec3f* angularWalkVariance, vec3f* baseTuning, vec3f* adaptiveTuning);
2930 
2938 void VnUartPacket_parseVpeGyroBasicTuningRaw(char *packet, vec3f* angularWalkVariance, vec3f* baseTuning, vec3f* adaptiveTuning);
2939 
2946 
2952 void VnUartPacket_parseFilterStartupGyroBiasRaw(char *packet, vec3f* bias);
2953 
2961 void VnUartPacket_parseMagnetometerCalibrationControl(VnUartPacket *packet, uint8_t* hsiMode, uint8_t* hsiOutput, uint8_t* convergeRate);
2962 
2970 void VnUartPacket_parseMagnetometerCalibrationControlRaw(char *packet, uint8_t* hsiMode, uint8_t* hsiOutput, uint8_t* convergeRate);
2971 
2979 
2987 
2994 void VnUartPacket_parseIndoorHeadingModeControl(VnUartPacket *packet, float* maxRateError, uint8_t* reserved1);
2995 
3002 void VnUartPacket_parseIndoorHeadingModeControlRaw(char *packet, float* maxRateError, uint8_t* reserved1);
3003 
3010 
3016 void VnUartPacket_parseVelocityCompensationMeasurementRaw(char *packet, vec3f* velocity);
3017 
3025 void VnUartPacket_parseVelocityCompensationControl(VnUartPacket *packet, uint8_t* mode, float* velocityTuning, float* rateTuning);
3026 
3034 void VnUartPacket_parseVelocityCompensationControlRaw(char *packet, uint8_t* mode, float* velocityTuning, float* rateTuning);
3035 
3044 void VnUartPacket_parseVelocityCompensationStatus(VnUartPacket *packet, float* x, float* xDot, vec3f* accelOffset, vec3f* omega);
3045 
3054 void VnUartPacket_parseVelocityCompensationStatusRaw(char *packet, float* x, float* xDot, vec3f* accelOffset, vec3f* omega);
3055 
3065 void VnUartPacket_parseImuMeasurements(VnUartPacket *packet, vec3f* mag, vec3f* accel, vec3f* gyro, float* temp, float* pressure);
3066 
3076 void VnUartPacket_parseImuMeasurementsRaw(char *packet, vec3f* mag, vec3f* accel, vec3f* gyro, float* temp, float* pressure);
3077 
3087 void VnUartPacket_parseGpsConfiguration(VnUartPacket *packet, uint8_t* mode, uint8_t* ppsSource, uint8_t* reserved1, uint8_t* reserved2, uint8_t* reserved3);
3088 
3098 void VnUartPacket_parseGpsConfigurationRaw(char *packet, uint8_t* mode, uint8_t* ppsSource, uint8_t* reserved1, uint8_t* reserved2, uint8_t* reserved3);
3099 
3105 void VnUartPacket_parseGpsAntennaOffset(VnUartPacket *packet, vec3f* position);
3106 
3112 void VnUartPacket_parseGpsAntennaOffsetRaw(char *packet, vec3f* position);
3113 
3127 void VnUartPacket_parseGpsSolutionLla(VnUartPacket *packet, double* time, uint16_t* week, uint8_t* gpsFix, uint8_t* numSats, vec3d* lla, vec3f* nedVel, vec3f* nedAcc, float* speedAcc, float* timeAcc);
3128 
3142 void VnUartPacket_parseGpsSolutionLlaRaw(char *packet, double* time, uint16_t* week, uint8_t* gpsFix, uint8_t* numSats, vec3d* lla, vec3f* nedVel, vec3f* nedAcc, float* speedAcc, float* timeAcc);
3143 
3157 void VnUartPacket_parseGpsSolutionEcef(VnUartPacket *packet, double* tow, uint16_t* week, uint8_t* gpsFix, uint8_t* numSats, vec3d* position, vec3f* velocity, vec3f* posAcc, float* speedAcc, float* timeAcc);
3158 
3172 void VnUartPacket_parseGpsSolutionEcefRaw(char *packet, double* tow, uint16_t* week, uint8_t* gpsFix, uint8_t* numSats, vec3d* position, vec3f* velocity, vec3f* posAcc, float* speedAcc, float* timeAcc);
3173 
3187 void VnUartPacket_parseInsSolutionLla(VnUartPacket *packet, double* time, uint16_t* week, uint16_t* status, vec3f* yawPitchRoll, vec3d* position, vec3f* nedVel, float* attUncertainty, float* posUncertainty, float* velUncertainty);
3188 
3202 void VnUartPacket_parseInsSolutionLlaRaw(char *packet, double* time, uint16_t* week, uint16_t* status, vec3f* yawPitchRoll, vec3d* position, vec3f* nedVel, float* attUncertainty, float* posUncertainty, float* velUncertainty);
3203 
3217 void VnUartPacket_parseInsSolutionEcef(VnUartPacket *packet, double* time, uint16_t* week, uint16_t* status, vec3f* yawPitchRoll, vec3d* position, vec3f* velocity, float* attUncertainty, float* posUncertainty, float* velUncertainty);
3218 
3232 void VnUartPacket_parseInsSolutionEcefRaw(char *packet, double* time, uint16_t* week, uint16_t* status, vec3f* yawPitchRoll, vec3d* position, vec3f* velocity, float* attUncertainty, float* posUncertainty, float* velUncertainty);
3233 
3242 void VnUartPacket_parseInsBasicConfiguration(VnUartPacket *packet, uint8_t* scenario, uint8_t* ahrsAiding, uint8_t* estBaseline, uint8_t* resv2);
3243 
3252 void VnUartPacket_parseInsBasicConfigurationRaw(char *packet, uint8_t* scenario, uint8_t* ahrsAiding, uint8_t* estBaseline, uint8_t* resv2);
3253 
3273 void VnUartPacket_parseInsAdvancedConfiguration(VnUartPacket *packet, uint8_t* useMag, uint8_t* usePres, uint8_t* posAtt, uint8_t* velAtt, uint8_t* velBias, uint8_t* useFoam, uint8_t* gpsCovType, uint8_t* velCount, float* velInit, float* moveOrigin, float* gpsTimeout, float* deltaLimitPos, float* deltaLimitVel, float* minPosUncertainty, float* minVelUncertainty);
3274 
3294 void VnUartPacket_parseInsAdvancedConfigurationRaw(char *packet, uint8_t* useMag, uint8_t* usePres, uint8_t* posAtt, uint8_t* velAtt, uint8_t* velBias, uint8_t* useFoam, uint8_t* gpsCovType, uint8_t* velCount, float* velInit, float* moveOrigin, float* gpsTimeout, float* deltaLimitPos, float* deltaLimitVel, float* minPosUncertainty, float* minVelUncertainty);
3295 
3305 void VnUartPacket_parseInsStateLla(VnUartPacket *packet, vec3f* yawPitchRoll, vec3d* position, vec3f* velocity, vec3f* accel, vec3f* angularRate);
3306 
3316 void VnUartPacket_parseInsStateLlaRaw(char *packet, vec3f* yawPitchRoll, vec3d* position, vec3f* velocity, vec3f* accel, vec3f* angularRate);
3317 
3327 void VnUartPacket_parseInsStateEcef(VnUartPacket *packet, vec3f* yawPitchRoll, vec3d* position, vec3f* velocity, vec3f* accel, vec3f* angularRate);
3328 
3338 void VnUartPacket_parseInsStateEcefRaw(char *packet, vec3f* yawPitchRoll, vec3d* position, vec3f* velocity, vec3f* accel, vec3f* angularRate);
3339 
3347 void VnUartPacket_parseStartupFilterBiasEstimate(VnUartPacket *packet, vec3f* gyroBias, vec3f* accelBias, float* pressureBias);
3348 
3356 void VnUartPacket_parseStartupFilterBiasEstimateRaw(char *packet, vec3f* gyroBias, vec3f* accelBias, float* pressureBias);
3357 
3365 void VnUartPacket_parseDeltaThetaAndDeltaVelocity(VnUartPacket *packet, float* deltaTime, vec3f* deltaTheta, vec3f* deltaVelocity);
3366 
3374 void VnUartPacket_parseDeltaThetaAndDeltaVelocityRaw(char *packet, float* deltaTime, vec3f* deltaTheta, vec3f* deltaVelocity);
3375 
3385 void VnUartPacket_parseDeltaThetaAndDeltaVelocityConfiguration(VnUartPacket *packet, uint8_t* integrationFrame, uint8_t* gyroCompensation, uint8_t* accelCompensation, uint8_t* reserved1, uint16_t* reserved2);
3386 
3396 void VnUartPacket_parseDeltaThetaAndDeltaVelocityConfigurationRaw(char *packet, uint8_t* integrationFrame, uint8_t* gyroCompensation, uint8_t* accelCompensation, uint8_t* reserved1, uint16_t* reserved2);
3397 
3409 void VnUartPacket_parseReferenceVectorConfiguration(VnUartPacket *packet, uint8_t* useMagModel, uint8_t* useGravityModel, uint8_t* resv1, uint8_t* resv2, uint32_t* recalcThreshold, float* year, vec3d* position);
3410 
3422 void VnUartPacket_parseReferenceVectorConfigurationRaw(char *packet, uint8_t* useMagModel, uint8_t* useGravityModel, uint8_t* resv1, uint8_t* resv2, uint32_t* recalcThreshold, float* year, vec3d* position);
3423 
3431 
3438 void VnUartPacket_parseGyroCompensationRaw(char *packet, mat3f* c, vec3f* b);
3439 
3454 void VnUartPacket_parseImuFilteringConfiguration(VnUartPacket *packet, uint16_t* magWindowSize, uint16_t* accelWindowSize, uint16_t* gyroWindowSize, uint16_t* tempWindowSize, uint16_t* presWindowSize, uint8_t* magFilterMode, uint8_t* accelFilterMode, uint8_t* gyroFilterMode, uint8_t* tempFilterMode, uint8_t* presFilterMode);
3455 
3470 void VnUartPacket_parseImuFilteringConfigurationRaw(char *packet, uint16_t* magWindowSize, uint16_t* accelWindowSize, uint16_t* gyroWindowSize, uint16_t* tempWindowSize, uint16_t* presWindowSize, uint8_t* magFilterMode, uint8_t* accelFilterMode, uint8_t* gyroFilterMode, uint8_t* tempFilterMode, uint8_t* presFilterMode);
3471 
3478 void VnUartPacket_parseGpsCompassBaseline(VnUartPacket *packet, vec3f* position, vec3f* uncertainty);
3479 
3486 void VnUartPacket_parseGpsCompassBaselineRaw(char *packet, vec3f* position, vec3f* uncertainty);
3487 
3497 void VnUartPacket_parseGpsCompassEstimatedBaseline(VnUartPacket *packet, uint8_t* estBaselineUsed, uint8_t* resv, uint16_t* numMeas, vec3f* position, vec3f* uncertainty);
3498 
3508 void VnUartPacket_parseGpsCompassEstimatedBaselineRaw(char *packet, uint8_t* estBaselineUsed, uint8_t* resv, uint16_t* numMeas, vec3f* position, vec3f* uncertainty);
3509 
3518 void VnUartPacket_parseImuRateConfiguration(VnUartPacket *packet, uint16_t* imuRate, uint16_t* navDivisor, float* filterTargetRate, float* filterMinRate);
3519 
3528 void VnUartPacket_parseImuRateConfigurationRaw(char *packet, uint16_t* imuRate, uint16_t* navDivisor, float* filterTargetRate, float* filterMinRate);
3529 
3538 
3546 void VnUartPacket_parseYawPitchRollTrueBodyAccelerationAndAngularRatesRaw(char *packet, vec3f* yawPitchRoll, vec3f* bodyAccel, vec3f* gyro);
3547 
3555 void VnUartPacket_parseYawPitchRollTrueInertialAccelerationAndAngularRates(VnUartPacket *packet, vec3f* yawPitchRoll, vec3f* inertialAccel, vec3f* gyro);
3556 
3564 void VnUartPacket_parseYawPitchRollTrueInertialAccelerationAndAngularRatesRaw(char *packet, vec3f* yawPitchRoll, vec3f* inertialAccel, vec3f* gyro);
3565 
3573 void strFromVnAsciiAsync(char *out, VnAsciiAsync val);
3574 
3575 #ifdef __cplusplus
3576 }
3577 #endif
3578 
3579 #endif
VnError VnUartPacket_genReadMagneticAccelerationAndAngularRates(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Magnetic, Acceleration and Angular Rates register on a VectorNav sens...
void VnUartPacket_parseSynchronizationControlRaw(char *packet, uint8_t *syncInMode, uint8_t *syncInEdge, uint16_t *syncInSkipFactor, uint32_t *reserved1, uint8_t *syncOutMode, uint8_t *syncOutPolarity, uint16_t *syncOutSkipFactor, uint32_t *syncOutPulseWidth, uint32_t *reserved2)
Parses a response from reading the Synchronization Control register.
void VnUartPacket_parseAsyncDataOutputType(VnUartPacket *packet, uint32_t *ador)
Parses a response from reading the Async Data Output Type register.
VnError VnUartPacket_genWriteVpeAccelerometerBasicTuning(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, vec3f baseTuning, vec3f adaptiveTuning, vec3f adaptiveFiltering)
Generates a command to write to the VPE Accelerometer Basic Tuning register on a VectorNav sensor...
void VnUartPacket_parseGpsConfiguration(VnUartPacket *packet, uint8_t *mode, uint8_t *ppsSource, uint8_t *reserved1, uint8_t *reserved2, uint8_t *reserved3)
Parses a response from reading the GPS Configuration register.
void VnUartPacket_parseInsBasicConfigurationRaw(char *packet, uint8_t *scenario, uint8_t *ahrsAiding, uint8_t *estBaseline, uint8_t *resv2)
Parses a response from reading the INS Basic Configuration register.
void VnUartPacket_parseIndoorHeadingModeControl(VnUartPacket *packet, float *maxRateError, uint8_t *reserved1)
Parses a response from reading the Indoor Heading Mode Control register.
void VnUartPacket_parseVelocityCompensationStatus(VnUartPacket *packet, float *x, float *xDot, vec3f *accelOffset, vec3f *omega)
Parses a response from reading the Velocity Compensation Status register.
VnError VnUartPacket_genWriteDeltaThetaAndDeltaVelocityConfiguration(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, uint8_t integrationFrame, uint8_t gyroCompensation, uint8_t accelCompensation, uint8_t reserved1, uint16_t reserved2)
Generates a command to write to the Delta Theta and Delta Velocity Configuration register on a Vector...
VnError VnUartPacket_genReadAccelerationMeasurements(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Acceleration Measurements register on a VectorNav sensor...
VnError VnUartPacket_genCmdTare(uint8_t *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to tare the sensor.
void VnUartPacket_parseAccelerationCompensation(VnUartPacket *packet, mat3f *c, vec3f *b)
Parses a response from reading the Acceleration Compensation register.
void VnUartPacket_parseFilterBasicControlRaw(char *packet, uint8_t *magMode, uint8_t *extMagMode, uint8_t *extAccMode, uint8_t *extGyroMode, vec3f *gyroLimit)
Parses a response from reading the Filter Basic Control register.
VnError VnUartPacket_genWriteSerialBaudRate(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, uint32_t baudrate)
Generates a command to write to the Serial Baud Rate register on a VectorNav sensor.
void VnUartPacket_parseReferenceVectorConfigurationRaw(char *packet, uint8_t *useMagModel, uint8_t *useGravityModel, uint8_t *resv1, uint8_t *resv2, uint32_t *recalcThreshold, float *year, vec3d *position)
Parses a response from reading the Reference Vector Configuration register.
VnError VnUartPacket_genWriteMagnetometerCalibrationControl(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, uint8_t hsiMode, uint8_t hsiOutput, uint8_t convergeRate)
Generates a command to write to the Magnetometer Calibration Control register on a VectorNav sensor...
VnError VnUartPacket_parseVNYMR(VnUartPacket *packet, vec3f *yawPitchRoll, vec3f *magnetic, vec3f *acceleration, vec3f *angularRate)
Parses a VNYMR asynchronous packet.
void VnUartPacket_parseCommunicationProtocolControlRaw(char *packet, uint8_t *serialCount, uint8_t *serialStatus, uint8_t *spiCount, uint8_t *spiStatus, uint8_t *serialChecksum, uint8_t *spiChecksum, uint8_t *errorMode)
Parses a response from reading the Communication Protocol Control register.
void VnUartPacket_parseVNGYR(VnUartPacket *packet, vec3f *angularRate)
Parses a VNGYR asynchronous packet.
void VnUartPacket_parseUserTagRaw(char *packet, char *tag)
Parses a response from reading the User Tag register.
VnError VnUartPacket_genReadInsSolutionLla(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the INS Solution - LLA register on a VectorNav sensor.
void VnUartPacket_parseGpsAntennaOffsetRaw(char *packet, vec3f *position)
Parses a response from reading the GPS Antenna Offset register.
VnError VnUartPacket_genWriteSerialBaudRateWithOptions(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, uint32_t baudrate)
Generates a command to write to the Serial Baud Rate register on a VectorNav sensor.
VnError VnUartPacket_genReadBinaryOutput2(uint8_t *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Binary Output 2 register on a VectorNav sensor.
void VnUartPacket_parseErrorRaw(uint8_t *packet, uint8_t *error)
Parses an error packet to get the error type.
void VnUartPacket_parseInsStateLla(VnUartPacket *packet, vec3f *yawPitchRoll, vec3d *position, vec3f *velocity, vec3f *accel, vec3f *angularRate)
Parses a response from reading the INS State - LLA register.
VnError VnUartPacket_genWriteAsyncDataOutputType(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, uint32_t ador)
Generates a command to write to the Async Data Output Type register on a VectorNav sensor...
void VnUartPacket_parseDeltaThetaAndDeltaVelocity(VnUartPacket *packet, float *deltaTime, vec3f *deltaTheta, vec3f *deltaVelocity)
Parses a response from reading the Delta Theta and Delta Velocity register.
VnError VnUartPacket_genWriteSynchronizationStatus(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, uint32_t syncInCount, uint32_t syncInTime, uint32_t syncOutCount)
Generates a command to write to the Synchronization Status register on a VectorNav sensor...
void VnUartPacket_parseGpsConfigurationRaw(char *packet, uint8_t *mode, uint8_t *ppsSource, uint8_t *reserved1, uint8_t *reserved2, uint8_t *reserved3)
Parses a response from reading the GPS Configuration register.
void VnUartPacket_parseImuMeasurementsRaw(char *packet, vec3f *mag, vec3f *accel, vec3f *gyro, float *temp, float *pressure)
Parses a response from reading the IMU Measurements register.
mat3f VnUartPacket_extractMat3f(VnUartPacket *packet)
Extracts a mat3f data type from a binary packet and advances the next extraction point appropriately...
VnError VnUartPacket_genWriteSynchronizationControl(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, uint8_t syncInMode, uint8_t syncInEdge, uint16_t syncInSkipFactor, uint32_t reserved1, uint8_t syncOutMode, uint8_t syncOutPolarity, uint16_t syncOutSkipFactor, uint32_t syncOutPulseWidth, uint32_t reserved2)
Generates a command to write to the Synchronization Control register on a VectorNav sensor...
Structure representing a UART packet received from a VectorNav sensor.
Definition: upack.h:34
VnError VnUartPacket_genReadImuFilteringConfiguration(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the IMU Filtering Configuration register on a VectorNav sensor...
VnError VnUartPacket_genReadReferenceFrameRotation(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Reference Frame Rotation register on a VectorNav sensor.
VnError VnUartPacket_genWriteInsBasicConfiguration(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, uint8_t scenario, uint8_t ahrsAiding, uint8_t estBaseline, uint8_t resv2)
Generates a command to write to the INS Basic Configuration register on a VectorNav sensor...
void VnUartPacket_parseVpeGyroBasicTuning(VnUartPacket *packet, vec3f *angularWalkVariance, vec3f *baseTuning, vec3f *adaptiveTuning)
Parses a response from reading the VPE Gyro Basic Tuning register.
void VnUartPacket_parseQuaternionMagneticAccelerationAndAngularRatesRaw(char *packet, vec4f *quat, vec3f *mag, vec3f *accel, vec3f *gyro)
Parses a response from reading the Quaternion, Magnetic, Acceleration and Angular Rates register...
VnError VnUartPacket_genReadAsyncDataOutputFrequency(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Async Data Output Frequency register on a VectorNav sensor...
void VnUartPacket_parseInsBasicConfiguration(VnUartPacket *packet, uint8_t *scenario, uint8_t *ahrsAiding, uint8_t *estBaseline, uint8_t *resv2)
Parses a response from reading the INS Basic Configuration register.
VnError VnUartPacket_genReadBinaryOutput3(uint8_t *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Binary Output 3 register on a VectorNav sensor.
void VnUartPacket_parseMagneticMeasurementsRaw(char *packet, vec3f *mag)
Parses a response from reading the Magnetic Measurements register.
VnError VnUartPacket_genReadDeltaThetaAndDeltaVelocityConfiguration(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Delta Theta and Delta Velocity Configuration register on a VectorNav ...
void VnUartPacket_parseMagneticAccelerationAndAngularRates(VnUartPacket *packet, vec3f *mag, vec3f *accel, vec3f *gyro)
Parses a response from reading the Magnetic, Acceleration and Angular Rates register.
void VnUartPacket_parseMagnetometerCalibrationControl(VnUartPacket *packet, uint8_t *hsiMode, uint8_t *hsiOutput, uint8_t *convergeRate)
Parses a response from reading the Magnetometer Calibration Control register.
VnError VnUartPacket_genReadAsyncDataOutputType(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Async Data Output Type register on a VectorNav sensor.
void VnUartPacket_parseVpeMagnetometerAdvancedTuning(VnUartPacket *packet, vec3f *minFiltering, vec3f *maxFiltering, float *maxAdaptRate, float *disturbanceWindow, float *maxTuning)
Parses a response from reading the VPE Magnetometer Advanced Tuning register.
VnError VnUartPacket_genWriteAsyncDataOutputFrequency(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, uint32_t adof)
Generates a command to write to the Async Data Output Frequency register on a VectorNav sensor...
VnError VnUartPacket_genReadGyroCompensation(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Gyro Compensation register on a VectorNav sensor. ...
void VnUartPacket_parseVpeBasicControlRaw(char *packet, uint8_t *enable, uint8_t *headingMode, uint8_t *filteringMode, uint8_t *tuningMode)
Parses a response from reading the VPE Basic Control register.
VnError VnUartPacket_genWriteGpsConfiguration(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, uint8_t mode, uint8_t ppsSource, uint8_t reserved1, uint8_t reserved2, uint8_t reserved3)
Generates a command to write to the GPS Configuration register on a VectorNav sensor.
VnError VnUartPacket_genReadInsSolutionEcef(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the INS Solution - ECEF register on a VectorNav sensor.
VnError VnUartPacket_genWriteVelocityCompensationMeasurement(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, vec3f velocity)
Generates a command to write to the Velocity Compensation Measurement register on a VectorNav sensor...
VnError VnUartPacket_genReadGpsCompassBaseline(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the GPS Compass Baseline register on a VectorNav sensor.
void VnUartPacket_parseAccelerationCompensationRaw(char *packet, mat3f *c, vec3f *b)
Parses a response from reading the Acceleration Compensation register.
void VnUartPacket_parseSerialBaudRateRaw(char *packet, uint32_t *baudrate)
Parses a response from reading the Serial Baud Rate register.
void VnUartPacket_parseCalculatedMagnetometerCalibration(VnUartPacket *packet, mat3f *c, vec3f *b)
Parses a response from reading the Calculated Magnetometer Calibration register.
void VnUartPacket_parseVelocityCompensationMeasurement(VnUartPacket *packet, vec3f *velocity)
Parses a response from reading the Velocity Compensation Measurement register.
void VnUartPacket_parseBinaryOutput(VnUartPacket *packet, uint16_t *asyncMode, uint16_t *rateDivisor, uint16_t *outputGroup, uint16_t *commonField, uint16_t *timeField, uint16_t *imuField, uint16_t *gpsField, uint16_t *attitudeField, uint16_t *insField)
Parses a response from reading any of the Binary Output registers.
void VnUartPacket_parseReferenceFrameRotation(VnUartPacket *packet, mat3f *c)
Parses a response from reading the Reference Frame Rotation register.
void VnUartPacket_parseFilterMeasurementsVarianceParametersRaw(char *packet, float *angularWalkVariance, vec3f *angularRateVariance, vec3f *magneticVariance, vec3f *accelerationVariance)
Parses a response from reading the Filter Measurements Variance Parameters register.
void VnUartPacket_parseVNMAR(VnUartPacket *packet, vec3f *magnetic, vec3f *acceleration, vec3f *angularRate)
Parses a VNMAR asynchronous packet.
uint8_t * data
Definition: upack.h:43
void VnUartPacket_parseVNISE(VnUartPacket *packet, vec3f *ypr, vec3d *position, vec3f *velocity, vec3f *acceleration, vec3f *angularRate)
Parse a VNISE asynchronous packet.
void VnUartPacket_parseVNDTV(VnUartPacket *packet, float *deltaTime, vec3f *deltaTheta, vec3f *deltaVelocity)
Parses a VNDTV asynchronous packet.
VnError VnUartPacket_genReadAngularRateMeasurements(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Angular Rate Measurements register on a VectorNav sensor...
void VnUartPacket_parseAngularRateMeasurementsRaw(char *packet, vec3f *gyro)
Parses a response from reading the Angular Rate Measurements register.
void VnUartPacket_parseUserTag(VnUartPacket *packet, char *tag)
Parses a response from reading the User Tag register.
void VnUartPacket_parseGyroCompensation(VnUartPacket *packet, mat3f *c, vec3f *b)
Parses a response from reading the Gyro Compensation register.
VnError VnUartPacket_genReadStartupFilterBiasEstimate(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Startup Filter Bias Estimate register on a VectorNav sensor...
void VnUartPacket_parseImuFilteringConfigurationRaw(char *packet, uint16_t *magWindowSize, uint16_t *accelWindowSize, uint16_t *gyroWindowSize, uint16_t *tempWindowSize, uint16_t *presWindowSize, uint8_t *magFilterMode, uint8_t *accelFilterMode, uint8_t *gyroFilterMode, uint8_t *tempFilterMode, uint8_t *presFilterMode)
Parses a response from reading the IMU Filtering Configuration register.
void VnUartPacket_parseQuaternionMagneticAccelerationAndAngularRates(VnUartPacket *packet, vec4f *quat, vec3f *mag, vec3f *accel, vec3f *gyro)
Parses a response from reading the Quaternion, Magnetic, Acceleration and Angular Rates register...
void VnUartPacket_parseSerialNumber(VnUartPacket *packet, uint32_t *serialNum)
Parses a response from reading the Serial Number register.
VnError VnUartPacket_genReadYawPitchRoll(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Yaw Pitch Roll register on a VectorNav sensor.
void VnUartPacket_parseHardwareRevisionRaw(char *packet, uint32_t *revision)
Parses a response from reading the Hardware Revision register.
VnError VnUartPacket_genWriteMagnetometerCompensation(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, mat3f c, vec3f b)
Generates a command to write to the Magnetometer Compensation register on a VectorNav sensor...
VnError VnUartPacket_genCmdWriteSettings(uint8_t *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to write sensor settings to non-volitile memory.
VnError VnUartPacket_genReadInsStateEcef(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the INS State - ECEF register on a VectorNav sensor.
VnError VnUartPacket_genReadMagneticMeasurements(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Magnetic Measurements register on a VectorNav sensor.
void VnUartPacket_parseVNGPS(VnUartPacket *packet, double *time, uint16_t *week, uint8_t *gpsFix, uint8_t *numSats, vec3d *lla, vec3f *nedVel, vec3f *nedAcc, float *speedAcc, float *timeAcc)
Parses a VNGPS asynchronous packet.
void VnUartPacket_parseSynchronizationStatusRaw(char *packet, uint32_t *syncInCount, uint32_t *syncInTime, uint32_t *syncOutCount)
Parses a response from reading the Synchronization Status register.
VnError VnUartPacket_genReadVelocityCompensationControl(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Velocity Compensation Control register on a VectorNav sensor...
void VnUartPacket_parseVpeBasicControl(VnUartPacket *packet, uint8_t *enable, uint8_t *headingMode, uint8_t *filteringMode, uint8_t *tuningMode)
Parses a response from reading the VPE Basic Control register.
void VnUartPacket_parseSerialBaudRate(VnUartPacket *packet, uint32_t *baudrate)
Parses a response from reading the Serial Baud Rate register.
void VnUartPacket_parseAngularRateMeasurements(VnUartPacket *packet, vec3f *gyro)
Parses a response from reading the Angular Rate Measurements register.
void VnUartPacket_parseFilterActiveTuningParameters(VnUartPacket *packet, float *magneticDisturbanceGain, float *accelerationDisturbanceGain, float *magneticDisturbanceMemory, float *accelerationDisturbanceMemory)
Parses a response from reading the Filter Active Tuning Parameters register.
VnError VnUartPacket_genWriteVpeBasicControl(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, uint8_t enable, uint8_t headingMode, uint8_t filteringMode, uint8_t tuningMode)
Generates a command to write to the VPE Basic Control register on a VectorNav sensor.
void VnUartPacket_parseAsyncDataOutputFrequencyRaw(char *packet, uint32_t *adof)
Parses a response from reading the Async Data Output Frequency register.
void VnUartPacket_parseFilterStartupGyroBiasRaw(char *packet, vec3f *bias)
Parses a response from reading the Filter Startup Gyro Bias register.
void VnUartPacket_parseVNGPE(VnUartPacket *packet, double *tow, uint16_t *week, uint8_t *gpsFix, uint8_t *numSats, vec3d *position, vec3f *velocity, vec3f *posAcc, float *speedAcc, float *timeAcc)
Parses a VNGPE asynchronous packet.
VnError VnUartPacket_genReadGpsAntennaOffset(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the GPS Antenna Offset register on a VectorNav sensor.
void VnUartPacket_parseVpeAccelerometerBasicTuningRaw(char *packet, vec3f *baseTuning, vec3f *adaptiveTuning, vec3f *adaptiveFiltering)
Parses a response from reading the VPE Accelerometer Basic Tuning register.
VnError VnUartPacket_genWriteVelocityCompensationControl(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, uint8_t mode, float velocityTuning, float rateTuning)
Generates a command to write to the Velocity Compensation Control register on a VectorNav sensor...
int8_t VnUartPacket_extractInt8(VnUartPacket *packet)
Extracts a int8_t data type from a binary packet and advances the next extraction point appropriately...
void VnUartPacket_parseVpeAccelerometerAdvancedTuning(VnUartPacket *packet, vec3f *minFiltering, vec3f *maxFiltering, float *maxAdaptRate, float *disturbanceWindow, float *maxTuning)
Parses a response from reading the VPE Accelerometer Advanced Tuning register.
void VnUartPacket_parseAttitudeQuaternion(VnUartPacket *packet, vec4f *quat)
Parses a response from reading the Attitude Quaternion register.
void VnUartPacket_parseVNINE(VnUartPacket *packet, double *time, uint16_t *week, uint16_t *status, vec3f *yawPitchRoll, vec3d *position, vec3f *velocity, float *attUncertainty, float *posUncertainty, float *velUncertainty)
Parses a VNINE asynchronous packet.
void VnUartPacket_parseGpsCompassBaseline(VnUartPacket *packet, vec3f *position, vec3f *uncertainty)
Parses a response from reading the GPS Compass Baseline register.
void VnUartPacket_parseFilterStartupGyroBias(VnUartPacket *packet, vec3f *bias)
Parses a response from reading the Filter Startup Gyro Bias register.
VnError VnUartPacket_genWriteAsyncDataOutputTypeWithOptions(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, uint32_t ador)
Generates a command to write to the Async Data Output Type register on a VectorNav sensor...
void VnUartPacket_parseFilterActiveTuningParametersRaw(char *packet, float *magneticDisturbanceGain, float *accelerationDisturbanceGain, float *magneticDisturbanceMemory, float *accelerationDisturbanceMemory)
Parses a response from reading the Filter Active Tuning Parameters register.
VnError VnUartPacket_genWriteReferenceVectorConfiguration(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, uint8_t useMagModel, uint8_t useGravityModel, uint8_t resv1, uint8_t resv2, uint32_t recalcThreshold, float year, vec3d position)
Generates a command to write to the Reference Vector Configuration register on a VectorNav sensor...
void VnUartPacket_parseMagneticAndGravityReferenceVectorsRaw(char *packet, vec3f *magRef, vec3f *accRef)
Parses a response from reading the Magnetic and Gravity Reference Vectors register.
void VnUartPacket_parseVelocityCompensationControl(VnUartPacket *packet, uint8_t *mode, float *velocityTuning, float *rateTuning)
Parses a response from reading the Velocity Compensation Control register.
void VnUartPacket_parseInsSolutionEcef(VnUartPacket *packet, double *time, uint16_t *week, uint16_t *status, vec3f *yawPitchRoll, vec3d *position, vec3f *velocity, float *attUncertainty, float *posUncertainty, float *velUncertainty)
Parses a response from reading the INS Solution - ECEF register.
VnError VnUartPacket_genWriteUserTag(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, char *tag)
Generates a command to write to the User Tag register on a VectorNav sensor.
uint32_t VnUartPacket_extractUint32(VnUartPacket *packet)
Extracts a uint32_t data type from a binary packet and advances the next extraction point appropriate...
void VnUartPacket_parseGpsSolutionEcefRaw(char *packet, double *tow, uint16_t *week, uint8_t *gpsFix, uint8_t *numSats, vec3d *position, vec3f *velocity, vec3f *posAcc, float *speedAcc, float *timeAcc)
Parses a response from reading the GPS Solution - ECEF register.
void VnUartPacket_parseSynchronizationStatus(VnUartPacket *packet, uint32_t *syncInCount, uint32_t *syncInTime, uint32_t *syncOutCount)
Parses a response from reading the Synchronization Status register.
VnError VnUartPacket_genWriteAsyncDataOutputFrequencyWithOptions(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, uint32_t adof)
Generates a command to write to the Async Data Output Frequency register on a VectorNav sensor...
void VnUartPacket_parseAsyncDataOutputTypeRaw(char *packet, uint32_t *ador)
Parses a response from reading the Async Data Output Type register.
Represents a 4 component vector with an underlying data type of float.
Definition: vector.h:68
Represents a 3 component vector with an underlying data type of double.
Definition: vector.h:41
void VnUartPacket_parseVNYIA(VnUartPacket *packet, vec3f *yawPitchRoll, vec3f *accelerationInertial, vec3f *angularRate)
Parses a VNYIA asynchronous packet.
VnError VnUartPacket_genReadMagnetometerCalibrationControl(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Magnetometer Calibration Control register on a VectorNav sensor...
VnError VnUartPacket_genReadAccelerationCompensation(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Acceleration Compensation register on a VectorNav sensor...
VnError VnUartPacket_genReadYawPitchRollTrueBodyAccelerationAndAngularRates(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Yaw, Pitch, Roll, True Body Acceleration and Angular Rates register o...
VnError VnUartPacket_genReadMagnetometerCompensation(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Magnetometer Compensation register on a VectorNav sensor...
void VnUartPacket_parseReferenceVectorConfiguration(VnUartPacket *packet, uint8_t *useMagModel, uint8_t *useGravityModel, uint8_t *resv1, uint8_t *resv2, uint32_t *recalcThreshold, float *year, vec3d *position)
Parses a response from reading the Reference Vector Configuration register.
VnError VnUartPacket_genReadQuaternionMagneticAccelerationAndAngularRates(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Quaternion, Magnetic, Acceleration and Angular Rates register on a Ve...
VnError VnUartPacket_genWriteGpsCompassBaseline(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, vec3f position, vec3f uncertainty)
Generates a command to write to the GPS Compass Baseline register on a VectorNav sensor.
void VnUartPacket_parseInsSolutionLla(VnUartPacket *packet, double *time, uint16_t *week, uint16_t *status, vec3f *yawPitchRoll, vec3d *position, vec3f *nedVel, float *attUncertainty, float *posUncertainty, float *velUncertainty)
Parses a response from reading the INS Solution - LLA register.
VnError VnUartPacket_genWriteMagneticAndGravityReferenceVectors(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, vec3f magRef, vec3f accRef)
Generates a command to write to the Magnetic and Gravity Reference Vectors register on a VectorNav se...
void VnUartPacket_parseYawPitchRollMagneticAccelerationAndAngularRates(VnUartPacket *packet, vec3f *yawPitchRoll, vec3f *mag, vec3f *accel, vec3f *gyro)
Parses a response from reading the Yaw, Pitch, Roll, Magnetic, Acceleration and Angular Rates registe...
VnError VnUartPacket_genReadVpeBasicControl(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the VPE Basic Control register on a VectorNav sensor. ...
void VnUartPacket_parseInsStateLlaRaw(char *packet, vec3f *yawPitchRoll, vec3d *position, vec3f *velocity, vec3f *accel, vec3f *angularRate)
Parses a response from reading the INS State - LLA register.
void VnUartPacket_parseIndoorHeadingModeControlRaw(char *packet, float *maxRateError, uint8_t *reserved1)
Parses a response from reading the Indoor Heading Mode Control register.
void VnUartPacket_parseFilterBasicControl(VnUartPacket *packet, uint8_t *magMode, uint8_t *extMagMode, uint8_t *extAccMode, uint8_t *extGyroMode, vec3f *gyroLimit)
Parses a response from reading the Filter Basic Control register.
vec3f VnUartPacket_extractVec3f(VnUartPacket *packet)
Extracts a vec3f data type from a binary packet and advances the next extraction point appropriately...
VnError VnUartPacket_genReadYawPitchRollMagneticAccelerationAndAngularRates(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Yaw, Pitch, Roll, Magnetic, Acceleration and Angular Rates register o...
void VnUartPacket_parseYawPitchRollMagneticAccelerationAndAngularRatesRaw(char *packet, vec3f *yawPitchRoll, vec3f *mag, vec3f *accel, vec3f *gyro)
Parses a response from reading the Yaw, Pitch, Roll, Magnetic, Acceleration and Angular Rates registe...
VnError VnUartPacket_genReadBinaryOutput1(uint8_t *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Binary Output 1 register on a VectorNav sensor.
void VnUartPacket_parseReferenceFrameRotationRaw(char *packet, mat3f *c)
Parses a response from reading the Reference Frame Rotation register.
VnError VnUartPacket_genReadImuMeasurements(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the IMU Measurements register on a VectorNav sensor.
void VnUartPacket_parseGpsCompassEstimatedBaselineRaw(char *packet, uint8_t *estBaselineUsed, uint8_t *resv, uint16_t *numMeas, vec3f *position, vec3f *uncertainty)
Parses a response from reading the GPS Compass Estimated Baseline register.
void VnUartPacket_parseVelocityCompensationControlRaw(char *packet, uint8_t *mode, float *velocityTuning, float *rateTuning)
Parses a response from reading the Velocity Compensation Control register.
void VnUartPacket_parseYawPitchRollTrueBodyAccelerationAndAngularRates(VnUartPacket *packet, vec3f *yawPitchRoll, vec3f *bodyAccel, vec3f *gyro)
Parses a response from reading the Yaw, Pitch, Roll, True Body Acceleration and Angular Rates registe...
VnError VnUartPacket_genReadVpeAccelerometerBasicTuning(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the VPE Accelerometer Basic Tuning register on a VectorNav sensor...
VnError VnUartPacket_genReadSynchronizationStatus(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Synchronization Status register on a VectorNav sensor.
VnError VnUartPacket_genReadGpsConfiguration(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the GPS Configuration register on a VectorNav sensor. ...
void VnUartPacket_parseVNACC(VnUartPacket *packet, vec3f *acceleration)
Parses a VNACC asynchronous packet.
void VnUartPacket_parseYawPitchRollTrueBodyAccelerationAndAngularRatesRaw(char *packet, vec3f *yawPitchRoll, vec3f *bodyAccel, vec3f *gyro)
Parses a response from reading the Yaw, Pitch, Roll, True Body Acceleration and Angular Rates registe...
void VnUartPacket_parseGpsAntennaOffset(VnUartPacket *packet, vec3f *position)
Parses a response from reading the GPS Antenna Offset register.
void VnUartPacket_parseGpsSolutionLla(VnUartPacket *packet, double *time, uint16_t *week, uint8_t *gpsFix, uint8_t *numSats, vec3d *lla, vec3f *nedVel, vec3f *nedAcc, float *speedAcc, float *timeAcc)
Parses a response from reading the GPS Solution - LLA register.
VnError VnUartPacket_genCmdKnownAccelerationDisturbance(uint8_t *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, bool disturbancePresent, size_t *cmdSize)
Generates a command to alert the sensor of a known acceleration disturbance.
VnError VnUartPacket_genCmdReset(uint8_t *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to reset the sensor.
void VnUartPacket_parseBinaryOutputRaw(uint8_t *packet, uint16_t *asyncMode, uint16_t *rateDivisor, uint16_t *outputGroup, uint16_t *commonField, uint16_t *timeField, uint16_t *imuField, uint16_t *gpsField, uint16_t *attitudeField, uint16_t *insField)
Parses a response from reading any of the Binary Output registers.
void VnUartPacket_parseAsyncDataOutputFrequency(VnUartPacket *packet, uint32_t *adof)
Parses a response from reading the Async Data Output Frequency register.
void VnUartPacket_parseMagneticAccelerationAndAngularRatesRaw(char *packet, vec3f *mag, vec3f *accel, vec3f *gyro)
Parses a response from reading the Magnetic, Acceleration and Angular Rates register.
void VnUartPacket_parseMagnetometerCalibrationControlRaw(char *packet, uint8_t *hsiMode, uint8_t *hsiOutput, uint8_t *convergeRate)
Parses a response from reading the Magnetometer Calibration Control register.
void VnUartPacket_parseSynchronizationControl(VnUartPacket *packet, uint8_t *syncInMode, uint8_t *syncInEdge, uint16_t *syncInSkipFactor, uint32_t *reserved1, uint8_t *syncOutMode, uint8_t *syncOutPolarity, uint16_t *syncOutSkipFactor, uint32_t *syncOutPulseWidth, uint32_t *reserved2)
Parses a response from reading the Synchronization Control register.
VnError VnUartPacket_genWriteBinaryOutput3(uint8_t *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, uint16_t asyncMode, uint16_t rateDivisor, uint16_t commonField, uint16_t timeField, uint16_t imuField, uint16_t gpsField, uint16_t attitudeField, uint16_t insField)
Generates a command to write to the Binary Output 3 register.
vec3d VnUartPacket_extractVec3d(VnUartPacket *packet)
Extracts a vec3d data type from a binary packet and advances the next extraction point appropriately...
VnError VnUartPacket_genWriteVpeMagnetometerBasicTuning(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, vec3f baseTuning, vec3f adaptiveTuning, vec3f adaptiveFiltering)
Generates a command to write to the VPE Magnetometer Basic Tuning register on a VectorNav sensor...
VnError VnUartPacket_genReadSynchronizationControl(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Synchronization Control register on a VectorNav sensor.
void VnUartPacket_parseYawPitchRoll(VnUartPacket *packet, vec3f *yawPitchRoll)
Parses a response from reading the Yaw Pitch Roll register.
VnError VnUartPacket_genReadInsStateLla(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the INS State - LLA register on a VectorNav sensor.
void VnUartPacket_parseYawPitchRollTrueInertialAccelerationAndAngularRates(VnUartPacket *packet, vec3f *yawPitchRoll, vec3f *inertialAccel, vec3f *gyro)
Parses a response from reading the Yaw, Pitch, Roll, True Inertial Acceleration and Angular Rates reg...
void VnUartPacket_parseFirmwareVersionRaw(char *packet, char *firmwareVersion)
Parses a response from reading the Firmware Version register.
VnError VnUartPacket_genWriteBinaryOutput2(uint8_t *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, uint16_t asyncMode, uint16_t rateDivisor, uint16_t commonField, uint16_t timeField, uint16_t imuField, uint16_t gpsField, uint16_t attitudeField, uint16_t insField)
Generates a command to write to the Binary Output 2 register.
void VnUartPacket_parseVpeAccelerometerBasicTuning(VnUartPacket *packet, vec3f *baseTuning, vec3f *adaptiveTuning, vec3f *adaptiveFiltering)
Parses a response from reading the VPE Accelerometer Basic Tuning register.
void VnUartPacket_parseInsSolutionEcefRaw(char *packet, double *time, uint16_t *week, uint16_t *status, vec3f *yawPitchRoll, vec3d *position, vec3f *velocity, float *attUncertainty, float *posUncertainty, float *velUncertainty)
Parses a response from reading the INS Solution - ECEF register.
VnError VnUartPacket_genReadHardwareRevision(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Hardware Revision register on a VectorNav sensor. ...
void VnUartPacket_parseCalculatedMagnetometerCalibrationRaw(char *packet, mat3f *c, vec3f *b)
Parses a response from reading the Calculated Magnetometer Calibration register.
void VnUartPacket_parseInsSolutionLlaRaw(char *packet, double *time, uint16_t *week, uint16_t *status, vec3f *yawPitchRoll, vec3d *position, vec3f *nedVel, float *attUncertainty, float *posUncertainty, float *velUncertainty)
Parses a response from reading the INS Solution - LLA register.
void VnUartPacket_parseInsAdvancedConfiguration(VnUartPacket *packet, uint8_t *useMag, uint8_t *usePres, uint8_t *posAtt, uint8_t *velAtt, uint8_t *velBias, uint8_t *useFoam, uint8_t *gpsCovType, uint8_t *velCount, float *velInit, float *moveOrigin, float *gpsTimeout, float *deltaLimitPos, float *deltaLimitVel, float *minPosUncertainty, float *minVelUncertainty)
Parses a response from reading the INS Advanced Configuration register.
uint8_t VnUartPacket_extractUint8(VnUartPacket *packet)
Extracts a uint8_t data type from a binary packet and advances the next extraction point appropriatel...
VnError VnUartPacket_genReadYawPitchRollTrueInertialAccelerationAndAngularRates(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Yaw, Pitch, Roll, True Inertial Acceleration and Angular Rates regist...
void VnUartPacket_parseVpeMagnetometerBasicTuningRaw(char *packet, vec3f *baseTuning, vec3f *adaptiveTuning, vec3f *adaptiveFiltering)
Parses a response from reading the VPE Magnetometer Basic Tuning register.
VnError VnUartPacket_genReadCommunicationProtocolControl(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Communication Protocol Control register on a VectorNav sensor...
void VnUartPacket_parseImuRateConfiguration(VnUartPacket *packet, uint16_t *imuRate, uint16_t *navDivisor, float *filterTargetRate, float *filterMinRate)
Parses a response from reading the IMU Rate Configuration register.
VnError VnUartPacket_genReadGpsSolutionLla(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the GPS Solution - LLA register on a VectorNav sensor.
void VnUartPacket_parseVNQTN(VnUartPacket *packet, vec4f *quaternion)
Parses a VNQTN asynchronous packet.
void VnUartPacket_parseVelocityCompensationStatusRaw(char *packet, float *x, float *xDot, vec3f *accelOffset, vec3f *omega)
Parses a response from reading the Velocity Compensation Status register.
void VnUartPacket_parseDeltaThetaAndDeltaVelocityConfiguration(VnUartPacket *packet, uint8_t *integrationFrame, uint8_t *gyroCompensation, uint8_t *accelCompensation, uint8_t *reserved1, uint16_t *reserved2)
Parses a response from reading the Delta Theta and Delta Velocity Configuration register.
VnError VnUartPacket_genReadAttitudeQuaternion(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Attitude Quaternion register on a VectorNav sensor.
void VnUartPacket_parseGpsCompassBaselineRaw(char *packet, vec3f *position, vec3f *uncertainty)
Parses a response from reading the GPS Compass Baseline register.
void VnUartPacket_parseInsAdvancedConfigurationRaw(char *packet, uint8_t *useMag, uint8_t *usePres, uint8_t *posAtt, uint8_t *velAtt, uint8_t *velBias, uint8_t *useFoam, uint8_t *gpsCovType, uint8_t *velCount, float *velInit, float *moveOrigin, float *gpsTimeout, float *deltaLimitPos, float *deltaLimitVel, float *minPosUncertainty, float *minVelUncertainty)
Parses a response from reading the INS Advanced Configuration register.
void VnUartPacket_parseImuRateConfigurationRaw(char *packet, uint16_t *imuRate, uint16_t *navDivisor, float *filterTargetRate, float *filterMinRate)
Parses a response from reading the IMU Rate Configuration register.
VnError VnUartPacket_genReadVelocityCompensationMeasurement(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Velocity Compensation Measurement register on a VectorNav sensor...
void VnUartPacket_parseGpsCompassEstimatedBaseline(VnUartPacket *packet, uint8_t *estBaselineUsed, uint8_t *resv, uint16_t *numMeas, vec3f *position, vec3f *uncertainty)
Parses a response from reading the GPS Compass Estimated Baseline register.
VnError VnUartPacket_genWriteGyroCompensation(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, mat3f c, vec3f b)
Generates a command to write to the Gyro Compensation register on a VectorNav sensor.
void VnUartPacket_parseMagneticAndGravityReferenceVectors(VnUartPacket *packet, vec3f *magRef, vec3f *accRef)
Parses a response from reading the Magnetic and Gravity Reference Vectors register.
void VnUartPacket_parseVNQMR(VnUartPacket *packet, vec4f *quaternion, vec3f *magnetic, vec3f *acceleration, vec3f *angularRate)
Parses a VNQMR asynchronous packet.
VnError VnUartPacket_genCmdRestoreFactorySettings(uint8_t *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to restore the sensor to factory settings.
void VnUartPacket_parseVNYPR(VnUartPacket *packet, vec3f *yawPitchRoll)
Parses a VNYPR asynchronous packet.
void VnUartPacket_parseImuFilteringConfiguration(VnUartPacket *packet, uint16_t *magWindowSize, uint16_t *accelWindowSize, uint16_t *gyroWindowSize, uint16_t *tempWindowSize, uint16_t *presWindowSize, uint8_t *magFilterMode, uint8_t *accelFilterMode, uint8_t *gyroFilterMode, uint8_t *tempFilterMode, uint8_t *presFilterMode)
Parses a response from reading the IMU Filtering Configuration register.
void VnUartPacket_parseVNISL(VnUartPacket *packet, vec3f *ypr, vec3d *lla, vec3f *velocity, vec3f *acceleration, vec3f *angularRate)
Parse a VNISL asynchronous packet.
VnError VnUartPacket_genCmdSetGyroBias(uint8_t *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to set the gyro bias.
VnError VnUartPacket_genReadSerialBaudRate(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Serial Baud Rate register on a VectorNav sensor.
VnError VnUartPacket_genWriteImuFilteringConfiguration(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, uint16_t magWindowSize, uint16_t accelWindowSize, uint16_t gyroWindowSize, uint16_t tempWindowSize, uint16_t presWindowSize, uint8_t magFilterMode, uint8_t accelFilterMode, uint8_t gyroFilterMode, uint8_t tempFilterMode, uint8_t presFilterMode)
Generates a command to write to the IMU Filtering Configuration register on a VectorNav sensor...
VnError VnUartPacket_genWriteReferenceFrameRotation(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, mat3f c)
Generates a command to write to the Reference Frame Rotation register on a VectorNav sensor...
VnError VnUartPacket_genCmdKnownMagneticDisturbance(uint8_t *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, bool disturbancePresent, size_t *cmdSize)
Generates a command to alert the sensor of a known magnetic disturbance.
void VnUartPacket_parseVNMAG(VnUartPacket *packet, vec3f *magnetic)
Parses a VNMAG asynchronous packet.
VnError VnUartPacket_genReadFirmwareVersion(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Firmware Version register on a VectorNav sensor.
void VnUartPacket_parseVNIMU(VnUartPacket *packet, vec3f *magneticUncompensated, vec3f *accelerationUncompensated, vec3f *angularRateUncompensated, float *temperature, float *pressure)
Parses a VNIMU asynchronous packet.
float VnUartPacket_extractFloat(VnUartPacket *packet)
Extracts a float data type from a binary packet and advances the next extraction point appropriately...
VnError VnUartPacket_genReadDeltaThetaAndDeltaVelocity(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Delta Theta and Delta Velocity register on a VectorNav sensor...
void VnUartPacket_parseStartupFilterBiasEstimateRaw(char *packet, vec3f *gyroBias, vec3f *accelBias, float *pressureBias)
Parses a response from reading the Startup Filter Bias Estimate register.
VnError VnUartPacket_genReadUserTag(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the User Tag register on a VectorNav sensor.
void VnUartPacket_parseVpeAccelerometerAdvancedTuningRaw(char *packet, vec3f *minFiltering, vec3f *maxFiltering, float *maxAdaptRate, float *disturbanceWindow, float *maxTuning)
Parses a response from reading the VPE Accelerometer Advanced Tuning register.
void VnUartPacket_parseImuMeasurements(VnUartPacket *packet, vec3f *mag, vec3f *accel, vec3f *gyro, float *temp, float *pressure)
Parses a response from reading the IMU Measurements register.
Represents a 3x3 matrix with an underlying data type of float.
Definition: matrix.h:11
void VnUartPacket_parseAccelerationMeasurementsRaw(char *packet, vec3f *accel)
Parses a response from reading the Acceleration Measurements register.
void VnUartPacket_parseAccelerationMeasurements(VnUartPacket *packet, vec3f *accel)
Parses a response from reading the Acceleration Measurements register.
VnError VnUartPacket_genWriteCommunicationProtocolControl(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, uint8_t serialCount, uint8_t serialStatus, uint8_t spiCount, uint8_t spiStatus, uint8_t serialChecksum, uint8_t spiChecksum, uint8_t errorMode)
Generates a command to write to the Communication Protocol Control register on a VectorNav sensor...
void VnUartPacket_parseFirmwareVersion(VnUartPacket *packet, char *firmwareVersion)
Parses a response from reading the Firmware Version register.
void VnUartPacket_parseYawPitchRollTrueInertialAccelerationAndAngularRatesRaw(char *packet, vec3f *yawPitchRoll, vec3f *inertialAccel, vec3f *gyro)
Parses a response from reading the Yaw, Pitch, Roll, True Inertial Acceleration and Angular Rates reg...
VnError VnUartPacket_genReadGpsCompassEstimatedBaseline(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the GPS Compass Estimated Baseline register on a VectorNav sensor...
VnError VnUartPacket_genReadInsBasicConfiguration(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the INS Basic Configuration register on a VectorNav sensor.
VnError VnUartPacket_genReadReferenceVectorConfiguration(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Reference Vector Configuration register on a VectorNav sensor...
void VnUartPacket_parseMagnetometerCompensationRaw(char *packet, mat3f *c, vec3f *b)
Parses a response from reading the Magnetometer Compensation register.
void VnUartPacket_parseGpsSolutionEcef(VnUartPacket *packet, double *tow, uint16_t *week, uint8_t *gpsFix, uint8_t *numSats, vec3d *position, vec3f *velocity, vec3f *posAcc, float *speedAcc, float *timeAcc)
Parses a response from reading the GPS Solution - ECEF register.
VnError VnUartPacket_genWriteStartupFilterBiasEstimate(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, vec3f gyroBias, vec3f accelBias, float pressureBias)
Generates a command to write to the Startup Filter Bias Estimate register on a VectorNav sensor...
VnError VnUartPacket_genWriteAccelerationCompensation(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, mat3f c, vec3f b)
Generates a command to write to the Acceleration Compensation register on a VectorNav sensor...
void VnUartPacket_parseMagneticMeasurements(VnUartPacket *packet, vec3f *mag)
Parses a response from reading the Magnetic Measurements register.
uint64_t VnUartPacket_extractUint64(VnUartPacket *packet)
Extracts a uint64_t data type from a binary packet and advances the next extraction point appropriate...
VnError VnUartPacket_genReadVpeMagnetometerBasicTuning(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the VPE Magnetometer Basic Tuning register on a VectorNav sensor...
void VnUartPacket_parseYawPitchRollRaw(char *packet, vec3f *yawPitchRoll)
Parses a response from reading the Yaw Pitch Roll register.
void VnUartPacket_parseGpsSolutionLlaRaw(char *packet, double *time, uint16_t *week, uint8_t *gpsFix, uint8_t *numSats, vec3d *lla, vec3f *nedVel, vec3f *nedAcc, float *speedAcc, float *timeAcc)
Parses a response from reading the GPS Solution - LLA register.
VnError VnUartPacket_genReadSerialNumber(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Serial Number register on a VectorNav sensor.
void VnUartPacket_parseVNYBA(VnUartPacket *packet, vec3f *yawPitchRoll, vec3f *accelerationBody, vec3f *angularRate)
Parses a VNYMR asynchronous packet.
VnError VnUartPacket_genReadCalculatedMagnetometerCalibration(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Calculated Magnetometer Calibration register on a VectorNav sensor...
void VnUartPacket_parseModelNumberRaw(char *packet, char *productName)
Parses a response from reading the Model Number register.
void VnUartPacket_parseFilterMeasurementsVarianceParameters(VnUartPacket *packet, float *angularWalkVariance, vec3f *angularRateVariance, vec3f *magneticVariance, vec3f *accelerationVariance)
Parses a response from reading the Filter Measurements Variance Parameters register.
void VnUartPacket_parseGyroCompensationRaw(char *packet, mat3f *c, vec3f *b)
Parses a response from reading the Gyro Compensation register.
vec4f VnUartPacket_extractVec4f(VnUartPacket *packet)
Extracts a vec4f data type from a binary packet and advances the next extraction point appropriately...
void VnUartPacket_parseVelocityCompensationMeasurementRaw(char *packet, vec3f *velocity)
Parses a response from reading the Velocity Compensation Measurement register.
void VnUartPacket_parseAttitudeQuaternionRaw(char *packet, vec4f *quat)
Parses a response from reading the Attitude Quaternion register.
void VnUartPacket_parseStartupFilterBiasEstimate(VnUartPacket *packet, vec3f *gyroBias, vec3f *accelBias, float *pressureBias)
Parses a response from reading the Startup Filter Bias Estimate register.
uint16_t VnUartPacket_extractUint16(VnUartPacket *packet)
Extracts a uint16_t data type from a binary packet and advances the next extraction point appropriate...
VnError VnUartPacket_genReadMagneticAndGravityReferenceVectors(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Magnetic and Gravity Reference Vectors register on a VectorNav sensor...
void VnUartPacket_parseInsStateEcefRaw(char *packet, vec3f *yawPitchRoll, vec3d *position, vec3f *velocity, vec3f *accel, vec3f *angularRate)
Parses a response from reading the INS State - ECEF register.
Various vector types and operations.
Definition: vector.h:14
void VnUartPacket_parseError(VnUartPacket *packet, uint8_t *error)
Parses an error packet to get the error type.
void VnUartPacket_parseDeltaThetaAndDeltaVelocityRaw(char *packet, float *deltaTime, vec3f *deltaTheta, vec3f *deltaVelocity)
Parses a response from reading the Delta Theta and Delta Velocity register.
void VnUartPacket_parseVpeGyroBasicTuningRaw(char *packet, vec3f *angularWalkVariance, vec3f *baseTuning, vec3f *adaptiveTuning)
Parses a response from reading the VPE Gyro Basic Tuning register.
void VnUartPacket_parseVpeMagnetometerAdvancedTuningRaw(char *packet, vec3f *minFiltering, vec3f *maxFiltering, float *maxAdaptRate, float *disturbanceWindow, float *maxTuning)
Parses a response from reading the VPE Magnetometer Advanced Tuning register.
void VnUartPacket_parseInsStateEcef(VnUartPacket *packet, vec3f *yawPitchRoll, vec3d *position, vec3f *velocity, vec3f *accel, vec3f *angularRate)
Parses a response from reading the INS State - ECEF register.
size_t curExtractLoc
Definition: upack.h:37
VnError VnUartPacket_genReadGpsSolutionEcef(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the GPS Solution - ECEF register on a VectorNav sensor.
void VnUartPacket_parseCommunicationProtocolControl(VnUartPacket *packet, uint8_t *serialCount, uint8_t *serialStatus, uint8_t *spiCount, uint8_t *spiStatus, uint8_t *serialChecksum, uint8_t *spiChecksum, uint8_t *errorMode)
Parses a response from reading the Communication Protocol Control register.
void VnUartPacket_parseHardwareRevision(VnUartPacket *packet, uint32_t *revision)
Parses a response from reading the Hardware Revision register.
void VnUartPacket_parseDeltaThetaAndDeltaVelocityConfigurationRaw(char *packet, uint8_t *integrationFrame, uint8_t *gyroCompensation, uint8_t *accelCompensation, uint8_t *reserved1, uint16_t *reserved2)
Parses a response from reading the Delta Theta and Delta Velocity Configuration register.
void VnUartPacket_parseSerialNumberRaw(char *packet, uint32_t *serialNum)
Parses a response from reading the Serial Number register.
void VnUartPacket_parseMagnetometerCompensation(VnUartPacket *packet, mat3f *c, vec3f *b)
Parses a response from reading the Magnetometer Compensation register.
void VnUartPacket_parseVNINS(VnUartPacket *packet, double *time, uint16_t *week, uint16_t *status, vec3f *yawPitchRoll, vec3d *lla, vec3f *nedVel, float *attUncertainty, float *posUncertainty, float *velUncertainty)
Parses a VNINS asynchronous packet.
VnError VnUartPacket_genWriteBinaryOutput1(uint8_t *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, uint16_t asyncMode, uint16_t rateDivisor, uint16_t commonField, uint16_t timeField, uint16_t imuField, uint16_t gpsField, uint16_t attitudeField, uint16_t insField)
Generates a command to write to the Binary Output 1 register.
VnError VnUartPacket_genReadModelNumber(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize)
Generates a command to read the Model Number register on a VectorNav sensor.
VnError VnUartPacket_genWriteGpsAntennaOffset(char *buffer, size_t bufferSize, VnErrorDetectionMode errorDetectionMode, size_t *cmdSize, vec3f position)
Generates a command to write to the GPS Antenna Offset register on a VectorNav sensor.
size_t length
Definition: upack.h:40
void VnUartPacket_parseVpeMagnetometerBasicTuning(VnUartPacket *packet, vec3f *baseTuning, vec3f *adaptiveTuning, vec3f *adaptiveFiltering)
Parses a response from reading the VPE Magnetometer Basic Tuning register.
void VnUartPacket_parseModelNumber(VnUartPacket *packet, char *productName)
Parses a response from reading the Model Number register.