VectorNav C Library
spi.h
1 #ifndef _VNSPI_H_
2 #define _VNSPI_H_
3 
4 #include <stddef.h>
5 
6 #include "vn/int.h"
7 #include "vn/error.h"
8 #include "vn/math/vector.h"
9 #include "vn/math/matrix.h"
10 
11 #ifdef __cplusplus
12 extern "C" {
13 #endif
14 
25 VnError VnSpi_genWriteSettings(
26  char* buffer,
27  size_t* size,
28  size_t desiredLength,
29  size_t* responseSize);
30 
41 VnError VnSpi_genRestorFactorySettings(
42  char* buffer,
43  size_t* size,
44  size_t desiredLength,
45  size_t* responseSize);
46 
57 VnError VnSpi_genTare(
58  char* buffer,
59  size_t* size,
60  size_t desiredLength,
61  size_t* responseSize);
62 
73 VnError VnSpi_genReset(
74  char* buffer,
75  size_t* size,
76  size_t desiredLength,
77  size_t* responseSize);
78 
89 VnError VnSpi_genRead(
90  char* buffer,
91  size_t* size,
92  uint8_t regId,
93  size_t desiredLength);
94 
101 VnError VnSpi_parseUserTag(
102  const char* response,
103  char* tag,
104  size_t tagLength);
105 
112 VnError VnSpi_parseModelNumber(
113  const char* response,
114  char* productName,
115  size_t productNameLength);
116 
122 VnError VnSpi_parseHardwareRevision(
123  const char* response,
124  uint32_t* revision);
125 
131 VnError VnSpi_parseSerialNumber(
132  const char* response,
133  uint32_t* serialNum);
134 
141 VnError VnSpi_parseFirmwareVersion(
142  const char* response,
143  char* firmwareVersion,
144  size_t firmwareVersionLength);
145 
151 VnError VnSpi_parseSerialBaudRate(
152  const char* response,
153  uint32_t* baudrate);
154 
160 VnError VnSpi_parseAsyncDataOutputType(
161  const char* response,
162  uint32_t* ador);
163 
169 VnError VnSpi_parseAsyncDataOutputFrequency(
170  const char* response,
171  uint32_t* adof);
172 
178 VnError VnSpi_parseYawPitchRoll(
179  const char* response,
180  vec3f* yawPitchRoll);
181 
187 VnError VnSpi_parseAttitudeQuaternion(
188  const char* response,
189  vec4f* quat);
190 
199 VnError VnSpi_parseQuaternionMagneticAccelerationAndAngularRates(
200  const char* response,
201  vec4f* quat,
202  vec3f* mag,
203  vec3f* accel,
204  vec3f* gyro);
205 
211 VnError VnSpi_parseMagneticMeasurements(
212  const char* response,
213  vec3f* mag);
214 
220 VnError VnSpi_parseAccelerationMeasurements(
221  const char* response,
222  vec3f* accel);
223 
229 VnError VnSpi_parseAngularRateMeasurements(
230  const char* response,
231  vec3f* gyro);
232 
240 VnError VnSpi_parseMagneticAccelerationAndAngularRates(
241  const char* response,
242  vec3f* mag,
243  vec3f* accel,
244  vec3f* gyro);
245 
252 VnError VnSpi_parseMagneticAndGravityReferenceVectors(
253  const char* response,
254  vec3f* magRef,
255  vec3f* accRef);
256 
265 VnError VnSpi_parseFilterMeasurementsVarianceParameters(
266  const char* response,
267  float* angularWalkVariance,
268  vec3f* angularRateVariance,
269  vec3f* magneticVariance,
270  vec3f* accelerationVariance);
271 
278 VnError VnSpi_parseMagnetometerCompensation(
279  const char* response,
280  mat3f* c,
281  vec3f* b);
282 
291 VnError VnSpi_parseFilterActiveTuningParameters(
292  const char* response,
293  float* magneticDisturbanceGain,
294  float* accelerationDisturbanceGain,
295  float* magneticDisturbanceMemory,
296  float* accelerationDisturbanceMemory);
297 
304 VnError VnSpi_parseAccelerationCompensation(
305  const char* response,
306  mat3f* c,
307  vec3f* b);
308 
314 VnError VnSpi_parseReferenceFrameRotation(
315  const char* response,
316  mat3f* c);
317 
326 VnError VnSpi_parseYawPitchRollMagneticAccelerationAndAngularRates(
327  const char* response,
328  vec3f* yawPitchRoll,
329  vec3f* mag,
330  vec3f* accel,
331  vec3f* gyro);
332 
344 VnError VnSpi_parseCommunicationProtocolControl(
345  const char* response,
346  uint8_t* serialCount,
347  uint8_t* serialStatus,
348  uint8_t* spiCount,
349  uint8_t* spiStatus,
350  uint8_t* serialChecksum,
351  uint8_t* spiChecksum,
352  uint8_t* errorMode);
353 
367 VnError VnSpi_parseSynchronizationControl(
368  const char* response,
369  uint8_t* syncInMode,
370  uint8_t* syncInEdge,
371  uint16_t* syncInSkipFactor,
372  uint32_t* reserved1,
373  uint8_t* syncOutMode,
374  uint8_t* syncOutPolarity,
375  uint16_t* syncOutSkipFactor,
376  uint32_t* syncOutPulseWidth,
377  uint32_t* reserved2);
378 
386 VnError VnSpi_parseSynchronizationStatus(
387  const char* response,
388  uint32_t* syncInCount,
389  uint32_t* syncInTime,
390  uint32_t* syncOutCount);
391 
401 VnError VnSpi_parseFilterBasicControl(
402  const char* response,
403  uint8_t* magMode,
404  uint8_t* extMagMode,
405  uint8_t* extAccMode,
406  uint8_t* extGyroMode,
407  vec3f* gyroLimit);
408 
417 VnError VnSpi_parseVpeBasicControl(
418  const char* response,
419  uint8_t* enable,
420  uint8_t* headingMode,
421  uint8_t* filteringMode,
422  uint8_t* tuningMode);
423 
431 VnError VnSpi_parseVpeMagnetometerBasicTuning(
432  const char* response,
433  vec3f* baseTuning,
434  vec3f* adaptiveTuning,
435  vec3f* adaptiveFiltering);
436 
446 VnError VnSpi_parseVpeMagnetometerAdvancedTuning(
447  const char* response,
448  vec3f* minFiltering,
449  vec3f* maxFiltering,
450  float* maxAdaptRate,
451  float* disturbanceWindow,
452  float* maxTuning);
453 
461 VnError VnSpi_parseVpeAccelerometerBasicTuning(
462  const char* response,
463  vec3f* baseTuning,
464  vec3f* adaptiveTuning,
465  vec3f* adaptiveFiltering);
466 
476 VnError VnSpi_parseVpeAccelerometerAdvancedTuning(
477  const char* response,
478  vec3f* minFiltering,
479  vec3f* maxFiltering,
480  float* maxAdaptRate,
481  float* disturbanceWindow,
482  float* maxTuning);
483 
491 VnError VnSpi_parseVpeGyroBasicTuning(
492  const char* response,
493  vec3f* angularWalkVariance,
494  vec3f* baseTuning,
495  vec3f* adaptiveTuning);
496 
502 VnError VnSpi_parseFilterStartupGyroBias(
503  const char* response,
504  vec3f* bias);
505 
513 VnError VnSpi_parseMagnetometerCalibrationControl(
514  const char* response,
515  uint8_t* hsiMode,
516  uint8_t* hsiOutput,
517  uint8_t* convergeRate);
518 
525 VnError VnSpi_parseCalculatedMagnetometerCalibration(
526  const char* response,
527  mat3f* c,
528  vec3f* b);
529 
536 VnError VnSpi_parseIndoorHeadingModeControl(
537  const char* response,
538  float* maxRateError,
539  uint8_t* reserved1);
540 
546 VnError VnSpi_parseVelocityCompensationMeasurement(
547  const char* response,
548  vec3f* velocity);
549 
557 VnError VnSpi_parseVelocityCompensationControl(
558  const char* response,
559  uint8_t* mode,
560  float* velocityTuning,
561  float* rateTuning);
562 
571 VnError VnSpi_parseVelocityCompensationStatus(
572  const char* response,
573  float* x,
574  float* xDot,
575  vec3f* accelOffset,
576  vec3f* omega);
577 
587 VnError VnSpi_parseImuMeasurements(
588  const char* response,
589  vec3f* mag,
590  vec3f* accel,
591  vec3f* gyro,
592  float* temp,
593  float* pressure);
594 
604 VnError VnSpi_parseGpsConfiguration(
605  const char* response,
606  uint8_t* mode,
607  uint8_t* ppsSource,
608  uint8_t* reserved1,
609  uint8_t* reserved2,
610  uint8_t* reserved3);
611 
617 VnError VnSpi_parseGpsAntennaOffset(
618  const char* response,
619  vec3f* position);
620 
634 VnError VnSpi_parseGpsSolutionLla(
635  const char* response,
636  double* time,
637  uint16_t* week,
638  uint8_t* gpsFix,
639  uint8_t* numSats,
640  vec3d* lla,
641  vec3f* nedVel,
642  vec3f* nedAcc,
643  float* speedAcc,
644  float* timeAcc);
645 
659 VnError VnSpi_parseGpsSolutionEcef(
660  const char* response,
661  double* tow,
662  uint16_t* week,
663  uint8_t* gpsFix,
664  uint8_t* numSats,
665  vec3d* position,
666  vec3f* velocity,
667  vec3f* posAcc,
668  float* speedAcc,
669  float* timeAcc);
670 
684 VnError VnSpi_parseInsSolutionLla(
685  const char* response,
686  double* time,
687  uint16_t* week,
688  uint16_t* status,
689  vec3f* yawPitchRoll,
690  vec3d* position,
691  vec3f* nedVel,
692  float* attUncertainty,
693  float* posUncertainty,
694  float* velUncertainty);
695 
709 VnError VnSpi_parseInsSolutionEcef(
710  const char* response,
711  double* time,
712  uint16_t* week,
713  uint16_t* status,
714  vec3f* yawPitchRoll,
715  vec3d* position,
716  vec3f* velocity,
717  float* attUncertainty,
718  float* posUncertainty,
719  float* velUncertainty);
720 
729 VnError VnSpi_parseInsBasicConfiguration(
730  const char* response,
731  uint8_t* scenario,
732  uint8_t* ahrsAiding,
733  uint8_t* estBaseline,
734  uint8_t* resv2);
735 
755 VnError VnSpi_parseInsAdvancedConfiguration(
756  const char* response,
757  uint8_t* useMag,
758  uint8_t* usePres,
759  uint8_t* posAtt,
760  uint8_t* velAtt,
761  uint8_t* velBias,
762  uint8_t* useFoam,
763  uint8_t* gpsCovType,
764  uint8_t* velCount,
765  float* velInit,
766  float* moveOrigin,
767  float* gpsTimeout,
768  float* deltaLimitPos,
769  float* deltaLimitVel,
770  float* minPosUncertainty,
771  float* minVelUncertainty);
772 
782 VnError VnSpi_parseInsStateLla(
783  const char* response,
784  vec3f* yawPitchRoll,
785  vec3d* position,
786  vec3f* velocity,
787  vec3f* accel,
788  vec3f* angularRate);
789 
799 VnError VnSpi_parseInsStateEcef(
800  const char* response,
801  vec3f* yawPitchRoll,
802  vec3d* position,
803  vec3f* velocity,
804  vec3f* accel,
805  vec3f* angularRate);
806 
814 VnError VnSpi_parseStartupFilterBiasEstimate(
815  const char* response,
816  vec3f* gyroBias,
817  vec3f* accelBias,
818  float* pressureBias);
819 
827 VnError VnSpi_parseDeltaThetaAndDeltaVelocity(
828  const char* response,
829  float* deltaTime,
830  vec3f* deltaTheta,
831  vec3f* deltaVelocity);
832 
842 VnError VnSpi_parseDeltaThetaAndDeltaVelocityConfiguration(
843  const char* response,
844  uint8_t* integrationFrame,
845  uint8_t* gyroCompensation,
846  uint8_t* accelCompensation,
847  uint8_t* reserved1,
848  uint16_t* reserved2);
849 
861 VnError VnSpi_parseReferenceVectorConfiguration(
862  const char* response,
863  uint8_t* useMagModel,
864  uint8_t* useGravityModel,
865  uint8_t* resv1,
866  uint8_t* resv2,
867  uint32_t* recalcThreshold,
868  float* year,
869  vec3d* position);
870 
877 VnError VnSpi_parseGyroCompensation(
878  const char* response,
879  mat3f* c,
880  vec3f* b);
881 
896 VnError VnSpi_parseImuFilteringConfiguration(
897  const char* response,
898  uint16_t* magWindowSize,
899  uint16_t* accelWindowSize,
900  uint16_t* gyroWindowSize,
901  uint16_t* tempWindowSize,
902  uint16_t* presWindowSize,
903  uint8_t* magFilterMode,
904  uint8_t* accelFilterMode,
905  uint8_t* gyroFilterMode,
906  uint8_t* tempFilterMode,
907  uint8_t* presFilterMode);
908 
915 VnError VnSpi_parseGpsCompassBaseline(
916  const char* response,
917  vec3f* position,
918  vec3f* uncertainty);
919 
929 VnError VnSpi_parseGpsCompassEstimatedBaseline(
930  const char* response,
931  uint8_t* estBaselineUsed,
932  uint8_t* resv,
933  uint16_t* numMeas,
934  vec3f* position,
935  vec3f* uncertainty);
936 
945 VnError VnSpi_parseImuRateConfiguration(
946  const char* response,
947  uint16_t* imuRate,
948  uint16_t* navDivisor,
949  float* filterTargetRate,
950  float* filterMinRate);
951 
959 VnError VnSpi_parseYawPitchRollTrueBodyAccelerationAndAngularRates(
960  const char* response,
961  vec3f* yawPitchRoll,
962  vec3f* bodyAccel,
963  vec3f* gyro);
964 
972 VnError VnSpi_parseYawPitchRollTrueInertialAccelerationAndAngularRates(
973  const char* response,
974  vec3f* yawPitchRoll,
975  vec3f* inertialAccel,
976  vec3f* gyro);
977 
1004 VnError VnSpi_genReadUserTag(
1005  char* buffer,
1006  size_t* size,
1007  size_t desiredLength,
1008  size_t* responseSize);
1009 
1020 VnError VnSpi_genReadModelNumber(
1021  char* buffer,
1022  size_t* size,
1023  size_t desiredLength,
1024  size_t* responseSize);
1025 
1037  char* buffer,
1038  size_t* size,
1039  size_t desiredLength,
1040  size_t* responseSize);
1041 
1053  char* buffer,
1054  size_t* size,
1055  size_t desiredLength,
1056  size_t* responseSize);
1057 
1069  char* buffer,
1070  size_t* size,
1071  size_t desiredLength,
1072  size_t* responseSize);
1073 
1085  char* buffer,
1086  size_t* size,
1087  size_t desiredLength,
1088  size_t* responseSize);
1089 
1101  char* buffer,
1102  size_t* size,
1103  size_t desiredLength,
1104  size_t* responseSize);
1105 
1117  char* buffer,
1118  size_t* size,
1119  size_t desiredLength,
1120  size_t* responseSize);
1121 
1133  char* buffer,
1134  size_t* size,
1135  size_t desiredLength,
1136  size_t* responseSize);
1137 
1149  char* buffer,
1150  size_t* size,
1151  size_t desiredLength,
1152  size_t* responseSize);
1153 
1165  char* buffer,
1166  size_t* size,
1167  size_t desiredLength,
1168  size_t* responseSize);
1169 
1181  char* buffer,
1182  size_t* size,
1183  size_t desiredLength,
1184  size_t* responseSize);
1185 
1197  char* buffer,
1198  size_t* size,
1199  size_t desiredLength,
1200  size_t* responseSize);
1201 
1213  char* buffer,
1214  size_t* size,
1215  size_t desiredLength,
1216  size_t* responseSize);
1217 
1229  char* buffer,
1230  size_t* size,
1231  size_t desiredLength,
1232  size_t* responseSize);
1233 
1245  char* buffer,
1246  size_t* size,
1247  size_t desiredLength,
1248  size_t* responseSize);
1249 
1261  char* buffer,
1262  size_t* size,
1263  size_t desiredLength,
1264  size_t* responseSize);
1265 
1277  char* buffer,
1278  size_t* size,
1279  size_t desiredLength,
1280  size_t* responseSize);
1281 
1293  char* buffer,
1294  size_t* size,
1295  size_t desiredLength,
1296  size_t* responseSize);
1297 
1309  char* buffer,
1310  size_t* size,
1311  size_t desiredLength,
1312  size_t* responseSize);
1313 
1325  char* buffer,
1326  size_t* size,
1327  size_t desiredLength,
1328  size_t* responseSize);
1329 
1341  char* buffer,
1342  size_t* size,
1343  size_t desiredLength,
1344  size_t* responseSize);
1345 
1357  char* buffer,
1358  size_t* size,
1359  size_t desiredLength,
1360  size_t* responseSize);
1361 
1373  char* buffer,
1374  size_t* size,
1375  size_t desiredLength,
1376  size_t* responseSize);
1377 
1389  char* buffer,
1390  size_t* size,
1391  size_t desiredLength,
1392  size_t* responseSize);
1393 
1405  char* buffer,
1406  size_t* size,
1407  size_t desiredLength,
1408  size_t* responseSize);
1409 
1421  char* buffer,
1422  size_t* size,
1423  size_t desiredLength,
1424  size_t* responseSize);
1425 
1437  char* buffer,
1438  size_t* size,
1439  size_t desiredLength,
1440  size_t* responseSize);
1441 
1453  char* buffer,
1454  size_t* size,
1455  size_t desiredLength,
1456  size_t* responseSize);
1457 
1469  char* buffer,
1470  size_t* size,
1471  size_t desiredLength,
1472  size_t* responseSize);
1473 
1485  char* buffer,
1486  size_t* size,
1487  size_t desiredLength,
1488  size_t* responseSize);
1489 
1501  char* buffer,
1502  size_t* size,
1503  size_t desiredLength,
1504  size_t* responseSize);
1505 
1517  char* buffer,
1518  size_t* size,
1519  size_t desiredLength,
1520  size_t* responseSize);
1521 
1533  char* buffer,
1534  size_t* size,
1535  size_t desiredLength,
1536  size_t* responseSize);
1537 
1549  char* buffer,
1550  size_t* size,
1551  size_t desiredLength,
1552  size_t* responseSize);
1553 
1565  char* buffer,
1566  size_t* size,
1567  size_t desiredLength,
1568  size_t* responseSize);
1569 
1581  char* buffer,
1582  size_t* size,
1583  size_t desiredLength,
1584  size_t* responseSize);
1585 
1597  char* buffer,
1598  size_t* size,
1599  size_t desiredLength,
1600  size_t* responseSize);
1601 
1613  char* buffer,
1614  size_t* size,
1615  size_t desiredLength,
1616  size_t* responseSize);
1617 
1628 VnError VnSpi_genReadInsStateLla(
1629  char* buffer,
1630  size_t* size,
1631  size_t desiredLength,
1632  size_t* responseSize);
1633 
1645  char* buffer,
1646  size_t* size,
1647  size_t desiredLength,
1648  size_t* responseSize);
1649 
1661  char* buffer,
1662  size_t* size,
1663  size_t desiredLength,
1664  size_t* responseSize);
1665 
1677  char* buffer,
1678  size_t* size,
1679  size_t desiredLength,
1680  size_t* responseSize);
1681 
1693  char* buffer,
1694  size_t* size,
1695  size_t desiredLength,
1696  size_t* responseSize);
1697 
1709  char* buffer,
1710  size_t* size,
1711  size_t desiredLength,
1712  size_t* responseSize);
1713 
1725  char* buffer,
1726  size_t* size,
1727  size_t desiredLength,
1728  size_t* responseSize);
1729 
1741  char* buffer,
1742  size_t* size,
1743  size_t desiredLength,
1744  size_t* responseSize);
1745 
1757  char* buffer,
1758  size_t* size,
1759  size_t desiredLength,
1760  size_t* responseSize);
1761 
1773  char* buffer,
1774  size_t* size,
1775  size_t desiredLength,
1776  size_t* responseSize);
1777 
1789  char* buffer,
1790  size_t* size,
1791  size_t desiredLength,
1792  size_t* responseSize);
1793 
1805  char* buffer,
1806  size_t* size,
1807  size_t desiredLength,
1808  size_t* responseSize);
1809 
1810 /* \}*/
1811 
1846 VnError VnSpi_genWriteUserTag(
1847  char* buffer,
1848  size_t* size,
1849  size_t desiredLength,
1850  size_t* responseSize,
1851  char* tag);
1852 
1865  char* buffer,
1866  size_t* size,
1867  size_t desiredLength,
1868  size_t* responseSize,
1869  uint32_t baudrate);
1870 
1883  char* buffer,
1884  size_t* size,
1885  size_t desiredLength,
1886  size_t* responseSize,
1887  uint32_t baudrate);
1888 
1901  char* buffer,
1902  size_t* size,
1903  size_t desiredLength,
1904  size_t* responseSize,
1905  uint32_t ador);
1906 
1919  char* buffer,
1920  size_t* size,
1921  size_t desiredLength,
1922  size_t* responseSize,
1923  uint32_t ador);
1924 
1937  char* buffer,
1938  size_t* size,
1939  size_t desiredLength,
1940  size_t* responseSize,
1941  uint32_t adof);
1942 
1955  char* buffer,
1956  size_t* size,
1957  size_t desiredLength,
1958  size_t* responseSize,
1959  uint32_t adof);
1960 
1974  char* buffer,
1975  size_t* size,
1976  size_t desiredLength,
1977  size_t* responseSize,
1978  vec3f magRef,
1979  vec3f accRef);
1980 
1994  char* buffer,
1995  size_t* size,
1996  size_t desiredLength,
1997  size_t* responseSize,
1998  mat3f c,
1999  vec3f b);
2000 
2014  char* buffer,
2015  size_t* size,
2016  size_t desiredLength,
2017  size_t* responseSize,
2018  mat3f c,
2019  vec3f b);
2020 
2033  char* buffer,
2034  size_t* size,
2035  size_t desiredLength,
2036  size_t* responseSize,
2037  mat3f c);
2038 
2057  char* buffer,
2058  size_t* size,
2059  size_t desiredLength,
2060  size_t* responseSize,
2061  uint8_t serialCount,
2062  uint8_t serialStatus,
2063  uint8_t spiCount,
2064  uint8_t spiStatus,
2065  uint8_t serialChecksum,
2066  uint8_t spiChecksum,
2067  uint8_t errorMode);
2068 
2089  char* buffer,
2090  size_t* size,
2091  size_t desiredLength,
2092  size_t* responseSize,
2093  uint8_t syncInMode,
2094  uint8_t syncInEdge,
2095  uint16_t syncInSkipFactor,
2096  uint32_t reserved1,
2097  uint8_t syncOutMode,
2098  uint8_t syncOutPolarity,
2099  uint16_t syncOutSkipFactor,
2100  uint32_t syncOutPulseWidth,
2101  uint32_t reserved2);
2102 
2117  char* buffer,
2118  size_t* size,
2119  size_t desiredLength,
2120  size_t* responseSize,
2121  uint32_t syncInCount,
2122  uint32_t syncInTime,
2123  uint32_t syncOutCount);
2124 
2140  char* buffer,
2141  size_t* size,
2142  size_t desiredLength,
2143  size_t* responseSize,
2144  uint8_t enable,
2145  uint8_t headingMode,
2146  uint8_t filteringMode,
2147  uint8_t tuningMode);
2148 
2163  char* buffer,
2164  size_t* size,
2165  size_t desiredLength,
2166  size_t* responseSize,
2167  vec3f baseTuning,
2168  vec3f adaptiveTuning,
2169  vec3f adaptiveFiltering);
2170 
2185  char* buffer,
2186  size_t* size,
2187  size_t desiredLength,
2188  size_t* responseSize,
2189  vec3f baseTuning,
2190  vec3f adaptiveTuning,
2191  vec3f adaptiveFiltering);
2192 
2207  char* buffer,
2208  size_t* size,
2209  size_t desiredLength,
2210  size_t* responseSize,
2211  uint8_t hsiMode,
2212  uint8_t hsiOutput,
2213  uint8_t convergeRate);
2214 
2227  char* buffer,
2228  size_t* size,
2229  size_t desiredLength,
2230  size_t* responseSize,
2231  vec3f velocity);
2232 
2247  char* buffer,
2248  size_t* size,
2249  size_t desiredLength,
2250  size_t* responseSize,
2251  uint8_t mode,
2252  float velocityTuning,
2253  float rateTuning);
2254 
2271  char* buffer,
2272  size_t* size,
2273  size_t desiredLength,
2274  size_t* responseSize,
2275  uint8_t mode,
2276  uint8_t ppsSource,
2277  uint8_t reserved1,
2278  uint8_t reserved2,
2279  uint8_t reserved3);
2280 
2293  char* buffer,
2294  size_t* size,
2295  size_t desiredLength,
2296  size_t* responseSize,
2297  vec3f position);
2298 
2314  char* buffer,
2315  size_t* size,
2316  size_t desiredLength,
2317  size_t* responseSize,
2318  uint8_t scenario,
2319  uint8_t ahrsAiding,
2320  uint8_t estBaseline,
2321  uint8_t resv2);
2322 
2337  char* buffer,
2338  size_t* size,
2339  size_t desiredLength,
2340  size_t* responseSize,
2341  vec3f gyroBias,
2342  vec3f accelBias,
2343  float pressureBias);
2344 
2361  char* buffer,
2362  size_t* size,
2363  size_t desiredLength,
2364  size_t* responseSize,
2365  uint8_t integrationFrame,
2366  uint8_t gyroCompensation,
2367  uint8_t accelCompensation,
2368  uint8_t reserved1,
2369  uint16_t reserved2);
2370 
2389  char* buffer,
2390  size_t* size,
2391  size_t desiredLength,
2392  size_t* responseSize,
2393  uint8_t useMagModel,
2394  uint8_t useGravityModel,
2395  uint8_t resv1,
2396  uint8_t resv2,
2397  uint32_t recalcThreshold,
2398  float year,
2399  vec3d position);
2400 
2414  char* buffer,
2415  size_t* size,
2416  size_t desiredLength,
2417  size_t* responseSize,
2418  mat3f c,
2419  vec3f b);
2420 
2442  char* buffer,
2443  size_t* size,
2444  size_t desiredLength,
2445  size_t* responseSize,
2446  uint16_t magWindowSize,
2447  uint16_t accelWindowSize,
2448  uint16_t gyroWindowSize,
2449  uint16_t tempWindowSize,
2450  uint16_t presWindowSize,
2451  uint8_t magFilterMode,
2452  uint8_t accelFilterMode,
2453  uint8_t gyroFilterMode,
2454  uint8_t tempFilterMode,
2455  uint8_t presFilterMode);
2456 
2470  char* buffer,
2471  size_t* size,
2472  size_t desiredLength,
2473  size_t* responseSize,
2474  vec3f position,
2475  vec3f uncertainty);
2476 
2477 #ifdef __cplusplus
2478 }
2479 #endif
2480 
2481 #endif
VnError VnSpi_genReadAccelerationMeasurements(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Acceleration Measurements register on a VectorNav sensor...
VnError VnSpi_genReadReferenceFrameRotation(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Reference Frame Rotation register on a VectorNav sensor.
VnError VnSpi_genWriteAsyncDataOutputFrequency(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, uint32_t adof)
Generates a command to write the Async Data Output Frequency register on a VectorNav sensor...
VnError VnSpi_genReadAngularRateMeasurements(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Angular Rate Measurements register on a VectorNav sensor...
VnError VnSpi_genReadDeltaThetaAndDeltaVelocityConfiguration(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Delta Theta and Delta Velocity Configuration register on a VectorNav ...
VnError VnSpi_genReadGpsCompassBaseline(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the GPS Compass Baseline register on a VectorNav sensor.
VnError VnSpi_genReadInsStateLla(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the INS State - LLA register on a VectorNav sensor.
VnError VnSpi_genReadGpsConfiguration(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the GPS Configuration register on a VectorNav sensor. ...
VnError VnSpi_genWriteMagnetometerCompensation(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, mat3f c, vec3f b)
Generates a command to write the Magnetometer Compensation register on a VectorNav sensor...
VnError VnSpi_genReadMagneticAndGravityReferenceVectors(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Magnetic and Gravity Reference Vectors register on a VectorNav sensor...
VnError VnSpi_genWriteDeltaThetaAndDeltaVelocityConfiguration(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, uint8_t integrationFrame, uint8_t gyroCompensation, uint8_t accelCompensation, uint8_t reserved1, uint16_t reserved2)
Generates a command to write the Delta Theta and Delta Velocity Configuration register on a VectorNav...
VnError VnSpi_genReadImuMeasurements(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the IMU Measurements register on a VectorNav sensor.
VnError VnSpi_genWriteVelocityCompensationMeasurement(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, vec3f velocity)
Generates a command to write the Velocity Compensation Measurement register on a VectorNav sensor...
VnError VnSpi_genReadSerialNumber(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Serial Number register on a VectorNav sensor.
VnError VnSpi_genWriteCommunicationProtocolControl(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, 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 the Communication Protocol Control register on a VectorNav sensor...
VnError VnSpi_genWriteVpeBasicControl(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, uint8_t enable, uint8_t headingMode, uint8_t filteringMode, uint8_t tuningMode)
Generates a command to write the VPE Basic Control register on a VectorNav sensor.
VnError VnSpi_genReadYawPitchRollMagneticAccelerationAndAngularRates(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Yaw, Pitch, Roll, Magnetic, Acceleration and Angular Rates register o...
VnError VnSpi_genWriteGpsAntennaOffset(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, vec3f position)
Generates a command to write the GPS Antenna Offset register on a VectorNav sensor.
VnError VnSpi_genWriteUserTag(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, char *tag)
Generates a command to write the User Tag register on a VectorNav sensor.
VnError VnSpi_genReadGpsSolutionLla(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the GPS Solution - LLA register on a VectorNav sensor.
VnError VnSpi_genReadVpeAccelerometerBasicTuning(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the VPE Accelerometer Basic Tuning register on a VectorNav sensor...
VnError VnSpi_genReadGpsSolutionEcef(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the GPS Solution - ECEF register on a VectorNav sensor.
VnError VnSpi_genWriteMagnetometerCalibrationControl(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, uint8_t hsiMode, uint8_t hsiOutput, uint8_t convergeRate)
Generates a command to write the Magnetometer Calibration Control register on a VectorNav sensor...
VnError VnSpi_genReadInsSolutionLla(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the INS Solution - LLA register on a VectorNav sensor.
VnError VnSpi_genReadImuFilteringConfiguration(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the IMU Filtering Configuration register on a VectorNav sensor...
VnError VnSpi_genWriteReferenceFrameRotation(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, mat3f c)
Generates a command to write the Reference Frame Rotation register on a VectorNav sensor...
VnError VnSpi_genReadAsyncDataOutputType(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Async Data Output Type register on a VectorNav sensor.
VnError VnSpi_genReadInsStateEcef(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the INS State - ECEF register on a VectorNav sensor.
VnError VnSpi_genReadStartupFilterBiasEstimate(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Startup Filter Bias Estimate register on a VectorNav sensor...
VnError VnSpi_genWriteAccelerationCompensation(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, mat3f c, vec3f b)
Generates a command to write the Acceleration Compensation register on a VectorNav sensor...
Represents a 4 component vector with an underlying data type of float.
Definition: vector.h:68
VnError VnSpi_genReadUserTag(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the User Tag register on a VectorNav sensor.
VnError VnSpi_genWriteVpeAccelerometerBasicTuning(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, vec3f baseTuning, vec3f adaptiveTuning, vec3f adaptiveFiltering)
Generates a command to write the VPE Accelerometer Basic Tuning register on a VectorNav sensor...
Represents a 3 component vector with an underlying data type of double.
Definition: vector.h:41
VnError VnSpi_genReadInsBasicConfiguration(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the INS Basic Configuration register on a VectorNav sensor.
VnError VnSpi_genReadAsyncDataOutputFrequency(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Async Data Output Frequency register on a VectorNav sensor...
VnError VnSpi_genReadVelocityCompensationControl(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Velocity Compensation Control register on a VectorNav sensor...
VnError VnSpi_genReadAccelerationCompensation(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Acceleration Compensation register on a VectorNav sensor...
VnError VnSpi_genWriteInsBasicConfiguration(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, uint8_t scenario, uint8_t ahrsAiding, uint8_t estBaseline, uint8_t resv2)
Generates a command to write the INS Basic Configuration register on a VectorNav sensor.
VnError VnSpi_genReadMagneticAccelerationAndAngularRates(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Magnetic, Acceleration and Angular Rates register on a VectorNav sens...
VnError VnSpi_genWriteGpsConfiguration(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, uint8_t mode, uint8_t ppsSource, uint8_t reserved1, uint8_t reserved2, uint8_t reserved3)
Generates a command to write the GPS Configuration register on a VectorNav sensor.
VnError VnSpi_genWriteAsyncDataOutputType(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, uint32_t ador)
Generates a command to write the Async Data Output Type register on a VectorNav sensor.
VnError VnSpi_genReadSynchronizationControl(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Synchronization Control register on a VectorNav sensor.
VnError VnSpi_genReadYawPitchRollTrueInertialAccelerationAndAngularRates(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Yaw, Pitch, Roll, True Inertial Acceleration and Angular Rates regist...
VnError VnSpi_genWriteSerialBaudRateWithOptions(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, uint32_t baudrate)
Generates a command to write the Serial Baud Rate register on a VectorNav sensor. ...
VnError VnSpi_genReadQuaternionMagneticAccelerationAndAngularRates(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Quaternion, Magnetic, Acceleration and Angular Rates register on a Ve...
VnError VnSpi_genReadSynchronizationStatus(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Synchronization Status register on a VectorNav sensor.
VnError VnSpi_genReadVpeMagnetometerBasicTuning(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the VPE Magnetometer Basic Tuning register on a VectorNav sensor...
VnError VnSpi_genReadYawPitchRollTrueBodyAccelerationAndAngularRates(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Yaw, Pitch, Roll, True Body Acceleration and Angular Rates register o...
VnError VnSpi_genReadFirmwareVersion(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Firmware Version register on a VectorNav sensor.
VnError VnSpi_genReadSerialBaudRate(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Serial Baud Rate register on a VectorNav sensor.
VnError VnSpi_genWriteStartupFilterBiasEstimate(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, vec3f gyroBias, vec3f accelBias, float pressureBias)
Generates a command to write the Startup Filter Bias Estimate register on a VectorNav sensor...
VnError VnSpi_genWriteSerialBaudRate(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, uint32_t baudrate)
Generates a command to write the Serial Baud Rate register on a VectorNav sensor. ...
VnError VnSpi_genReadYawPitchRoll(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Yaw Pitch Roll register on a VectorNav sensor.
VnError VnSpi_genWriteImuFilteringConfiguration(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, 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 the IMU Filtering Configuration register on a VectorNav sensor...
VnError VnSpi_genReadDeltaThetaAndDeltaVelocity(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Delta Theta and Delta Velocity register on a VectorNav sensor...
VnError VnSpi_genWriteSynchronizationControl(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, 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 the Synchronization Control register on a VectorNav sensor.
VnError VnSpi_genWriteSynchronizationStatus(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, uint32_t syncInCount, uint32_t syncInTime, uint32_t syncOutCount)
Generates a command to write the Synchronization Status register on a VectorNav sensor.
VnError VnSpi_genWriteAsyncDataOutputFrequencyWithOptions(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, uint32_t adof)
Generates a command to write the Async Data Output Frequency register on a VectorNav sensor...
VnError VnSpi_genReadGpsAntennaOffset(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the GPS Antenna Offset register on a VectorNav sensor.
VnError VnSpi_genReadCommunicationProtocolControl(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Communication Protocol Control register on a VectorNav sensor...
VnError VnSpi_genReadReferenceVectorConfiguration(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Reference Vector Configuration register on a VectorNav sensor...
Represents a 3x3 matrix with an underlying data type of float.
Definition: matrix.h:11
VnError VnSpi_genReadVpeBasicControl(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the VPE Basic Control register on a VectorNav sensor. ...
VnError VnSpi_genWriteAsyncDataOutputTypeWithOptions(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, uint32_t ador)
Generates a command to write the Async Data Output Type register on a VectorNav sensor.
VnError VnSpi_genReadMagnetometerCalibrationControl(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Magnetometer Calibration Control register on a VectorNav sensor...
VnError VnSpi_genWriteReferenceVectorConfiguration(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, uint8_t useMagModel, uint8_t useGravityModel, uint8_t resv1, uint8_t resv2, uint32_t recalcThreshold, float year, vec3d position)
Generates a command to write the Reference Vector Configuration register on a VectorNav sensor...
VnError VnSpi_genReadGpsCompassEstimatedBaseline(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the GPS Compass Estimated Baseline register on a VectorNav sensor...
VnError VnSpi_genWriteGyroCompensation(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, mat3f c, vec3f b)
Generates a command to write the Gyro Compensation register on a VectorNav sensor.
VnError VnSpi_genReadCalculatedMagnetometerCalibration(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Calculated Magnetometer Calibration register on a VectorNav sensor...
VnError VnSpi_genReadHardwareRevision(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Hardware Revision register on a VectorNav sensor. ...
VnError VnSpi_genReadMagneticMeasurements(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Magnetic Measurements register on a VectorNav sensor.
VnError VnSpi_genReadGyroCompensation(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Gyro Compensation register on a VectorNav sensor. ...
Various vector types and operations.
Definition: vector.h:14
VnError VnSpi_genReadVelocityCompensationMeasurement(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Velocity Compensation Measurement register on a VectorNav sensor...
VnError VnSpi_genReadModelNumber(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Model Number register on a VectorNav sensor.
VnError VnSpi_genWriteVelocityCompensationControl(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, uint8_t mode, float velocityTuning, float rateTuning)
Generates a command to write the Velocity Compensation Control register on a VectorNav sensor...
VnError VnSpi_genReadInsSolutionEcef(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the INS Solution - ECEF register on a VectorNav sensor.
VnError VnSpi_genReadMagnetometerCompensation(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Magnetometer Compensation register on a VectorNav sensor...
VnError VnSpi_genWriteMagneticAndGravityReferenceVectors(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, vec3f magRef, vec3f accRef)
Generates a command to write the Magnetic and Gravity Reference Vectors register on a VectorNav senso...
VnError VnSpi_genReadAttitudeQuaternion(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize)
Generates a command to read the Attitude Quaternion register on a VectorNav sensor.
VnError VnSpi_genWriteVpeMagnetometerBasicTuning(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, vec3f baseTuning, vec3f adaptiveTuning, vec3f adaptiveFiltering)
Generates a command to write the VPE Magnetometer Basic Tuning register on a VectorNav sensor...
VnError VnSpi_genWriteGpsCompassBaseline(char *buffer, size_t *size, size_t desiredLength, size_t *responseSize, vec3f position, vec3f uncertainty)
Generates a command to write the GPS Compass Baseline register on a VectorNav sensor.