|
enum | OpenPortStage { OPS_OpenPort = 1,
OPS_InitDevice = 4,
OPS_InitStart = OPS_InitDevice,
OPS_Full = OPS_OpenPort | OPS_InitDevice
} |
| Port opening stages. More...
|
|
enum | SyncLineGmt {
XSLGMT_ClockIn = 0,
XSLGMT_GnssClockIn = 1,
XSLGMT_In1 = 2,
XSLGMT_BiIn = 3,
XSLGMT_BiOut = 4,
XSLGMT_ReqData = 6,
XSLGMT_Out = 7,
XSLGMT_Gnss1Pps = 8,
XSLGMT_In2 = 9,
XSLGMT_In3 = 10,
XSLGMT_Invalid
} |
| Synchronization line identifiers for the generic motion tracker (GMT) devices, only to be used directly in Xbus messages Applies to these devices: MTx2 MTw2 MTi-1 series. More...
|
|
enum | SyncLineMk4 {
XSL4_ClockIn = 0,
XSL4_GnssClockIn = 1,
XSL4_In = 2,
XSL4_BiIn = 3,
XSL4_BiOut = 4,
XSL4_ExtTimepulseIn = 5,
XSL4_ReqData = 6,
XSL4_Gnss1Pps = 8,
XSL4_Invalid
} |
| Synchronization line identifiers for the Mk4 devices, only to be used directly in Xbus messages. More...
|
|
enum | XsAccessControlMode { XACM_None = -1,
XACM_BlackList = 0,
XACM_WhiteList = 1
} |
| Device access control modes (XsDevice::setAccessControlMode()) More...
|
|
enum | XsAlignmentFrame { XAF_Sensor,
XAF_Local
} |
| Alignment frame. More...
|
|
enum | XsCalibratedDataMode {
XCDM_None = 0,
XCDM_Acceleration = (1 << 0),
XCDM_GyroscopeData = (1 << 1),
XCDM_MagneticField = (1 << 2),
XCDM_AccGyr = XCDM_Acceleration | XCDM_GyroscopeData,
XCDM_AccMag = XCDM_Acceleration | XCDM_MagneticField,
XCDM_GyrMag = XCDM_GyroscopeData | XCDM_MagneticField,
XCDM_All = XCDM_Acceleration | XCDM_GyroscopeData | XCDM_MagneticField
} |
| Legacy calibrated data output selection flags. More...
|
|
enum | XsCanConfigIdentifier {
XCCI_LowestIdentifier = 0xA0,
XCCI_DeviceIdReq = 0xAA,
XCCI_DeviceId = 0xAB,
XCCI_GotoConfig = 0xAC,
XCCI_GotoMeasurement = 0xAD,
XCCI_Reset = 0xAE,
XCCI_HighestIdentifier
} |
| Defines the config identifiers for CAN messages. More...
|
|
enum | XsCanDataIdentifier {
XCDI_Invalid = 0x00,
XCDI_Error = 0x01,
XCDI_Warning = 0x02,
XCDI_SampleTime = 0x05,
XCDI_GroupCounter = 0x06,
XCDI_UtcTime = 0x07,
XCDI_StatusWord = 0x11,
XCDI_Quaternion = 0x21,
XCDI_EulerAngles = 0x22,
XCDI_RotationMatrix = 0x23,
XCDI_DeltaV = 0x31,
XCDI_RateOfTurn = 0x32,
XCDI_DeltaQ = 0x33,
XCDI_Acceleration = 0x34,
XCDI_FreeAcceleration = 0x35,
XCDI_MagneticField = 0x41,
XCDI_Temperature = 0x51,
XCDI_BaroPressure = 0x52,
XCDI_RateOfTurnHR = 0x61,
XCDI_AccelerationHR = 0x62,
XCDI_LatLong = 0x71,
XCDI_AltitudeEllipsoid = 0x72,
XCDI_PositionEcef_X = 0x73,
XCDI_PositionEcef_Y = 0x74,
XCDI_PositionEcef_Z = 0x75,
XCDI_Velocity = 0x76,
XCDI_Latitude = 0x77,
XCDI_Longitude = 0x78,
XCDI_GnssReceiverStatus = 0x79,
XCDI_GnssReceiverDop = 0x7A,
XCDI_EndOfGroup,
XCDI_HighestIdentifier
} |
| Defines the data identifiers for CAN messages. More...
|
|
enum | XsCanFrameFormat { XCFF_11Bit_Identifier = 0,
XCFF_29Bit_Identifier = 1
} |
| Defines the Frame format for CAN messages. More...
|
|
enum | XsConnectivityState {
XCS_Disconnected,
XCS_Rejected,
XCS_PluggedIn,
XCS_Wireless,
XCS_WirelessOutOfRange,
XCS_File,
XCS_Unknown
} |
| XsDevice connectivity state identifiers. More...
|
|
enum | XsControlLine {
XCL_DCD = 0x0001,
XCL_RD = 0x0002,
XCL_TD = 0x0004,
XCL_DTR = 0x0008,
XCL_GND = 0x0010,
XCL_DSR = 0x0020,
XCL_RTS = 0x0040,
XCL_CTS = 0x0080,
XCL_RI = 0x0100
} |
| Serial control lines. More...
|
|
enum | XsCoordinateSystem { CS_NorthWestUp,
CS_NorthEastDown
} |
| Coordinate system definition flags. More...
|
|
enum | XsDataFlags { XSDF_None = 0,
XSDF_Managed = 1,
XSDF_FixedSize = 2,
XSDF_Empty = 4
} |
| These flags define the behaviour of data contained by Xsens data structures. More...
|
|
enum | XsDataIdentifier {
XDI_None = 0x0000,
XDI_TypeMask = 0xFE00,
XDI_FullTypeMask = 0xFFF0,
XDI_FullMask = 0xFFFF,
XDI_FormatMask = 0x01FF,
XDI_DataFormatMask = 0x000F,
XDI_SubFormatMask = 0x0003,
XDI_SubFormatFloat = 0x0000,
XDI_SubFormatFp1220 = 0x0001,
XDI_SubFormatFp1632 = 0x0002,
XDI_SubFormatDouble = 0x0003,
XDI_SubFormatLeft = 0x0000,
XDI_SubFormatRight = 0x0001,
XDI_TemperatureGroup = 0x0800,
XDI_Temperature = 0x0810,
XDI_TimestampGroup = 0x1000,
XDI_UtcTime = 0x1010,
XDI_PacketCounter = 0x1020,
XDI_Itow = 0x1030,
XDI_GnssAge = 0x1040,
XDI_PressureAge = 0x1050,
XDI_SampleTimeFine = 0x1060,
XDI_SampleTimeCoarse = 0x1070,
XDI_FrameRange = 0x1080,
XDI_PacketCounter8 = 0x1090,
XDI_SampleTime64 = 0x10A0,
XDI_OrientationGroup = 0x2000,
XDI_CoordSysMask = 0x000C,
XDI_CoordSysEnu = 0x0000,
XDI_CoordSysNed = 0x0004,
XDI_CoordSysNwu = 0x0008,
XDI_Quaternion = 0x2010,
XDI_RotationMatrix = 0x2020,
XDI_EulerAngles = 0x2030,
XDI_PressureGroup = 0x3000,
XDI_BaroPressure = 0x3010,
XDI_AccelerationGroup = 0x4000,
XDI_DeltaV = 0x4010,
XDI_Acceleration = 0x4020,
XDI_FreeAcceleration = 0x4030,
XDI_AccelerationHR = 0x4040,
XDI_IndicationGroup = 0x4800,
XDI_TriggerIn1 = 0x4810,
XDI_TriggerIn2 = 0x4820,
XDI_TriggerIn3 = 0x4830,
XDI_PositionGroup = 0x5000,
XDI_AltitudeMsl = 0x5010,
XDI_AltitudeEllipsoid = 0x5020,
XDI_PositionEcef = 0x5030,
XDI_LatLon = 0x5040,
XDI_GnssGroup = 0x7000,
XDI_GnssPvtData = 0x7010,
XDI_GnssSatInfo = 0x7020,
XDI_GnssPvtPulse = 0x7030,
XDI_AngularVelocityGroup = 0x8000,
XDI_RateOfTurn = 0x8020,
XDI_DeltaQ = 0x8030,
XDI_RateOfTurnHR = 0x8040,
XDI_RawSensorGroup = 0xA000,
XDI_RawUnsigned = 0x0000,
XDI_RawSigned = 0x0001,
XDI_RawAccGyrMagTemp = 0xA010,
XDI_RawGyroTemp = 0xA020,
XDI_RawAcc = 0xA030,
XDI_RawGyr = 0xA040,
XDI_RawMag = 0xA050,
XDI_RawDeltaQ = 0xA060,
XDI_RawDeltaV = 0xA070,
XDI_RawBlob = 0xA080,
XDI_AnalogInGroup = 0xB000,
XDI_AnalogIn1 = 0xB010,
XDI_AnalogIn2 = 0xB020,
XDI_MagneticGroup = 0xC000,
XDI_MagneticField = 0xC020,
XDI_MagneticFieldCorrected = 0xC030,
XDI_SnapshotGroup = 0xC800,
XDI_RetransmissionMask = 0x0001,
XDI_RetransmissionFlag = 0x0001,
XDI_AwindaSnapshot = 0xC810,
XDI_FullSnapshot = 0xC820,
XDI_GloveSnapshotLeft = 0xC830,
XDI_GloveSnapshotRight = 0xC840,
XDI_GloveDataGroup = 0xCA00,
XDI_GloveDataLeft = 0xCA30,
XDI_GloveDataRight = 0xCA40,
XDI_VelocityGroup = 0xD000,
XDI_VelocityXYZ = 0xD010,
XDI_StatusGroup = 0xE000,
XDI_StatusByte = 0xE010,
XDI_StatusWord = 0xE020,
XDI_Rssi = 0xE040,
XDI_DeviceId = 0xE080,
XDI_LocationId = 0xE090
} |
| Defines the data identifiers. More...
|
|
enum | XsDataIdentifierValue { XDIV_MaxFrequency = XDI_MAX_FREQUENCY_VAL
} |
| Defines some convenience values for use with the data identifiers. More...
|
|
enum | XsDeviceCapability {
XDC_Invalid = 0x00000000,
XDC_Acc = 0x00000001,
XDC_Gyr = 0x00000002,
XDC_Mag = 0x00000004,
XDC_Baro = 0x00000008,
XDC_Gnss = 0x00000010,
XDC_Imu = 0x00000020,
XDC_Vru = 0x00000040,
XDC_Ahrs = 0x00000080,
XDC_GnssIns = 0x00000100,
XDC_Rtk = 0x00000200
} |
| Device capability flags. More...
|
|
enum | XsDeviceOptionFlag {
XDOF_DisableAutoStore = 0x00000001,
XDOF_DisableAutoMeasurement = 0x00000002,
XDOF_EnableBeidou = 0x00000004,
XDOF_DisableGps = 0x00000008,
XDOF_EnableAhs = 0x00000010,
XDOF_EnableOrientationSmoother = 0x00000020,
XDOF_EnableConfigurableBusId = 0x00000040,
XDOF_EnableInrunCompassCalibration = 0x00000080,
XDOF_DisableSleepMode = 0x00000100,
XDOF_EnableConfigMessageAtStartup = 0x00000200,
XDOF_EnableColdFilterResets = 0x00000400,
XDOF_EnablePositionVelocitySmoother = 0x00000800,
XDOF_EnableContinuousZRU = 0x00001000,
XDOF_EnableRawGnssInputForwarding = 0x00002000,
XDOF_None = 0x00000000,
XDOF_All = 0x7FFFFFFF
} |
| Used to enable or disable some device options. More...
|
|
enum | XsDeviceParameterIdentifier {
XDPI_Unknown = 0x0000,
XDPI_PacketErrorRate = 0x0001,
XDPI_ExtendedBuffer = 0x0002,
XDPI_UplinkTimeout = 0x0003,
XDPI_SyncLossTimeout = 0x0004
} |
| Defines the device parameter identifiers. More...
|
|
enum | XsDeviceState {
XDS_Initial,
XDS_Config,
XDS_Measurement,
XDS_WaitingForRecordingStart,
XDS_Recording,
XDS_FlushingData,
XDS_Destructing
} |
| XsDevice state identifiers. More...
|
|
enum | XsErrorMode {
XEM_Ignore = 0x0000,
XEM_IncreasePacketCounter = 0x0001,
XEM_IncreasePacketCounterAndSendError = 0x0002,
XEM_SendErrorAndGoToConfig = 0x0003,
XEM_Invalid
} |
| Error modes for use in XsDevice::setErrorMode. More...
|
|
enum | XsFloatFormat { FF_IEEE754Float,
FF_FixedPoint1220,
FF_FixedPoint1632
} |
| Legacy floating point / fixed point format options. More...
|
|
enum | XsGnssAntennaStatus {
XGAS_OpenCircuit = 0,
XGAS_ShortCircuit = 1,
XGAS_OK = 2,
XGAS_DontKnow = 3,
XGAS_Requesting = 4,
XGAS_Init = 5
} |
| Contains flags indicating the status of the GNSS antenna. More...
|
|
enum | XsGnssStatusFlag { XGSF_GnssReceiverInitialized = 0x01,
XGSF_GnssReceiverDataOk = 0x02,
XGSF_AntennaDetectionMask = 0x70
} |
| GNSS status flags. More...
|
|
enum | XsGnssStatusFlagOffset { XGSFO_OffsetGnssReceiverInitialized = 0,
XGSFO_OffsetGnssReceiverDataOk = 1,
XGSFO_OffsetAntennaDetection = 4
} |
| GNSS status flags offsets. More...
|
|
enum | XsHandId { XHI_LeftHand = 0,
XHI_RightHand = 1,
XHI_Unknown
} |
| This is an enumerator that contains the left and right hand. More...
|
|
enum | XsInfoRequest { XIR_BatteryLevel = 0,
XIR_GnssSvInfo
} |
| Information request identifiers. More...
|
|
enum | XsOption {
XSO_None = 0,
XSO_Calibrate = 0x0001,
XSO_Orientation = 0x0002,
XSO_KeepLastLiveData = 0x0004,
XSO_RetainLiveData = 0x0008,
XSO_RetainBufferedData = 0x0010,
XSO_OrientationInLiveStream = 0x0020,
XSO_OrientationInBufferedStream = 0x0040,
XSO_ApplyOrientationResetToCalData = 0x0080,
XSO_InterpolateMissingData = 0x1000,
XSO_SkipDataBundling = 0x2000,
XSO_ExpectNoRetransmissionsInFile = 0x4000,
XSO_Reserved = 0x8000
} |
| Xda options, used to control the kind of data processing done by XDA. More...
|
|
enum | XsOrientationMode { OM_None,
OM_Euler,
OM_Quaternion,
OM_Matrix
} |
| Legacy orientation output mode selection. More...
|
|
enum | XsProtocol { XP_None = 0,
XP_Xbus = 1,
XP_Nmea = 5,
XP_Rtcm = 6
} |
| Protocol types, used for MTi6x0 devices. More...
|
|
enum | XsProtocolType {
XPT_Xbus = 0,
XPT_Nmea,
XPT_ImarFsas,
XPT_ImarIfog,
XPT_ImarIfogUart
} |
| Protocol types (XsDevice::enableProtocol()) More...
|
|
enum | XsPvtDataQualityIndicator {
XPDQI_NoFix = 0,
XPDQI_DeadReckiningOnly = 1,
XPDQI_2DFix = 2,
XPDQI_3DFix = 3,
XPDQI_GnssAndDeadReck = 4,
XPDQI_TimeOnlyFix = 5
} |
| Defines the quality indicator flags of the GNSS Fix type. More...
|
|
enum | XsPvtDataUtcFlags { XPDUF_ValidDate = 0x01,
XPDUF_ValidTime = 0x02,
XPDUF_FullyResolved = 0x04,
XPDUF_ValidMag = 0x08
} |
| Define the validity flags for the UTC time. More...
|
|
enum | XsRejectReason {
XRR_Unknown = 0,
XRR_VersionMismatch = 1,
XRR_Blacklisted = 2,
XRR_StationIsDisconnecting = 3,
XRR_SystemIsOperational = 4
} |
| Identifiers for why a device's connection was rejected. More...
|
|
enum | XsResetMethod {
XRM_StoreAlignmentMatrix = 0,
XRM_Heading = 1,
XRM_Object = 3,
XRM_Inclination = XRM_Object,
XRM_Alignment = 4,
XRM_Global = XRM_Alignment,
XRM_DefaultHeading = 5,
XRM_DefaultInclination = 6,
XRM_DefaultAlignment = 7,
XRM_None
} |
| Orientation reset type. More...
|
|
enum | XsResultValue {
XRV_OK = 0,
XRV_NOBUS = 1,
XRV_BUSNOTREADY = 2,
XRV_INVALIDPERIOD = 3,
XRV_INVALIDMSG = 4,
XRV_INITBUSFAIL1 = 16,
XRV_INITBUSFAIL2 = 17,
XRV_INITBUSFAIL3 = 18,
XRV_SETBIDFAIL1 = 20,
XRV_SETBIDFAIL2 = 21,
XRV_MEASUREMENTFAIL1 = 24,
XRV_MEASUREMENTFAIL2 = 25,
XRV_MEASUREMENTFAIL3 = 26,
XRV_MEASUREMENTFAIL4 = 27,
XRV_MEASUREMENTFAIL5 = 28,
XRV_MEASUREMENTFAIL6 = 29,
XRV_TIMEROVERFLOW = 30,
XRV_BAUDRATEINVALID = 32,
XRV_INVALIDPARAM = 33,
XRV_MEASUREMENTFAIL7 = 35,
XRV_MEASUREMENTFAIL8 = 36,
XRV_WIRELESSFAIL = 37,
XRV_DEVICEERROR = 40,
XRV_DATAOVERFLOW = 41,
XRV_BUFFEROVERFLOW = 42,
XRV_EXTTRIGGERERROR = 43,
XRV_SAMPLESTREAMERROR = 44,
XRV_POWER_DIP = 45,
XRV_POWER_OVERCURRENT = 46,
XRV_OVERHEATING = 47,
XRV_BATTERYLOW = 48,
XRV_INVALIDFILTERPROFILE = 49,
XRV_INVALIDSTOREDSETTINGS = 50,
XRV_ACCESSDENIED = 51,
XRV_FILEERROR = 52,
XRV_OUTPUTCONFIGERROR = 53,
XRV_FILE_SYSTEM_CORRUPT = 54,
XRV_ERROR = 256,
XRV_NOTIMPLEMENTED = 257,
XRV_TIMEOUT = 258,
XRV_TIMEOUTNODATA = 259,
XRV_CHECKSUMFAULT = 260,
XRV_OUTOFMEMORY = 261,
XRV_NOTFOUND = 262,
XRV_UNEXPECTEDMSG = 263,
XRV_INVALIDID = 264,
XRV_INVALIDOPERATION = 265,
XRV_INSUFFICIENTSPACE = 266,
XRV_INPUTCANNOTBEOPENED = 267,
XRV_OUTPUTCANNOTBEOPENED = 268,
XRV_ALREADYOPEN = 269,
XRV_ENDOFFILE = 270,
XRV_COULDNOTREADSETTINGS = 271,
XRV_NODATA = 272,
XRV_READONLY = 273,
XRV_NULLPTR = 274,
XRV_INSUFFICIENTDATA = 275,
XRV_BUSY = 276,
XRV_INVALIDINSTANCE = 277,
XRV_DATACORRUPT = 278,
XRV_READINITFAILED = 279,
XRV_NOXMFOUND = 280,
XRV_DEVICECOUNTZERO = 282,
XRV_MTLOCATIONINVALID = 283,
XRV_INSUFFICIENTMTS = 284,
XRV_INITFUSIONFAILED = 285,
XRV_OTHER = 286,
XRV_NOFILEOPEN = 287,
XRV_NOPORTOPEN = 288,
XRV_NOFILEORPORTOPEN = 289,
XRV_PORTNOTFOUND = 290,
XRV_INITPORTFAILED = 291,
XRV_CALIBRATIONFAILED = 292,
XRV_CONFIGCHECKFAIL = 293,
XRV_ALREADYDONE = 294,
XRV_SYNC_SINGLE_SLAVE = 295,
XRV_SYNC_SECOND_MASTER = 296,
XRV_SYNC_NO_SYNC = 297,
XRV_SYNC_NO_MASTER = 298,
XRV_SYNC_DATA_MISSING = 299,
XRV_VERSION_TOO_LOW = 300,
XRV_VERSION_PROBLEM = 301,
XRV_ABORTED = 302,
XRV_UNSUPPORTED = 303,
XRV_PACKETCOUNTERMISSED = 304,
XRV_MEASUREMENTFAILED = 305,
XRV_STARTRECORDINGFAILED = 306,
XRV_STOPRECORDINGFAILED = 307,
XRV_RADIO_CHANNEL_IN_USE = 311,
XRV_UNEXPECTED_DISCONNECT = 312,
XRV_TOO_MANY_CONNECTED_TRACKERS = 313,
XRV_GOTOCONFIGFAILED = 314,
XRV_OUTOFRANGE = 315,
XRV_BACKINRANGE = 316,
XRV_EXPECTED_DISCONNECT = 317,
XRV_RESTORE_COMMUNICATION_FAILED = 318,
XRV_RESTORE_COMMUNICATION_STOPPED = 319,
XRV_EXPECTED_CONNECT = 320,
XRV_IN_USE = 321,
XRV_PERFORMANCE_WARNING = 322,
XRV_PERFORMANCE_OK = 323,
XRV_SHUTTINGDOWN = 400,
XRV_GNSSCONFIGURATIONERROR = 401,
XRV_GNSSCOMMTIMEOUT = 402,
XRV_GNSSERROR = 403,
XRV_DEVICE_NOT_CALIBRATED = 404,
XRV_GNSSCONNECTIONLOST = 405,
XRV_GNSSLOWINPUTRATE = 406,
XRV_GNSSINCOMPLETEDATASET = 407
} |
| Xsens result values. More...
|
|
enum | XsSatInfoFlags {
XSIF_SignalQualityIndicator_Mask = 0x7,
XSIF_SignalQualityIndicator_NoSignal = 0x0,
XSIF_SignalQualityIndicator_Searching = 0x1,
XSIF_SignalQualityIndicator_Acquired = 0x2,
XSIF_SignalQualityIndicator_Unusable = 0x3,
XSIF_SignalQualityIndicator_CodeTimeOk = 0x4,
XSIF_SignalQualityIndicator_CodeCarrierTimeOk1 = 0x5,
XSIF_SignalQualityIndicator_CodeCarrierTimeOk2 = 0x6,
XSIF_SignalQualityIndicator_CodeCarrierTimeOk3 = 0x7,
XSIF_UsedForNavigation_Mask = 0x8,
XSIF_UsedForNavigation_Used = 0x8,
XSIF_HealthFlag_Mask = 0x30,
XSIF_HealthFlag_Unknown = 0x00,
XSIF_HealthFlag_Healthy = 0x10,
XSIF_HealthFlag_Unhealthy = 0x20,
XSIF_Differential_Mask = 0x40,
XSIF_Differential_Available = 0x40
} |
| Xsens Satellite Info Flags. More...
|
|
enum | XsSelfTestFlag {
XSTF_X = 0x01,
XSTF_Y = 0x02,
XSTF_Z = 0x04,
XSTF_AccShift = 0,
XSTF_AccX = XSTF_X << XSTF_AccShift,
XSTF_AccY = XSTF_Y << XSTF_AccShift,
XSTF_AccZ = XSTF_Z << XSTF_AccShift,
XSTF_GyrShift = 3,
XSTF_GyrX = XSTF_X << XSTF_GyrShift,
XSTF_GyrY = XSTF_Y << XSTF_GyrShift,
XSTF_GyrZ = XSTF_Z << XSTF_GyrShift,
XSTF_MagShift = 6,
XSTF_MagX = XSTF_X << XSTF_MagShift,
XSTF_MagY = XSTF_Y << XSTF_MagShift,
XSTF_MagZ = XSTF_Z << XSTF_MagShift,
XSTF_Baro = 1 << 9,
XSTF_Gnss = 1 << 10,
XSTF_Battery = 1 << 11,
XSTF_Flash = 1 << 12,
XSTF_Button = 1 << 13,
XSTF_Sync = 1 << 14
} |
| Enumeration of bits that describe whether the various self-tests succeeded. More...
|
|
enum | XsStatusFlag {
XSF_SelfTestOk = 0x01,
XSF_OrientationValid = 0x02,
XSF_GpsValid = 0x04,
XSF_NoRotationMask = 0x18,
XSF_NoRotationAborted = 0x10,
XSF_NoRotationSamplesRejected = 0x08,
XSF_NoRotationRunningNormally = 0x18,
XSF_RepresentativeMotion = 0x20,
XSF_ExternalClockSynced = 0x40,
XSF_FilterInputStart = 0x80,
XSF_ClipAccX = 0x00000100,
XSF_ClipAccY = 0x00000200,
XSF_ClipAccZ = 0x00000400,
XSF_ClipGyrX = 0x00000800,
XSF_ClipGyrY = 0x00001000,
XSF_ClipGyrZ = 0x00002000,
XSF_ClipMagX = 0x00004000,
XSF_ClipMagY = 0x00008000,
XSF_ClipMagZ = 0x00010000,
XSF_Retransmitted = 0x00040000,
XSF_ClippingDetected = 0x00080000,
XSF_Interpolated = 0x00100000,
XSF_SyncIn = 0x00200000,
XSF_SyncOut = 0x00400000,
XSF_FilterMode = 0x03800000,
XSF_HaveGnssTimePulse = 0x04000000,
XSF_RtkStatus = 0x18000000
} |
| Status flags. More...
|
|
enum | XsStatusFlagOffset {
XSFO_OffsetSelfTestOk = 0,
XSFO_OffsetOrientationValid = 1,
XSFO_OffsetGpsValid = 2,
XSFO_OffsetNoRotation = 3,
XSFO_OffsetRepresentativeMotion = 5,
XSFO_OffsetExternalClockSynced = 6,
XSFO_OffsetClipAccX = 8,
XSFO_OffsetClipAccY = 9,
XSFO_OffsetClipAccZ = 10,
XSFO_OffsetClipGyrX = 11,
XSFO_OffsetClipGyrY = 12,
XSFO_OffsetClipGyrZ = 13,
XSFO_OffsetClipMagX = 14,
XSFO_OffsetClipMagY = 15,
XSFO_OffsetClipMagZ = 16,
XSFO_Retransmitted = 18,
XSFO_ClippingDetected = 19,
XSFO_Interpolated = 20,
XSFO_SyncIn = 21,
XSFO_SyncOut = 22,
XSFO_FilterMode = 23,
XSFO_FilterModeNrOfBits = 3,
XSFO_HaveGnssTimePulse = 26,
XSFO_RtkStatus = 27,
XSFO_RtkStatusNrOfBits = 2
} |
| Status flag bit offsets. More...
|
|
enum | XsStringOutputType {
XSOT_None = 0x0000,
XSOT_HCHDM = 0x0001,
XSOT_HCHDG = 0x0002,
XSOT_TSS2 = 0x0004,
XSOT_PHTRO = 0x0008,
XSOT_PRDID = 0x0010,
XSOT_EM1000 = 0x0020,
XSOT_PSONCMS = 0x0040,
XSOT_HCMTW = 0x0080,
XSOT_HEHDT = 0x0100,
XSOT_HEROT = 0x0200,
XSOT_GPGGA = 0x0400,
XSOT_PTCF = 0x0800,
XSOT_XSVEL = 0x1000,
XSOT_GPZDA = 0x2000,
XSOT_GPRMC = 0x4000
} |
| String output types. More...
|
|
enum | XsSyncFunction {
XSF_StartRecordingIn,
XSF_StopRecordingIn,
XSF_ResetTimer,
XSF_TriggerIndication,
XSF_IntervalTransitionMeasurement,
XSF_IntervalTransitionRecording,
XSF_GotoOperational,
XSF_SampleAndSend,
XSF_SendLatest,
XSF_ClockBiasEstimation,
XSF_PulseWithModulation,
XSF_StartSampling,
XSF_StartRecordingOut,
XSF_StopRecordingOut,
XSF_Gnss1Pps,
XSF_BusSync,
XSF_Invalid,
XSF_Count = XSF_Invalid
} |
| Actions to be taken on input triggers. More...
|
|
enum | XsSyncLine {
XSL_Inputs,
XSL_In1 = XSL_Inputs,
XSL_In2,
XSL_In3,
XSL_Bi1In,
XSL_ClockIn,
XSL_CtsIn,
XSL_GnssClockIn,
XSL_ExtTimepulseIn,
XSL_ReqData,
XSL_Gnss1Pps,
XSL_Outputs,
XSL_Out1 = XSL_Outputs,
XSL_Out2,
XSL_Bi1Out,
XSL_RtsOut,
XSL_Invalid
} |
| Synchronization line identifiers. More...
|
|
enum | XsSyncPolarity {
XSP_None = 0,
XSP_RisingEdge = 1,
XSP_PositivePulse = XSP_RisingEdge,
XSP_FallingEdge = 2,
XSP_NegativePulse = XSP_FallingEdge,
XSP_Both
} |
| Signal polarity. More...
|
|
enum | XsSyncRole { XSR_Slave,
XSR_None,
XSR_MasterSlave,
XSR_Master
} |
| Synchronization roles. More...
|
|
enum | XsThreadPriority {
XS_THREAD_PRIORITY_LOWEST = 0,
XS_THREAD_PRIORITY_LOWER = 1,
XS_THREAD_PRIORITY_LOW = 2,
XS_THREAD_PRIORITY_NORMAL = 3,
XS_THREAD_PRIORITY_HIGH = 4,
XS_THREAD_PRIORITY_HIGHER = 5,
XS_THREAD_PRIORITY_HIGHEST = 6
} |
| Thread priorities for xsSetThreadPriority() and xsGetThreadPriority() More...
|
|
enum | XsXbusMessageId {
XMID_InvalidMessage = 0x00,
XMID_ReqDid = 0x00,
XMID_DeviceId = 0x01,
XMID_Initbus = 0x02,
XMID_InitBusResults = 0x03,
XMID_ReqPeriod = 0x04,
XMID_ReqPeriodAck = 0x05,
XMID_SetPeriod = 0x04,
XMID_SetPeriodAck = 0x05,
XMID_SetBid = 0x06,
XMID_SetBidAck = 0x07,
XMID_AutoStart = 0x06,
XMID_AutoStartAck = 0x07,
XMID_BusPower = 0x08,
XMID_BusPowerAck = 0x09,
XMID_ReqDataLength = 0x0A,
XMID_DataLength = 0x0B,
XMID_ReqConfiguration = 0x0C,
XMID_Configuration = 0x0D,
XMID_RestoreFactoryDef = 0x0E,
XMID_RestoreFactoryDefAck = 0x0F,
XMID_GotoMeasurement = 0x10,
XMID_GotoMeasurementAck = 0x11,
XMID_ReqFirmwareRevision = 0x12,
XMID_FirmwareRevision = 0x13,
XMID_ReqUniqueId = 0x14,
XMID_UniqueId = 0x15,
XMID_ReqBodypackMode = 0x16,
XMID_ReqBodypackAck = 0x17,
XMID_SetBodypackMode = 0x16,
XMID_SetBodypackModeAck = 0x17,
XMID_ReqBaudrate = 0x18,
XMID_ReqBaudrateAck = 0x19,
XMID_SetBaudrate = 0x18,
XMID_SetBaudrateAck = 0x19,
XMID_ReqProductVariant = 0x1A,
XMID_ProductVariant = 0x1B,
XMID_ReqProductCode = 0x1C,
XMID_ProductCode = 0x1D,
XMID_ReqHardwareVersion = 0x1E,
XMID_HardwareVersion = 0x1F,
XMID_ReqProcessingFlags = 0x20,
XMID_ReqProcessingFlagsAck = 0x21,
XMID_SetProcessingFlags = 0x20,
XMID_SetProcessingFlagsAck = 0x21,
XMID_SetNoRotation = 0x22,
XMID_SetNoRotationAck = 0x23,
XMID_RunSelfTest = 0x24,
XMID_SelfTestResults = 0x25,
XMID_ReqInputTrigger = 0x26,
XMID_ReqInputTriggerAck = 0x27,
XMID_SetInputTrigger = 0x26,
XMID_SetInputTriggerAck = 0x27,
XMID_ReqOutputTrigger = 0x28,
XMID_ReqOutputTriggerAck = 0x29,
XMID_SetOutputTrigger = 0x28,
XMID_SetOutputTriggerAck = 0x29,
XMID_SetSyncStationMode = 0x2A,
XMID_SetSyncStationModeAck = 0x2B,
XMID_ReqSyncStationMode = 0x2A,
XMID_ReqSyncStationModeAck = 0x2B,
XMID_SetSyncConfiguration = 0x2C,
XMID_SetSyncConfigurationAck = 0x2D,
XMID_ReqSyncConfiguration = 0x2C,
XMID_SyncConfiguration = 0x2D,
XMID_DriverDisconnect = 0x2E,
XMID_DriverDisconnectAck = 0x2F,
XMID_GotoConfig = 0x30,
XMID_GotoConfigAck = 0x31,
XMID_MtData = 0x32,
XMID_BusData = 0x32,
XMID_PrepareData = 0x32,
XMID_ReqData = 0x34,
XMID_ReqDataAck = 0x35,
XMID_MtData2 = 0x36,
XMID_MtData2Ack = 0x37,
XMID_RequestControl = 0x38,
XMID_RequestControlAck = 0x39,
XMID_SetDataPort = 0x3A,
XMID_SetDataPortAck = 0x3B,
XMID_ReqRetransmission = 0x3C,
XMID_ReqRetransmissionAck = 0x3D,
XMID_Wakeup = 0x3E,
XMID_WakeupAck = 0x3F,
XMID_Reset = 0x40,
XMID_ResetAck = 0x41,
XMID_Error = 0x42,
XMID_Warning = 0x43,
XMID_XmPowerOff = 0x44,
XMID_MasterIndication = 0x46,
XMID_XsbData = 0x47,
XMID_ReqOptionFlags = 0x48,
XMID_ReqOptionFlagsAck = 0x49,
XMID_SetOptionFlags = 0x48,
XMID_SetOptionFlagsAck = 0x49,
XMID_ReqStealthMode = 0x4A,
XMID_StealthMode = 0x4B,
XMID_SetStealthMode = 0x4A,
XMID_SetStealthModeAck = 0x4B,
XMID_UserInterface = 0x4C,
XMID_UserInterfaceAck = 0x4D,
XMID_EndOfRecording = 0x4E,
XMID_EndOfRecordingAck = 0x4F,
XMID_GotoTransparentMode = 0x50,
XMID_GotoTransparentModeAck = 0x51,
XMID_ReqDeviceCapabilities = 0x52,
XMID_DeviceCapabilities = 0x53,
XMID_DiscardRetransmissions = 0x54,
XMID_DiscardRetransmissionsAck = 0x55,
XMID_RunFactoryTest = 0x56,
XMID_FactoryTestResults = 0x57,
XMID_FactoryTestConnect = 0x58,
XMID_FactoryTestConnectAck = 0x59,
XMID_SetDataOutputDelay = 0x5A,
XMID_SetDataOutputDelayAck = 0x5B,
XMID_SetBodypackConfigFile = 0x5C,
XMID_SetBodypackConfigFileAck = 0x5D,
XMID_ReqObrStatus = 0x5E,
XMID_ObrStatus = 0x5F,
XMID_SetUtcTime = 0x60,
XMID_ReqUtcTime = 0x60,
XMID_SetUtcTimeAck = 0x61,
XMID_UtcTime = 0x61,
XMID_FactoryTestSensorTiming = 0x60,
XMID_FactoryTestSensorTimingResults = 0x61,
XMID_ReqAvailableFilterProfiles = 0x62,
XMID_AvailableFilterProfiles = 0x63,
XMID_ReqFilterProfile = 0x64,
XMID_ReqFilterProfileAck = 0x65,
XMID_SetFilterProfile = 0x64,
XMID_SetFilterProfileAck = 0x65,
XMID_ReqGravityMagnitude = 0x66,
XMID_ReqGravityMagnitudeAck = 0x67,
XMID_SetGravityMagnitude = 0x66,
XMID_SetGravityMagnitudeAck = 0x67,
XMID_ReqGnssLeverArm = 0x68,
XMID_ReqGnssLeverArmAck = 0x69,
XMID_SetGnssLeverArm = 0x68,
XMID_SetGnssLeverArmAck = 0x69,
XMID_ReqMagneticField = 0x6A,
XMID_ReqMagneticFieldAck = 0x6B,
XMID_SetMagneticField = 0x6A,
XMID_SetMagneticFieldAck = 0x6B,
XMID_ReqReplayMode = 0x6C,
XMID_ReqReplayModeAck = 0x6D,
XMID_SetReplayMode = 0x6C,
XMID_SetReplayModeAck = 0x6D,
XMID_ReqLatLonAlt = 0x6E,
XMID_ReqLatLonAltAck = 0x6F,
XMID_SetLatLonAlt = 0x6E,
XMID_SetLatLonAltAck = 0x6F,
XMID_KeepAlive = 0x70,
XMID_KeepAliveAck = 0x71,
XMID_CloseConnection = 0x72,
XMID_CloseConnectionAck = 0x73,
XMID_IccCommand = 0x74,
XMID_IccCommandAck = 0x75,
XMID_ReqGnssPlatform = 0x76,
XMID_ReqGnssPlatformAck = 0x77,
XMID_SetGnssPlatform = 0x76,
XMID_SetGnssPlatformAck = 0x77,
XMID_ReqConnectionSettings = 0x78,
XMID_ReqConnectionSettingsAck = 0x79,
XMID_SetConnectionSettings = 0x78,
XMID_SetConnectionSettingsAck = 0x79,
XMID_BodyPackBundle = 0x7A,
XMID_BodyPackBundleAck = 0x7B,
XMID_ReqStationOptions = 0x7C,
XMID_ReqStationOptionsAck = 0x7D,
XMID_ReqErrorReport = 0x7E,
XMID_ErrorReport = 0x7F,
XMID_ReqXmErrorMode = 0x82,
XMID_ReqXmErrorModeAck = 0x83,
XMID_SetXmErrorMode = 0x82,
XMID_SetXmErrorModeAck = 0x83,
XMID_ReqBufferSize = 0x84,
XMID_ReqBufferSizeAck = 0x85,
XMID_SetBufferSize = 0x84,
XMID_SetBufferSizeAck = 0x85,
XMID_ReqHeading = 0x82,
XMID_ReqHeadingAck = 0x83,
XMID_SetHeading = 0x82,
XMID_SetHeadingAck = 0x83,
XMID_ReqLocationId = 0x84,
XMID_ReqLocationIdAck = 0x85,
XMID_SetLocationId = 0x84,
XMID_SetLocationIdAck = 0x85,
XMID_ReqExtOutputMode = 0x86,
XMID_ReqExtOutputModeAck = 0x87,
XMID_SetExtOutputMode = 0x86,
XMID_SetExtOutputModeAck = 0x87,
XMID_ReqBatteryLevel = 0x88,
XMID_Batterylevel = 0x89,
XMID_ReqInitTrackMode = 0x88,
XMID_ReqInitTrackModeAck = 0x89,
XMID_SetInitTrackMode = 0x88,
XMID_SetInitTrackModeAck = 0x89,
XMID_ReqMasterSettings = 0x8A,
XMID_MasterSettings = 0x8B,
XMID_StoreFilterState = 0x8A,
XMID_StoreFilterStateAck = 0x8B,
XMID_ReqPortConfig = 0x8C,
XMID_SetPortConfig = 0x8C,
XMID_PortConfig = 0x8D,
XMID_SetPortConfigAck = 0x8D,
XMID_ReqStringOutputType = 0x8E,
XMID_ReqStringOutputTypeAck = 0x8F,
XMID_SetStringOutputType = 0x8E,
XMID_SetStringOutputTypeAck = 0x8F,
XMID_ReqStringOutputConfig = 0x8E,
XMID_ReqStringOutputConfigAck = 0x8F,
XMID_SetStringOutputConfig = 0x8E,
XMID_SetStringOutputConfigAck = 0x8F,
XMID_ReqEmts = 0x90,
XMID_EmtsData = 0x91,
XMID_UpdateFilterProfile = 0x92,
XMID_UpdateFilterProfileAck = 0x93,
XMID_RestoreEmts = 0x94,
XMID_RestoreEmtsAck = 0x95,
XMID_StoreEmts = 0x96,
XMID_StoreEmtsAck = 0x97,
XMID_UnlockMaintenanceMode = 0x98,
XMID_UnlockMaintenanceModeAck = 0x99,
XMID_ClockSyncCommand = 0x9A,
XMID_ClockSyncCommandAck = 0x9B,
XMID_ReqActiveClockCorrection = 0x9C,
XMID_ActiveClockCorrection = 0x9D,
XMID_StoreActiveClockCorrection = 0x9E,
XMID_StoreActiveClockCorrectionAck = 0x9F,
XMID_ReqFilterSettings = 0xA0,
XMID_ReqFilterSettingsAck = 0xA1,
XMID_SetFilterSettings = 0xA0,
XMID_SetFilterSettingsAck = 0xA1,
XMID_ReqAmd = 0xA2,
XMID_ReqAmdAck = 0xA3,
XMID_SetAmd = 0xA2,
XMID_SetAmdAck = 0xA3,
XMID_ResetOrientation = 0xA4,
XMID_ResetOrientationAck = 0xA5,
XMID_ReqGnssStatus = 0xA6,
XMID_GnssStatus = 0xA7,
XMID_AdjustUtcTime = 0xA8,
XMID_AdjustUtcTimeAck = 0xA9,
XMID_ReqAssemblyId = 0xAA,
XMID_SetAssemblyId = 0xAA,
XMID_AssemblyId = 0xAB,
XMID_SetAssemblyIdAck = 0xAB,
XMID_ReqGnssReceiverSettings = 0xAC,
XMID_ReqGnssReceiverSettingsAck = 0xAD,
XMID_SetGnssReceiverSettings = 0xAC,
XMID_SetGnssReceiverSettingsAck = 0xAD,
XMID_ReqAccessControlList = 0xAE,
XMID_AccessControlList = 0xAF,
XMID_SetAccessControlList = 0xAE,
XMID_SetAccessControlListAck = 0xAF,
XMID_ScanChannels = 0xB0,
XMID_ScanChannelsAck = 0xB1,
XMID_EnableMaster = 0xB2,
XMID_EnableMasterAck = 0xB3,
XMID_DisableMaster = 0xB4,
XMID_DisableMasterAck = 0xB5,
XMID_ReqRadioChannel = 0xB6,
XMID_ReqRadioChannelAck = 0xB7,
XMID_SetClientPriority = 0xB8,
XMID_SetClientPriorityAck = 0xB9,
XMID_ReqClientPriority = 0xB8,
XMID_ReqClientPriorityAck = 0xB9,
XMID_SetWirelessConfig = 0xBA,
XMID_SetWirelessConfigAck = 0xBB,
XMID_ReqWirelessConfig = 0xBA,
XMID_ReqWirelessConfigAck = 0xBB,
XMID_UpdateBias = 0xBC,
XMID_UpdateBiasAck = 0xBD,
XMID_ToggleIoPins = 0xBE,
XMID_ToggleIoPinsAck = 0xBF,
XMID_GotoOperational = 0xC0,
XMID_GotoOperationalAck = 0xC1,
XMID_SetTransportMode = 0xC2,
XMID_SetTransportModeAck = 0xC3,
XMID_ReqTransportMode = 0xC2,
XMID_ReqTransportModeAck = 0xC3,
XMID_AcceptMtw = 0xC4,
XMID_AcceptMtwAck = 0xC5,
XMID_RejectMtw = 0xC6,
XMID_RejectMtwAck = 0xC7,
XMID_InfoRequest = 0xC8,
XMID_InfoRequestAck = 0xC9,
XMID_ReqFrameRates = 0xCA,
XMID_ReqFrameRatesAck = 0xCB,
XMID_StartRecording = 0xCC,
XMID_StartRecordingAck = 0xCD,
XMID_StopRecording = 0xCE,
XMID_StopRecordingAck = 0xCF,
XMID_ReqOutputConfiguration = 0xC0,
XMID_ReqOutputConfigurationAck = 0xC1,
XMID_SetOutputConfiguration = 0xC0,
XMID_SetOutputConfigurationAck = 0xC1,
XMID_ReqOutputMode = 0xD0,
XMID_ReqOutputModeAck = 0xD1,
XMID_SetOutputMode = 0xD0,
XMID_SetOutputModeAck = 0xD1,
XMID_ReqOutputSettings = 0xD2,
XMID_ReqOutputSettingsAck = 0xD3,
XMID_SetOutputSettings = 0xD2,
XMID_SetOutputSettingsAck = 0xD3,
XMID_ReqOutputSkipFactor = 0xD4,
XMID_ReqOutputSkipFactorAck = 0xD5,
XMID_SetOutputSkipFactor = 0xD4,
XMID_SetOutputSkipFactorAck = 0xD5,
XMID_SetInitialHeading = 0xD6,
XMID_SetInitialHeadingAck = 0xD7,
XMID_ReqErrorMode = 0xDA,
XMID_ReqErrorModeAck = 0xDB,
XMID_SetErrorMode = 0xDA,
XMID_SetErrorModeAck = 0xDB,
XMID_ReqTransmitDelay = 0xDC,
XMID_ReqTransmitDelayAck = 0xDD,
XMID_SetTransmitDelay = 0xDC,
XMID_SetTransmitDelayAck = 0xDD,
XMID_SetMfmResults = 0xDE,
XMID_SetMfmResultsAck = 0xDF,
XMID_ReqObjectAlignment = 0xE0,
XMID_ReqObjectAlignmentAck = 0xE1,
XMID_SetObjectAlignment = 0xE0,
XMID_SetObjectAlignmentAck = 0xE1,
XMID_ForwardGnssData = 0xE2,
XMID_ForwardGnssDataAck = 0xE3,
XMID_ReqCanConfig = 0xE6,
XMID_SetCanConfig = 0xE6,
XMID_CanConfig = 0xE7,
XMID_SetCanConfigAck = 0xE7,
XMID_ReqCanOutputConfig = 0xE8,
XMID_SetCanOutputConfig = 0xE8,
XMID_CanOutputConfig = 0xE9,
XMID_SetCanOutputConfigAck = 0xE9,
XMID_ReqAlignmentRotation = 0xEC,
XMID_ReqAlignmentRotationAck = 0xED,
XMID_SetAlignmentRotation = 0xEC,
XMID_SetAlignmentRotationAck = 0xED,
XMID_ExtensionReserved1 = 0xEE,
XMID_ExtensionReserved2 = 0xEF,
XMID_SetDeviceIdContext = 0xFE,
XMID_SetDeviceIdContextAck = 0xFF
} |
| Xsens Xbus Message Identifiers. More...
|
|