Macros | Typedefs | Enumerations
Global enumerations

Macros

#define XSO_All   ((XsOption)0xFFFF)
 All options, note that setting 'all options' is not valid, but it is useful for clearing all options. More...
 

Typedefs

typedef enum XsBaudRate XsBaudRate
 Communication speed. More...
 
typedef enum XsBaudRate XsBaudRate
 Communication speed. More...
 

Enumerations

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...
 

Detailed Description

Macro Definition Documentation

◆ XSO_All

#define XSO_All   ((XsOption)0xFFFF)

All options, note that setting 'all options' is not valid, but it is useful for clearing all options.

Definition at line 95 of file xsoption.h.

Typedef Documentation

◆ XsBaudRate [1/2]

enum XSNOCOMEXPORT XsBaudRate

Communication speed.

Definition at line 151 of file xsbaudrate.h.

◆ XsBaudRate [2/2]

enum XSNOCOMEXPORT XsBaudRate

Communication speed.

Definition at line 81 of file xsbaud.h.

Enumeration Type Documentation

◆ OpenPortStage

Port opening stages.

Opening a communication port is done in 3 stages. In some cases not all stages should be performed or at least not all at the same time. For these cases, this enumeration supplies the option of selecting which stages should be performed.

Enumerator
OPS_OpenPort 
OPS_InitDevice 
OPS_InitStart 
OPS_Full 

Definition at line 76 of file openportstage.h.

◆ SyncLineGmt

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.

Enumerator
XSLGMT_ClockIn 

External clock sync XSL_ClockIn.

XSLGMT_GnssClockIn 

GNSS clock sync XSL_GnssClockIn.

XSLGMT_In1 

Sync in 1 XSL_In1.

XSLGMT_BiIn 

Bidirectional sync line, configured as input XSL_Bi1In.

XSLGMT_BiOut 

Bidirectional sync line, configured as output XSL_Bi1Out.

XSLGMT_ReqData 

Serial data sync option, use XMID_ReqData message id for this XSL_ReqData.

XSLGMT_Out 

Sync out 1 XSL_Out1.

XSLGMT_Gnss1Pps 

GNSS 1PPS pulse sync in line XSL_Gnss1Pps.

XSLGMT_In2 

Sync in 2 XSL_In2.

XSLGMT_In3 

Sync in 3.

XSLGMT_Invalid 

Definition at line 79 of file synclinegmt.h.

◆ SyncLineMk4

Synchronization line identifiers for the Mk4 devices, only to be used directly in Xbus messages.

Enumerator
XSL4_ClockIn 

External clock sync XSL_ClockIn.

XSL4_GnssClockIn 

GNSS clock sync XSL_GnssClockIn.

XSL4_In 

Send data line XSL_In1.

XSL4_BiIn 

Bidirectional sync line, configured as input XSL_Bi1In.

XSL4_BiOut 

Bidirectional sync line, configured as output XSL_Bi1Out.

XSL4_ExtTimepulseIn 

External Timepulse input XSL_ExtTimepulseIn.

XSL4_ReqData 

Serial data sync option, use XMID_ReqData message id for this XSL_ReqData.

XSL4_Gnss1Pps 

GNSS 1PPS sync line XSL_Gnss1Pps.

XSL4_Invalid 

Definition at line 74 of file synclinemk4.h.

◆ XsAccessControlMode

Device access control modes (XsDevice::setAccessControlMode())

Enumerator
XACM_None 

No access control mode defined, do not use in 'set' function. Devices that support Access Control are always in either BlackList or WhiteList mode and will return an error if you try to set the Access Control Mode to XACM_None.

XACM_BlackList 

Accept all device connections, explicit rejection through blacklist.

XACM_WhiteList 

Decline all device connections, explicit acceptance through whitelist.

Definition at line 74 of file xsaccesscontrolmode.h.

◆ XsAlignmentFrame

Alignment frame.

Enumerator
XAF_Sensor 

Sensor alignment frame.

XAF_Local 

Local alignment frame.

Definition at line 74 of file xsalignmentframe.h.

◆ XsCalibratedDataMode

Legacy calibrated data output selection flags.

Enumerator
XCDM_None 
XCDM_Acceleration 
XCDM_GyroscopeData 
XCDM_MagneticField 
XCDM_AccGyr 
XCDM_AccMag 
XCDM_GyrMag 
XCDM_All 

Definition at line 72 of file xscalibrateddatamode.h.

◆ XsCanConfigIdentifier

Defines the config identifiers for CAN messages.

Note
Have to be higher than XCDI_HighestIdentifier in xscandataidentifier.h
Enumerator
XCCI_LowestIdentifier 
XCCI_DeviceIdReq 
XCCI_DeviceId 
XCCI_GotoConfig 
XCCI_GotoMeasurement 
XCCI_Reset 
XCCI_HighestIdentifier 

Definition at line 80 of file xscanconfigidentifier.h.

◆ XsCanDataIdentifier

Defines the data identifiers for CAN messages.

Enumerator
XCDI_Invalid 
XCDI_Error 
XCDI_Warning 
XCDI_SampleTime 

Sample Time in us.

XCDI_GroupCounter 
XCDI_UtcTime 
XCDI_StatusWord 
XCDI_Quaternion 
XCDI_EulerAngles 
XCDI_RotationMatrix 
XCDI_DeltaV 

DeltaV SDI data output.

XCDI_RateOfTurn 
XCDI_DeltaQ 

DeltaQ SDI data.

XCDI_Acceleration 
XCDI_FreeAcceleration 
XCDI_MagneticField 

Magnetic field data in a.u.

XCDI_Temperature 

Temperature.

XCDI_BaroPressure 

Pressure output recorded from the barometer.

XCDI_RateOfTurnHR 
XCDI_AccelerationHR 
XCDI_LatLong 
XCDI_AltitudeEllipsoid 
XCDI_PositionEcef_X 
XCDI_PositionEcef_Y 
XCDI_PositionEcef_Z 
XCDI_Velocity 
XCDI_Latitude 
XCDI_Longitude 
XCDI_GnssReceiverStatus 
XCDI_GnssReceiverDop 
XCDI_EndOfGroup 
XCDI_HighestIdentifier 

Definition at line 82 of file xscandataidentifier.h.

◆ XsCanFrameFormat

Defines the Frame format for CAN messages.

Enumerator
XCFF_11Bit_Identifier 
XCFF_29Bit_Identifier 

Definition at line 78 of file xscanframeformat.h.

◆ XsConnectivityState

XsDevice connectivity state identifiers.

Enumerator
XCS_Disconnected 

Device has disconnected, only limited informational functionality is available.

XCS_Rejected 

Device has been rejected and is disconnected, only limited informational functionality is available.

XCS_PluggedIn 

Device is connected through a cable.

XCS_Wireless 

Device is connected wirelessly.

XCS_WirelessOutOfRange 

Device was connected wirelessly and is currently out of range.

XCS_File 

Device is reading from a file.

XCS_Unknown 

Device is in an unknown state.

Definition at line 78 of file xsconnectivitystate.h.

◆ XsControlLine

Serial control lines.

Enumerator
XCL_DCD 

pin 1: Carrier Detect

XCL_RD 

pin 2: Received Data

XCL_TD 

pin 3: Transmitted Data

XCL_DTR 

pin 4: Data Terminal Ready

XCL_GND 

pin 5: Common Ground

XCL_DSR 

pin 6: Data Set Ready

XCL_RTS 

pin 7: Request To Send

XCL_CTS 

pin 8: Clear To Send

XCL_RI 

pin 9: Ring Indicator

Definition at line 72 of file xscontrolline.h.

◆ XsCoordinateSystem

Coordinate system definition flags.

Enumerator
CS_NorthWestUp 
CS_NorthEastDown 

Definition at line 72 of file xscoordinatesystem.h.

◆ XsDataFlags

These flags define the behaviour of data contained by Xsens data structures.

Normally, the user should never need to use these directly.

Enumerator
XSDF_None 

No flag set.

XSDF_Managed 

The contained data should be managed (freed) by the object, when false, the object assumes the memory is freed by some other process after its destruction.

XSDF_FixedSize 

The contained data points to a fixed-size buffer, this allows creation of dynamic objects on the stack without malloc/free overhead.

XSDF_Empty 

The object contains undefined data / should be considered empty. Usually only relevant when XSDF_FixedSize is also set, as otherwise the data pointer will be NULL and empty-ness is implicit.

Definition at line 107 of file xstypedefs.h.

◆ XsDataIdentifier

Defines the data identifiers.

The list of standard data identifiers is shown below. The last positions in the data identifier depends on the configuration of the data. For example 0x4020 is 3D acceleration in single precision float format, where 0x4022 is 3D acceleration in fixed point 16.32 format.

Refer to the Low Level Communication Protocol for more details.

Enumerator
XDI_None 

Empty datatype.

XDI_TypeMask 

Mask for checking the group which a dataidentifier belongs to, Eg. XDI_TimestampGroup or XDI_OrientationGroup.

XDI_FullTypeMask 

Mask to get the type of data, without the data format.

XDI_FullMask 

Complete mask to get entire data identifier.

XDI_FormatMask 

Mask for getting the data id without checking the group.

XDI_DataFormatMask 

Mask for extracting just the data format /sa XDI_SubFormat.

XDI_SubFormatMask 

Determines, float, fp12.20, fp16.32, double output... (where applicable)

XDI_SubFormatFloat 

Floating point format.

XDI_SubFormatFp1220 

Fixed point 12.20.

XDI_SubFormatFp1632 

Fixed point 16.32.

XDI_SubFormatDouble 

Double format.

XDI_SubFormatLeft 

Left side data (ie XDI_GloveData for the left hand)

XDI_SubFormatRight 

Right side data (ie XDI_GloveData for the right hand)

XDI_TemperatureGroup 

Group for temperature outputs.

XDI_Temperature 

Temperature.

XDI_TimestampGroup 

Group for time stamp related outputs.

XDI_UtcTime 

Utc time from the GNSS receiver.

XDI_PacketCounter 

Packet counter, increments every packet.

XDI_Itow 

Itow. Time Of Week from the GNSS receiver.

XDI_GnssAge 

Gnss age from the GNSS receiver.

XDI_PressureAge 

Age of a pressure sample, in packet counts.

XDI_SampleTimeFine 

Sample Time Fine.

XDI_SampleTimeCoarse 

Sample Time Coarse.

XDI_FrameRange 

Reserved.

XDI_PacketCounter8 

8 bit packet counter, wraps at 256

XDI_SampleTime64 

64 bit sample time

XDI_OrientationGroup 

Group for orientation related outputs.

XDI_CoordSysMask 

Mask for the coordinate system part of the orientation data identifier.

XDI_CoordSysEnu 

East North Up orientation output.

XDI_CoordSysNed 

North East Down orientation output.

XDI_CoordSysNwu 

North West Up orientation output.

XDI_Quaternion 

Orientation in quaternion format.

XDI_RotationMatrix 

Orientation in rotation matrix format.

XDI_EulerAngles 

Orientation in euler angles format.

XDI_PressureGroup 

Group for pressure related outputs.

XDI_BaroPressure 

Pressure output recorded from the barometer.

XDI_AccelerationGroup 

Group for acceleration related outputs.

XDI_DeltaV 

DeltaV SDI data output.

XDI_Acceleration 

Acceleration output in m/s2.

XDI_FreeAcceleration 

Free acceleration output in m/s2.

XDI_AccelerationHR 

AccelerationHR output.

XDI_IndicationGroup 

0100.1000 -> bit reverse = 0001.0010 -> type 18

XDI_TriggerIn1 

Trigger in 1 indication.

XDI_TriggerIn2 

Trigger in 2 indication.

XDI_TriggerIn3 

Trigger in 3 indication.

XDI_PositionGroup 

Group for position related outputs.

XDI_AltitudeMsl 

Altitude at Mean Sea Level.

XDI_AltitudeEllipsoid 

Altitude at ellipsoid.

XDI_PositionEcef 

Position in earth-centered, earth-fixed format.

XDI_LatLon 

Position in latitude, longitude.

XDI_GnssGroup 

Group for Gnss related outputs.

XDI_GnssPvtData 

Gnss position, velocity and time data.

XDI_GnssSatInfo 

Gnss satellite information.

XDI_GnssPvtPulse 

Time of the PVT timepulse (4Hz upsampled from the 1PPS)

XDI_AngularVelocityGroup 

Group for angular velocity related outputs.

XDI_RateOfTurn 

Rate of turn data in rad/sec.

XDI_DeltaQ 

DeltaQ SDI data.

XDI_RateOfTurnHR 

Rate of turn HR data.

XDI_RawSensorGroup 

Group for raw sensor data related outputs.

XDI_RawUnsigned 

Tracker produces unsigned raw values, usually fixed behavior.

XDI_RawSigned 

Tracker produces signed raw values, usually fixed behavior.

XDI_RawAccGyrMagTemp 

Raw acceleration, gyroscope, magnetometer and temperature data.

XDI_RawGyroTemp 

Raw gyroscope and temperature data.

XDI_RawAcc 

Raw acceleration data.

XDI_RawGyr 

Raw gyroscope data.

XDI_RawMag 

Raw magnetometer data.

XDI_RawDeltaQ 

Raw deltaQ SDI data.

XDI_RawDeltaV 

Raw deltaV SDI data.

XDI_RawBlob 

Raw blob data.

XDI_AnalogInGroup 

Group for analog in related outputs.

XDI_AnalogIn1 

Data containing adc data from analog in 1 line (if present)

XDI_AnalogIn2 

Data containing adc data from analog in 2 line (if present)

XDI_MagneticGroup 

Group for magnetometer related outputs.

XDI_MagneticField 

Magnetic field data in a.u.

XDI_MagneticFieldCorrected 

Corrected Magnetic field data in a.u. (ICC result)

XDI_SnapshotGroup 

Group for snapshot related outputs.

XDI_RetransmissionMask 

Mask for the retransmission bit in the snapshot data.

XDI_RetransmissionFlag 

Bit indicating if the snapshot if from a retransmission.

XDI_AwindaSnapshot 

Awinda type snapshot.

XDI_FullSnapshot 

Full snapshot.

XDI_GloveSnapshotLeft 

Glove Snapshot for Left Hand.

XDI_GloveSnapshotRight 

Glove Snapshot for Right Hand.

XDI_GloveDataGroup 

Group for usable glove data.

XDI_GloveDataLeft 

Glove Data for Left Hand.

XDI_GloveDataRight 

Glove Data for Right Hand.

XDI_VelocityGroup 

Group for velocity related outputs.

XDI_VelocityXYZ 

Velocity in XYZ coordinate frame.

XDI_StatusGroup 

Group for status related outputs.

XDI_StatusByte 

Status byte.

XDI_StatusWord 

Status word.

XDI_Rssi 

Rssi information.

XDI_DeviceId 

DeviceId output.

XDI_LocationId 

LocationId output.

Definition at line 84 of file xsdataidentifier.h.

◆ XsDataIdentifierValue

Defines some convenience values for use with the data identifiers.

Refer to the Low Level Communication Protocol for more details.

Enumerator
XDIV_MaxFrequency 

Maximum / no frequency.

Definition at line 82 of file xsdataidentifiervalue.h.

◆ XsDeviceCapability

Device capability flags.

Enumerator
XDC_Invalid 

Indicates the XsDeviceCapabilities structure is invalid.

XDC_Acc 

Device has an operational accelerometer.

XDC_Gyr 

Device has an operational gyroscope.

XDC_Mag 

Device has an operational magnetometer.

XDC_Baro 

Device has an operational barometer.

XDC_Gnss 

Device has an operational GNSS receiver.

XDC_Imu 

Device is an IMU.

XDC_Vru 

Device is a VRU.

XDC_Ahrs 

Device is an AHRS.

XDC_GnssIns 

Device is a GNSS/INS.

XDC_Rtk 

Device has RTK features.

Definition at line 78 of file xsdevicecapabilities.h.

◆ XsDeviceOptionFlag

Used to enable or disable some device options.

See also
XsDevice::setDeviceOptionFlags
Note
Not all devices support all options.
Enumerator
XDOF_DisableAutoStore 

When set to 1, automatic writing of configuration will be disabled.

XDOF_DisableAutoMeasurement 

When set to 1, the MT will stay in Config Mode upon start up.

XDOF_EnableBeidou 

When set to 1, enables Beidou, disables GLONASS (MTi-G).

XDOF_DisableGps 

When set to 1, disables GPS (MTi-G).

XDOF_EnableAhs 

When set to 1, the MTi will have Active Heading Stabilization (AHS) enabled.

XDOF_EnableOrientationSmoother 

When set to 1, the MTi will have Orientation Smoother enabled. Only applicable to MTi-G-710, MTi-7, MTi-670 and MTi-680.

XDOF_EnableConfigurableBusId 

When set to 1, allows to configure the BUS ID.

XDOF_EnableInrunCompassCalibration 

When set to 1, the MTi will have In-run Compass Calibration (ICC) enabled.

XDOF_DisableSleepMode 

When set to 1, an MTw will not enter sleep mode after a scan timeout. It will scan indefinitely.

XDOF_EnableConfigMessageAtStartup 

When set to 1, the MT will send the Configuration to the Master at start-up.

XDOF_EnableColdFilterResets 

When set to 1, The MT performs a cold filter reset every time it goes to measurement.

XDOF_EnablePositionVelocitySmoother 

When set to 1, the MTi will have Position/Velocity Smoother enabled. Only applicable to MTi-680.

XDOF_EnableContinuousZRU 

When set to 1, the MTi filter will perform continuous Zero Rotation Updates for gyroscope bias and noise.

XDOF_EnableRawGnssInputForwarding 

When set to 1, the MTi will forward the raw input coming from the GNSS receiver encapsulated in an Xbus message.

XDOF_None 

When set to 1, disables all option flags.

XDOF_All 

When set to 1, enables all option flags.

Definition at line 75 of file xsdeviceoptionflag.h.

◆ XsDeviceParameterIdentifier

Defines the device parameter identifiers.

See also
XsDevice::setDeviceParameter for a detailed description of the following identifiers.
Enumerator
XDPI_Unknown 

Invalid value, set if the desired parameter is not supported.

XDPI_PacketErrorRate 
XDPI_ExtendedBuffer 
XDPI_UplinkTimeout 
XDPI_SyncLossTimeout 

Definition at line 77 of file xsdeviceparameteridentifier.h.

◆ XsDeviceState

XsDevice state identifiers.

Enumerator
XDS_Initial 

Initial unknown state

XDS_Config 

Configuration mode.

XDS_Measurement 

Measurement mode, devices are transmitting data.

XDS_WaitingForRecordingStart 

The device is in measurement mode and waiting for an external trigger to go to recording state.

Note
Awinda Station only
XDS_Recording 

Same as measurement mode, but on Awinda systems retransmissions now also occur.

Note
Only on an Awinda Station is this an actual state in the device. For other devices, the state exists only in XDA.
XDS_FlushingData 

The device has been notified that it should stop recording. It is still measuring data and may flush retransmitted data to XDA. When XDA decides that it will not receive any more data that should be recorded, the state will be switched to XDS_Measurement automatically

XDS_Destructing 

The device is being destructed. After this callback, the device and any references to it are invalid.

Definition at line 77 of file xsdevicestate.h.

◆ XsErrorMode

Error modes for use in XsDevice::setErrorMode.

See also
XsDevice::setErrorMode
XsDevice::errorMode
Enumerator
XEM_Ignore 

Ignore all errors without warning.

XEM_IncreasePacketCounter 

Increase packet counter when an error occurs, resulting in gaps in the packet counter.

XEM_IncreasePacketCounterAndSendError 

Increase packet counter when an error occurs, resulting in gaps in the packet counter and send an explicit error message.

XEM_SendErrorAndGoToConfig 

Abort measuring and send an error message.

XEM_Invalid 

No error mode available.

Definition at line 74 of file xserrormode.h.

◆ XsFloatFormat

Legacy floating point / fixed point format options.

Enumerator
FF_IEEE754Float 

Single precision floating point (IEEE 754)

FF_FixedPoint1220 

Fixed point 12.20 format (12 signed bits before decimal, 20 after)

FF_FixedPoint1632 

Fixed point 16.32 format (16 signed bits before decimal, 32 after)

Definition at line 72 of file xsfloatformat.h.

◆ XsGnssAntennaStatus

Contains flags indicating the status of the GNSS antenna.

Enumerator
XGAS_OpenCircuit 
XGAS_ShortCircuit 

No antenna is connected to the antenne port.

XGAS_OK 

The antennaconnector seems to be shorted with Ground.

XGAS_DontKnow 

Everything seems ok, antenna connected.

XGAS_Requesting 

Unknown Status.

XGAS_Init 

Busy requesting the current antenna status from the GNSS receiver.

Definition at line 98 of file xsgnssstatus.h.

◆ XsGnssStatusFlag

GNSS status flags.

The Flags contain bits the indicate the operational status of the GNSS module

Enumerator
XGSF_GnssReceiverInitialized 
XGSF_GnssReceiverDataOk 
XGSF_AntennaDetectionMask 

Definition at line 76 of file xsgnssstatus.h.

◆ XsGnssStatusFlagOffset

GNSS status flags offsets.

Sometimes (rarely) it is necessary to know the bit offset instead of the bit mask (ie when shifting to only keep a subset of flags) for the status flags. This enumeration provides these offsets.

See also
XsGnssStatusFlag
Enumerator
XGSFO_OffsetGnssReceiverInitialized 
XGSFO_OffsetGnssReceiverDataOk 
XGSFO_OffsetAntennaDetection 

Definition at line 89 of file xsgnssstatus.h.

◆ XsHandId

enum XsHandId

This is an enumerator that contains the left and right hand.

These values are to be used when addressing the left or right hand (or either).

Enumerator
XHI_LeftHand 

The Left Hand.

XHI_RightHand 

The Right Hand.

XHI_Unknown 

Used as uninitialized or unknown side.

Definition at line 75 of file xshandid.h.

◆ XsInfoRequest

Information request identifiers.

These values are used by the XsDevice::requestInfo function and XsCallback::onInfoResponse functions.

Enumerator
XIR_BatteryLevel 

Request battery level.

XIR_GnssSvInfo 

Request Gnss satellite vehicle information.

Definition at line 77 of file xsinforequest.h.

◆ XsOption

enum XsOption

Xda options, used to control the kind of data processing done by XDA.

These options are used to specify whether XDA should compute certain kinds of data from available other data. XsOptions can be logically ORed together

Enumerator
XSO_None 

No option.

XSO_Calibrate 

Compute calibrated inertial data from raw data and temperature.

XSO_Orientation 

Compute orientation, the orientation is typically only computed in one stream. If not specified the system will decide: when reading from file it will use XSO_OrientationInBufferedStream, otherwise XSO_OrientationInLiveStream.

XSO_KeepLastLiveData 

Keep the last available live data in a cache so XsDevice::lastAvailableLiveData will work.

XSO_RetainLiveData 

Keep the live data in a cache so it can be accessed through XsDevice::getDataPacketByIndex or XsDevice::takeFirstDataPacketInQueue. This option is mutually exclusive with XSO_RetainBufferedData. If both are set, XSO_RetainBufferedData will be used.

XSO_RetainBufferedData 

Keep the buffered data in a cache so it can be accessed through XsDevice::getDataPacketByIndex or XsDevice::takeFirstDataPacketInQueue. This option is mutually exclusive with XSO_RetainLiveData. If both are set, XSO_RetainBufferedData will be used.

XSO_OrientationInLiveStream 

Compute orientation in the live stream. This is no longer (since version 4.9.2) mutually exclusive with XSO_OrientationInBufferedStream, but unless they're both explicitly set, the system will choose only one stream to use. Please note that this option does not do anything unless XSO_Orientation is also enabled.

XSO_OrientationInBufferedStream 

Compute orientation in the buffered stream. This is no longer (since version 4.9.2) mutually exclusive with XSO_OrientationInLiveStream, but unless they're both explicitly set, the system will choose only one stream to use. Please note that this option does not do anything unless XSO_Orientation is also enabled.

XSO_ApplyOrientationResetToCalData 

Apply orientation reset to calibrated acc, gyr and mag (object reset only) and heading reset to free acc. Default is enabled for the MTw family, disabled for others.

XSO_InterpolateMissingData 

When set, any gaps in the data streams of child devices will be filled with interpolated data. This is only for applications that require data for each sample counter. Not recommended when XSO_SkipDataBundling is disabled.

XSO_SkipDataBundling 

When set, the onAll...DataAvailable callbacks will not be called by the master device. This prevents some internal buffering.

XSO_ExpectNoRetransmissionsInFile 

When set and reading a file, missing data is immediately treated as unavailable. The default behaviour is to read further in the file to see if the data was retransmitted.

XSO_Reserved 

Reserved for internal use.

Definition at line 76 of file xsoption.h.

◆ XsOrientationMode

Legacy orientation output mode selection.

Enumerator
OM_None 
OM_Euler 
OM_Quaternion 
OM_Matrix 

Definition at line 73 of file xsorientationmode.h.

◆ XsProtocol

enum XsProtocol

Protocol types, used for MTi6x0 devices.

Enumerator
XP_None 

None.

XP_Xbus 

The Xsens Xbus protocol.

XP_Nmea 

The NMEA protocol.

XP_Rtcm 

RTCM protocol for RTK.

Definition at line 72 of file xsprotocol.h.

◆ XsProtocolType

Protocol types (XsDevice::enableProtocol())

Enumerator
XPT_Xbus 

The Xsens Xbus protocol, enabled by default, always 0.

XPT_Nmea 

The NMEA protocol, only the messages that can be sent from Xsens devices are recognized.

XPT_ImarFsas 

An iMAR FSAS communication protocol.

XPT_ImarIfog 

An iMAR iFog communication protocol.

XPT_ImarIfogUart 

An iMAR iFog UART communication protocol.

Definition at line 72 of file xsprotocoltype.h.

◆ XsPvtDataQualityIndicator

Defines the quality indicator flags of the GNSS Fix type.

Enumerator
XPDQI_NoFix 
XPDQI_DeadReckiningOnly 
XPDQI_2DFix 
XPDQI_3DFix 
XPDQI_GnssAndDeadReck 
XPDQI_TimeOnlyFix 

Definition at line 121 of file xsrawgnsspvtdata.h.

◆ XsPvtDataUtcFlags

Define the validity flags for the UTC time.

Enumerator
XPDUF_ValidDate 
XPDUF_ValidTime 
XPDUF_FullyResolved 
XPDUF_ValidMag 

Definition at line 110 of file xsrawgnsspvtdata.h.

◆ XsRejectReason

Identifiers for why a device's connection was rejected.

Enumerator
XRR_Unknown 
XRR_VersionMismatch 
XRR_Blacklisted 
XRR_StationIsDisconnecting 
XRR_SystemIsOperational 

Definition at line 74 of file xsrejectreason.h.

◆ XsResetMethod

Orientation reset type.

Enumerator
XRM_StoreAlignmentMatrix 

Store the current object alignment matrix to persistent memory.

XRM_Heading 

Reset the heading (yaw)

XRM_Object 

Reset the attitude (roll, pitch), same as XRM_Inclination.

XRM_Inclination 

Reset the inclination (roll, pitch), same as XRM_Object.

XRM_Alignment 

Reset heading and attitude.

This effectively combines the XRM_Heading and XRM_Object

XRM_Global 

Reset the full orientation of the device.

Obsolete. Use XRM_Alignment instead.

XRM_DefaultHeading 

Revert to default behaviour for heading, undoes XRM_Heading.

XRM_DefaultInclination 

Revert to default behaviour for inclination, undoes XRM_Inclination.

XRM_DefaultAlignment 

Revert to default behaviour for heading and inclination, undoes any reset.

XRM_None 

No reset planned.

Definition at line 74 of file xsresetmethod.h.

◆ XsResultValue

Xsens result values.

These values are used to signal success or specific failures of functions

See also
XsResultValue_toString
Enumerator
XRV_OK 

0: Operation was performed successfully

XRV_NOBUS 

1: No bus communication possible

XRV_BUSNOTREADY 

2: InitBus and/or SetBID are not issued

XRV_INVALIDPERIOD 

3: Period sent is invalid

XRV_INVALIDMSG 

4: The message is invalid or not implemented

XRV_INITBUSFAIL1 

16: A slave did not respond to WaitForSetBID

XRV_INITBUSFAIL2 

17: An incorrect answer received after WaitForSetBID

XRV_INITBUSFAIL3 

18: After four bus-scans still undetected Motion Trackers

XRV_SETBIDFAIL1 

20: No reply to SetBID message during SetBID procedure

XRV_SETBIDFAIL2 

21: Other than SetBIDAck received

XRV_MEASUREMENTFAIL1 

24: Timer overflow - period too short to collect all data from Motion Trackers

XRV_MEASUREMENTFAIL2 

25: Motion Tracker responds with other than SlaveData message

XRV_MEASUREMENTFAIL3 

26: Total bytes of data of Motion Trackers including sample counter exceeds 255 bytes

XRV_MEASUREMENTFAIL4 

27: Timer overflows during measurement

XRV_MEASUREMENTFAIL5 

28: Timer overflows during measurement

XRV_MEASUREMENTFAIL6 

29: No correct response from Motion Tracker during measurement

XRV_TIMEROVERFLOW 

30: Timer overflows during measurement

XRV_BAUDRATEINVALID 

32: Baud rate does not comply with valid range

XRV_INVALIDPARAM 

33: An invalid parameter is supplied

XRV_MEASUREMENTFAIL7 

35: TX PC Buffer is full

XRV_MEASUREMENTFAIL8 

36: TX PC Buffer overflow, cannot fit full message

XRV_WIRELESSFAIL 

37: Wireless subsystem failed

XRV_DEVICEERROR 

40: The device generated an error, try updating the firmware

XRV_DATAOVERFLOW 

41: The device generates more data than the bus communication can handle (baud rate may be too low)

XRV_BUFFEROVERFLOW 

42: The sample buffer of the device was full during a communication outage

XRV_EXTTRIGGERERROR 

43: The external trigger is not behaving as configured

XRV_SAMPLESTREAMERROR 

44: The sample stream detected an error in the ordering of sample data

XRV_POWER_DIP 

45: A dip in the power supply was detected and recovered from

XRV_POWER_OVERCURRENT 

46: A current limiter has been activated, shutting down the device

XRV_OVERHEATING 

47: Device temperature is not within operational limits

XRV_BATTERYLOW 

48: Battery level reached lower limit

XRV_INVALIDFILTERPROFILE 

49: Specified filter profile ID is not available on the device or the user is trying to duplicate an existing filter profile type

XRV_INVALIDSTOREDSETTINGS 

50: The settings stored in the device's non volatile memory are invalid

XRV_ACCESSDENIED 

51: Request for control of the device was denied

XRV_FILEERROR 

52: Failure reading, writing, opening or closing a file

XRV_OUTPUTCONFIGERROR 

53: Erroneous output configuration, device can not go to measurement

XRV_FILE_SYSTEM_CORRUPT 

54: The internal file system of the device has become corrupt

XRV_ERROR 

256: A generic error occurred

XRV_NOTIMPLEMENTED 

257: Operation not implemented in this version (yet)

XRV_TIMEOUT 

258: A timeout occurred

XRV_TIMEOUTNODATA 

259: Operation aborted because of no data read

XRV_CHECKSUMFAULT 

260: Checksum fault occurred

XRV_OUTOFMEMORY 

261: No internal memory available

XRV_NOTFOUND 

262: The requested item was not found

XRV_UNEXPECTEDMSG 

263: Unexpected message received (e.g. no acknowledge message received)

XRV_INVALIDID 

264: Invalid id supplied

XRV_INVALIDOPERATION 

265: Operation is invalid at this point

XRV_INSUFFICIENTSPACE 

266: Insufficient buffer space available

XRV_INPUTCANNOTBEOPENED 

267: The specified i/o device can not be opened

XRV_OUTPUTCANNOTBEOPENED 

268: The specified i/o device can not be opened

XRV_ALREADYOPEN 

269: An I/O device is already opened with this object

XRV_ENDOFFILE 

270: End of file is reached

XRV_COULDNOTREADSETTINGS 

271: A required settings file could not be opened or is missing some data

XRV_NODATA 

272: No data is available

XRV_READONLY 

273: Tried to change a read-only value

XRV_NULLPTR 

274: Tried to supply a NULL value where it is not allowed

XRV_INSUFFICIENTDATA 

275: Insufficient data was supplied to a function

XRV_BUSY 

276: Busy processing, try again later

XRV_INVALIDINSTANCE 

277: Invalid instance called, because of an invalid or missing license

XRV_DATACORRUPT 

278: A trusted data stream proves to contain corrupted data

XRV_READINITFAILED 

279: Failure during read of settings

XRV_NOXMFOUND 

280: Could not find any MVN-compatible hardware

XRV_DEVICECOUNTZERO 

282: No xsens devices found

XRV_MTLOCATIONINVALID 

283: One or more sensors are not where they were expected

XRV_INSUFFICIENTMTS 

284: Not enough sensors were found

XRV_INITFUSIONFAILED 

285: Failure during initialization of Fusion Engine

XRV_OTHER 

286: Something else was received than was requested

XRV_NOFILEOPEN 

287: No file opened for reading/writing

XRV_NOPORTOPEN 

288: No serial port opened for reading/writing

XRV_NOFILEORPORTOPEN 

289: No file or serial port opened for reading/writing

XRV_PORTNOTFOUND 

290: A required port could not be found

XRV_INITPORTFAILED 

291: The low-level port handler failed to initialize

XRV_CALIBRATIONFAILED 

292: A calibration routine failed

XRV_CONFIGCHECKFAIL 

293: A configuration-time check of the device failed

XRV_ALREADYDONE 

294: The operation is once only and has already been performed

XRV_SYNC_SINGLE_SLAVE 

295: The single connected device is configured as a slave

XRV_SYNC_SECOND_MASTER 

296: More than one master was detected

XRV_SYNC_NO_SYNC 

297: A device was detected that was neither master nor slave

XRV_SYNC_NO_MASTER 

298: No master detected

XRV_SYNC_DATA_MISSING 

299: A device is not sending enough data

XRV_VERSION_TOO_LOW 

300: The version of the object is too low for the requested operation

XRV_VERSION_PROBLEM 

301: The object has an unrecognised version, so it's not safe to perform the operation

XRV_ABORTED 

302: The process was aborted by an external event, usually a user action or process termination

XRV_UNSUPPORTED 

303: The requested functionality is not supported by the device

XRV_PACKETCOUNTERMISSED 

304: A packet counter value was missed

XRV_MEASUREMENTFAILED 

305: An error occurred while trying to put the device in measurement mode

XRV_STARTRECORDINGFAILED 

306: A device could not start recording

XRV_STOPRECORDINGFAILED 

307: A device could not stop recording

XRV_RADIO_CHANNEL_IN_USE 

311: Radio channel is in use by another system

XRV_UNEXPECTED_DISCONNECT 

312: Motion tracker disconnected unexpectedly

XRV_TOO_MANY_CONNECTED_TRACKERS 

313: Too many motion trackers connected

XRV_GOTOCONFIGFAILED 

314: A device could not be put in config mode

XRV_OUTOFRANGE 

315: Device has gone out of range

XRV_BACKINRANGE 

316: Device is back in range, resuming normal operation

XRV_EXPECTED_DISCONNECT 

317: The device was disconnected

XRV_RESTORE_COMMUNICATION_FAILED 

318: Restore communication failed

XRV_RESTORE_COMMUNICATION_STOPPED 

319: Restore communication was stopped

XRV_EXPECTED_CONNECT 

320: The device was connected

XRV_IN_USE 

321: The requested device/port/address is already in use. Most likely returned by XsSocket::bind

XRV_PERFORMANCE_WARNING 

322: The system running the application can't fully keep up with the incoming data. This may lead to degraded performance or lag.

XRV_PERFORMANCE_OK 

323: The system running the application has recovered from a previously reported XRV_PERFORMANCE_WARNING.

XRV_SHUTTINGDOWN 

400: The device is shutting down

XRV_GNSSCONFIGURATIONERROR 

401: A configuration item was refused by the GNSS module

XRV_GNSSCOMMTIMEOUT 

402: The communication with the GNSS module timed out

XRV_GNSSERROR 

403: Communication between the device and the GNSS module failed

XRV_DEVICE_NOT_CALIBRATED 

404: The EMTS of the device does not contain calibration data

XRV_GNSSCONNECTIONLOST 

405: Connection lost with the GNSS module

XRV_GNSSLOWINPUTRATE 

406: GNSS input rate is too low

XRV_GNSSINCOMPLETEDATASET 

407: Incomplete dataset for the GNSS module

Definition at line 82 of file xsresultvalue.h.

◆ XsSatInfoFlags

Xsens Satellite Info Flags.

Enumerator
XSIF_SignalQualityIndicator_Mask 
XSIF_SignalQualityIndicator_NoSignal 
XSIF_SignalQualityIndicator_Searching 
XSIF_SignalQualityIndicator_Acquired 
XSIF_SignalQualityIndicator_Unusable 
XSIF_SignalQualityIndicator_CodeTimeOk 
XSIF_SignalQualityIndicator_CodeCarrierTimeOk1 
XSIF_SignalQualityIndicator_CodeCarrierTimeOk2 
XSIF_SignalQualityIndicator_CodeCarrierTimeOk3 
XSIF_UsedForNavigation_Mask 
XSIF_UsedForNavigation_Used 
XSIF_HealthFlag_Mask 
XSIF_HealthFlag_Unknown 
XSIF_HealthFlag_Healthy 
XSIF_HealthFlag_Unhealthy 
XSIF_Differential_Mask 
XSIF_Differential_Available 

Definition at line 90 of file xsrawgnsssatinfo.h.

◆ XsSelfTestFlag

Enumeration of bits that describe whether the various self-tests succeeded.

See also
XsSelfTestResult
Enumerator
XSTF_X 
XSTF_Y 
XSTF_Z 
XSTF_AccShift 
XSTF_AccX 
XSTF_AccY 
XSTF_AccZ 
XSTF_GyrShift 
XSTF_GyrX 
XSTF_GyrY 
XSTF_GyrZ 
XSTF_MagShift 
XSTF_MagX 
XSTF_MagY 
XSTF_MagZ 
XSTF_Baro 
XSTF_Gnss 
XSTF_Battery 
XSTF_Flash 
XSTF_Button 
XSTF_Sync 

Definition at line 76 of file xsselftestresult.h.

◆ XsStatusFlag

Status flags.

These flags define the function of specific bits in the status returned by XsDataPacket::status()

See also
XsDataPacket::status()
Enumerator
XSF_SelfTestOk 

Is set when the self test result was ok.

XSF_OrientationValid 

Is set when the computed orientation is valid. The orientation may be invalid during startup or when the sensor data is clipping during violent (for the device) motion.

XSF_GpsValid 

Is set when the device has a GPS receiver and the receiver says that there is a GPS position fix.

XSF_NoRotationMask 

If all of these flags are set, the No Rotation algorithm is running.

XSF_NoRotationAborted 

If only this flag is set (out of the XSF_NoRotationMask) then the No Rotation algorithm was aborted because of movement of the device.

XSF_NoRotationSamplesRejected 

If only this flag is set (out of the XSF_NoRotationMask) then the No Rotation algorithm is running but has rejected samples.

XSF_NoRotationRunningNormally 

If all these flags are set (out of the XSF_NoRotationMask) then the No Rotation algorithm is running normally.

XSF_RepresentativeMotion 

Indicates if the In-Run Compass Calibration is doing the representative motion analysis.

XSF_ExternalClockSynced 

Indicates whether the internal clock is synced with an external clock (Either GNNS or custom provided clock sync)

XSF_FilterInputStart 

Marks that the corresponding data is the first data fed to the (onboard) filter.

XSF_ClipAccX 
XSF_ClipAccY 
XSF_ClipAccZ 
XSF_ClipGyrX 
XSF_ClipGyrY 
XSF_ClipGyrZ 
XSF_ClipMagX 
XSF_ClipMagY 
XSF_ClipMagZ 
XSF_Retransmitted 

When set Indicates the sample was received as a retransmission.

XSF_ClippingDetected 

When set Indicates clipping has occurred.

XSF_Interpolated 

When set Indicates the sample is an interpolation between other samples.

XSF_SyncIn 

When set indicates a sync-in event has been triggered.

XSF_SyncOut 

When set Indicates a sync-out event has been generated.

XSF_FilterMode 

Mask for the 3 bit filter mode field.

XSF_HaveGnssTimePulse 

Indicates that the 1PPS GNSS time pulse is present.

XSF_RtkStatus 

Mask for 2 bit RTK status field 00: No RTK; 01: RTK floating; 10: RTK fixed.

Definition at line 79 of file xsstatusflag.h.

◆ XsStatusFlagOffset

Status flag bit offsets.

Sometimes (rarely) it is necessary to know the bit offset instead of the bit mask (ie when shifting to only keep a subset of flags) for the status flags. This enumeration provides these offsets.

See also
XsStatusFlag
Enumerator
XSFO_OffsetSelfTestOk 
XSFO_OffsetOrientationValid 
XSFO_OffsetGpsValid 
XSFO_OffsetNoRotation 
XSFO_OffsetRepresentativeMotion 
XSFO_OffsetExternalClockSynced 
XSFO_OffsetClipAccX 
XSFO_OffsetClipAccY 
XSFO_OffsetClipAccZ 
XSFO_OffsetClipGyrX 
XSFO_OffsetClipGyrY 
XSFO_OffsetClipGyrZ 
XSFO_OffsetClipMagX 
XSFO_OffsetClipMagY 
XSFO_OffsetClipMagZ 
XSFO_Retransmitted 
XSFO_ClippingDetected 
XSFO_Interpolated 
XSFO_SyncIn 
XSFO_SyncOut 
XSFO_FilterMode 
XSFO_FilterModeNrOfBits 
XSFO_HaveGnssTimePulse 
XSFO_RtkStatus 
XSFO_RtkStatusNrOfBits 

Definition at line 124 of file xsstatusflag.h.

◆ XsStringOutputType

String output types.

Enumerator
XSOT_None 
XSOT_HCHDM 

NMEA string with Magnetic Heading.

XSOT_HCHDG 

NMEA string with Heading and Magnetic Variation.

XSOT_TSS2 

Proprietry string with Heading, Heave, Roll and Pitch.

XSOT_PHTRO 

Proprietry NMEA string with Pitch and Roll.

XSOT_PRDID 

Proprietry NMEA string with Pitch, Roll and Heading.

XSOT_EM1000 

Binary format suitable for use with Simrad EM1000 mulitibeam sounders with Roll, Pitch, Heave and Heading.

XSOT_PSONCMS 

NMEA string with Xsens Compass Motion Sensor information.

XSOT_HCMTW 

NMEA string with (water) Temperature.

XSOT_HEHDT 

NMEA string with True Heading.

XSOT_HEROT 

NMEA string with Rate of Turn.

XSOT_GPGGA 

NMEA string with Global Positioning system fix data.

XSOT_PTCF 

NMEA string with motion data.

XSOT_XSVEL 

Proprietry NMEA string with velocity data.

XSOT_GPZDA 

NMEA string with date and time.

XSOT_GPRMC 

NMEA string with recommended minimum specific GPS/Transit data.

Definition at line 72 of file xsstringoutputtype.h.

◆ XsSyncFunction

Actions to be taken on input triggers.

Enumerator
XSF_StartRecordingIn 

Start recording on trigger or emit trigger when first recording frame is started (In).

Remarks
Applies to Awinda Station.
XSF_StopRecordingIn 

Stop recording on trigger or emit trigger when recording is stopped (In).

Remarks
Applies to Awinda Station.
XSF_ResetTimer 

On input trigger, the outgoing timer of the station will be set to 0.

Remarks
Applies to Awinda Station.
XSF_TriggerIndication 

An indication is sent to the driver when trigger is detected.

Remarks
Applies to Awinda Station.
XSF_IntervalTransitionMeasurement 

Emit trigger on an interval transition during measurement and recording.

XSF_IntervalTransitionRecording 

Emit trigger on an interval transition during recording.

XSF_GotoOperational 

Emit trigger when going to Operational mode.

Remarks
Applies to Awinda Station.
XSF_SampleAndSend 

Sample a sample and send the MT Data message.

Remarks
Applies to Mt.
XSF_SendLatest 

Send the latest sample.

Remarks
Applies to Mt.
XSF_ClockBiasEstimation 

Do a clock bias estimation on trigger.

Remarks
Applies to Mti-G.
XSF_PulseWithModulation 

Do interval transition measurement with pulse width modulation.

XSF_StartSampling 

Start sampling. Data will only be transmitted after this trigger has been received.

Remarks
Applies only to Mk4.
XSF_StartRecordingOut 

Start recording on trigger or emit trigger when first recording frame is started (Out).

Remarks
Applies to Awinda Station.
XSF_StopRecordingOut 

Stop recording on trigger or emit trigger when recording is stopped (Out).

Remarks
Applies to Awinda Station.
XSF_Gnss1Pps 

Emit trigger on the start of each second, generated by the GNSS receiver.

XSF_BusSync 

Supply periodic trigger to synchronize multiple MTi devices on a single bus.

XSF_Invalid 

Invalid action.

This indicates the trigger action is not usable.

XSF_Count 

Amount of trigger actions.

Definition at line 74 of file xssyncfunction.h.

◆ XsSyncLine

enum XsSyncLine

Synchronization line identifiers.

Enumerator
XSL_Inputs 

Value for checking if a line is an input, any item equal to or greater than XSL_Inputs and less than XSL_Outputs is an input.

XSL_In1 

Sync In 1.

Remarks
Applies to Awinda Station and Mt
XSL_In2 

Sync In 2.

Remarks
Applies to Awinda Station
XSL_In3 

Sync In 3.

Remarks
Applies to MTi-680
XSL_Bi1In 

Bidirectional Sync 1 In.

XSL_ClockIn 

Clock synchronisation input.

Remarks
Applies to Mk4
XSL_CtsIn 

RS232 CTS sync in.

XSL_GnssClockIn 

Clock synchronisation input line attached to internal GNSS unit.

Remarks
Applies to Mk4
XSL_ExtTimepulseIn 

External time pulse input (e.g. for external GNSS unit)

Remarks
Applies to Mk4 with external device
XSL_ReqData 

Serial data sync option, use XMID_ReqData message id for this.

Remarks
Applies to Mk4
XSL_Gnss1Pps 

GNSS 1PPS pulse sync line.

Remarks
Applies to MTi-7
XSL_Outputs 

Value for checking if a line is output. Values equal to or greater than this are outputs.

XSL_Out1 

Sync Out 1.

Remarks
Applies to Awinda Station and Mt
XSL_Out2 

Sync Out 2.

Remarks
Applies to Awinda Station
XSL_Bi1Out 

Bidirectional Sync 1 Out.

XSL_RtsOut 

RS232 RTS sync out.

XSL_Invalid 

Invalid sync setting. Used if no sync line is set.

Definition at line 74 of file xssyncline.h.

◆ XsSyncPolarity

Signal polarity.

Enumerator
XSP_None 

Don't generate or react to trigger level changes.

XSP_RisingEdge 

React to a rising edge on input.

XSP_PositivePulse 

Generate a positive pulse on output.

XSP_FallingEdge 

React to a falling edge on input.

XSP_NegativePulse 

Generate a falling edge on output.

XSP_Both 

Toggle output or react on all toggles on input.

Definition at line 74 of file xssyncpolarity.h.

◆ XsSyncRole

enum XsSyncRole

Synchronization roles.

Enumerator
XSR_Slave 
XSR_None 
XSR_MasterSlave 
XSR_Master 

Definition at line 73 of file xssyncrole.h.

◆ XsThreadPriority

Thread priorities for xsSetThreadPriority() and xsGetThreadPriority()

Enumerator
XS_THREAD_PRIORITY_LOWEST 
XS_THREAD_PRIORITY_LOWER 
XS_THREAD_PRIORITY_LOW 
XS_THREAD_PRIORITY_NORMAL 
XS_THREAD_PRIORITY_HIGH 
XS_THREAD_PRIORITY_HIGHER 
XS_THREAD_PRIORITY_HIGHEST 

Definition at line 162 of file xsthread.h.

◆ XsXbusMessageId

Xsens Xbus Message Identifiers.

Enumerator
XMID_InvalidMessage 
XMID_ReqDid 
XMID_DeviceId 
XMID_Initbus 
XMID_InitBusResults 
XMID_ReqPeriod 
XMID_ReqPeriodAck 
XMID_SetPeriod 
XMID_SetPeriodAck 
XMID_SetBid 
XMID_SetBidAck 
XMID_AutoStart 
XMID_AutoStartAck 
XMID_BusPower 
XMID_BusPowerAck 
XMID_ReqDataLength 
XMID_DataLength 
XMID_ReqConfiguration 
XMID_Configuration 
XMID_RestoreFactoryDef 
XMID_RestoreFactoryDefAck 
XMID_GotoMeasurement 
XMID_GotoMeasurementAck 
XMID_ReqFirmwareRevision 
XMID_FirmwareRevision 
XMID_ReqUniqueId 
XMID_UniqueId 
XMID_ReqBodypackMode 
XMID_ReqBodypackAck 
XMID_SetBodypackMode 
XMID_SetBodypackModeAck 
XMID_ReqBaudrate 
XMID_ReqBaudrateAck 
XMID_SetBaudrate 
XMID_SetBaudrateAck 
XMID_ReqProductVariant 
XMID_ProductVariant 
XMID_ReqProductCode 
XMID_ProductCode 
XMID_ReqHardwareVersion 
XMID_HardwareVersion 
XMID_ReqProcessingFlags 
XMID_ReqProcessingFlagsAck 
XMID_SetProcessingFlags 
XMID_SetProcessingFlagsAck 
XMID_SetNoRotation 
XMID_SetNoRotationAck 
XMID_RunSelfTest 
XMID_SelfTestResults 
XMID_ReqInputTrigger 
XMID_ReqInputTriggerAck 
XMID_SetInputTrigger 
XMID_SetInputTriggerAck 
XMID_ReqOutputTrigger 
XMID_ReqOutputTriggerAck 
XMID_SetOutputTrigger 
XMID_SetOutputTriggerAck 
XMID_SetSyncStationMode 

Request the current sync station mode.

XMID_SetSyncStationModeAck 

Message contains the current sync station mode.

XMID_ReqSyncStationMode 

Set the current sync station mode.

XMID_ReqSyncStationModeAck 

Acknowledge of setting the current sync station mode.

XMID_SetSyncConfiguration 
XMID_SetSyncConfigurationAck 
XMID_ReqSyncConfiguration 
XMID_SyncConfiguration 
XMID_DriverDisconnect 
XMID_DriverDisconnectAck 
XMID_GotoConfig 
XMID_GotoConfigAck 
XMID_MtData 
XMID_BusData 
XMID_PrepareData 
XMID_ReqData 
XMID_ReqDataAck 
XMID_MtData2 
XMID_MtData2Ack 
XMID_RequestControl 
XMID_RequestControlAck 
XMID_SetDataPort 
XMID_SetDataPortAck 
XMID_ReqRetransmission 
XMID_ReqRetransmissionAck 
XMID_Wakeup 
XMID_WakeupAck 
XMID_Reset 
XMID_ResetAck 
XMID_Error 
XMID_Warning 
XMID_XmPowerOff 
XMID_MasterIndication 
XMID_XsbData 
XMID_ReqOptionFlags 
XMID_ReqOptionFlagsAck 
XMID_SetOptionFlags 
XMID_SetOptionFlagsAck 
XMID_ReqStealthMode 
XMID_StealthMode 
XMID_SetStealthMode 
XMID_SetStealthModeAck 
XMID_UserInterface 
XMID_UserInterfaceAck 
XMID_EndOfRecording 
XMID_EndOfRecordingAck 
XMID_GotoTransparentMode 
XMID_GotoTransparentModeAck 
XMID_ReqDeviceCapabilities 
XMID_DeviceCapabilities 
XMID_DiscardRetransmissions 
XMID_DiscardRetransmissionsAck 
XMID_RunFactoryTest 
XMID_FactoryTestResults 
XMID_FactoryTestConnect 
XMID_FactoryTestConnectAck 
XMID_SetDataOutputDelay 
XMID_SetDataOutputDelayAck 
XMID_SetBodypackConfigFile 
XMID_SetBodypackConfigFileAck 
XMID_ReqObrStatus 
XMID_ObrStatus 
XMID_SetUtcTime 
XMID_ReqUtcTime 
XMID_SetUtcTimeAck 
XMID_UtcTime 
XMID_FactoryTestSensorTiming 
XMID_FactoryTestSensorTimingResults 
XMID_ReqAvailableFilterProfiles 

Request the available filter profiles.

XMID_AvailableFilterProfiles 

Message contains the available filter profiles.

XMID_ReqFilterProfile 

Request the current filter profile.

XMID_ReqFilterProfileAck 

Message contains the current filter profile.

XMID_SetFilterProfile 

Set the current filter profile.

XMID_SetFilterProfileAck 

Acknowledge of setting the current filter profile.

XMID_ReqGravityMagnitude 
XMID_ReqGravityMagnitudeAck 
XMID_SetGravityMagnitude 
XMID_SetGravityMagnitudeAck 
XMID_ReqGnssLeverArm 
XMID_ReqGnssLeverArmAck 
XMID_SetGnssLeverArm 
XMID_SetGnssLeverArmAck 
XMID_ReqMagneticField 
XMID_ReqMagneticFieldAck 
XMID_SetMagneticField 
XMID_SetMagneticFieldAck 
XMID_ReqReplayMode 
XMID_ReqReplayModeAck 
XMID_SetReplayMode 
XMID_SetReplayModeAck 
XMID_ReqLatLonAlt 
XMID_ReqLatLonAltAck 
XMID_SetLatLonAlt 
XMID_SetLatLonAltAck 
XMID_KeepAlive 
XMID_KeepAliveAck 
XMID_CloseConnection 
XMID_CloseConnectionAck 
XMID_IccCommand 
XMID_IccCommandAck 
XMID_ReqGnssPlatform 
XMID_ReqGnssPlatformAck 
XMID_SetGnssPlatform 
XMID_SetGnssPlatformAck 
XMID_ReqConnectionSettings 
XMID_ReqConnectionSettingsAck 
XMID_SetConnectionSettings 
XMID_SetConnectionSettingsAck 
XMID_BodyPackBundle 
XMID_BodyPackBundleAck 
XMID_ReqStationOptions 
XMID_ReqStationOptionsAck 
XMID_ReqErrorReport 
XMID_ErrorReport 
XMID_ReqXmErrorMode 
XMID_ReqXmErrorModeAck 
XMID_SetXmErrorMode 
XMID_SetXmErrorModeAck 
XMID_ReqBufferSize 
XMID_ReqBufferSizeAck 
XMID_SetBufferSize 
XMID_SetBufferSizeAck 
XMID_ReqHeading 
XMID_ReqHeadingAck 
XMID_SetHeading 
XMID_SetHeadingAck 
XMID_ReqLocationId 
XMID_ReqLocationIdAck 
XMID_SetLocationId 
XMID_SetLocationIdAck 
XMID_ReqExtOutputMode 
XMID_ReqExtOutputModeAck 
XMID_SetExtOutputMode 
XMID_SetExtOutputModeAck 
XMID_ReqBatteryLevel 
XMID_Batterylevel 
XMID_ReqInitTrackMode 
XMID_ReqInitTrackModeAck 
XMID_SetInitTrackMode 
XMID_SetInitTrackModeAck 
XMID_ReqMasterSettings 
XMID_MasterSettings 
XMID_StoreFilterState 
XMID_StoreFilterStateAck 
XMID_ReqPortConfig 
XMID_SetPortConfig 
XMID_PortConfig 
XMID_SetPortConfigAck 
XMID_ReqStringOutputType 
XMID_ReqStringOutputTypeAck 
XMID_SetStringOutputType 
XMID_SetStringOutputTypeAck 
XMID_ReqStringOutputConfig 
XMID_ReqStringOutputConfigAck 
XMID_SetStringOutputConfig 
XMID_SetStringOutputConfigAck 
XMID_ReqEmts 
XMID_EmtsData 
XMID_UpdateFilterProfile 
XMID_UpdateFilterProfileAck 
XMID_RestoreEmts 
XMID_RestoreEmtsAck 
XMID_StoreEmts 
XMID_StoreEmtsAck 
XMID_UnlockMaintenanceMode 
XMID_UnlockMaintenanceModeAck 
XMID_ClockSyncCommand 
XMID_ClockSyncCommandAck 
XMID_ReqActiveClockCorrection 
XMID_ActiveClockCorrection 
XMID_StoreActiveClockCorrection 
XMID_StoreActiveClockCorrectionAck 
XMID_ReqFilterSettings 
XMID_ReqFilterSettingsAck 
XMID_SetFilterSettings 
XMID_SetFilterSettingsAck 
XMID_ReqAmd 
XMID_ReqAmdAck 
XMID_SetAmd 
XMID_SetAmdAck 
XMID_ResetOrientation 
XMID_ResetOrientationAck 
XMID_ReqGnssStatus 
XMID_GnssStatus 
XMID_AdjustUtcTime 
XMID_AdjustUtcTimeAck 
XMID_ReqAssemblyId 
XMID_SetAssemblyId 
XMID_AssemblyId 
XMID_SetAssemblyIdAck 
XMID_ReqGnssReceiverSettings 
XMID_ReqGnssReceiverSettingsAck 
XMID_SetGnssReceiverSettings 
XMID_SetGnssReceiverSettingsAck 
XMID_ReqAccessControlList 
XMID_AccessControlList 
XMID_SetAccessControlList 
XMID_SetAccessControlListAck 
XMID_ScanChannels 
XMID_ScanChannelsAck 
XMID_EnableMaster 
XMID_EnableMasterAck 
XMID_DisableMaster 
XMID_DisableMasterAck 
XMID_ReqRadioChannel 
XMID_ReqRadioChannelAck 
XMID_SetClientPriority 
XMID_SetClientPriorityAck 
XMID_ReqClientPriority 
XMID_ReqClientPriorityAck 
XMID_SetWirelessConfig 
XMID_SetWirelessConfigAck 
XMID_ReqWirelessConfig 
XMID_ReqWirelessConfigAck 
XMID_UpdateBias 
XMID_UpdateBiasAck 
XMID_ToggleIoPins 
XMID_ToggleIoPinsAck 
XMID_GotoOperational 
XMID_GotoOperationalAck 
XMID_SetTransportMode 
XMID_SetTransportModeAck 
XMID_ReqTransportMode 
XMID_ReqTransportModeAck 
XMID_AcceptMtw 
XMID_AcceptMtwAck 
XMID_RejectMtw 
XMID_RejectMtwAck 
XMID_InfoRequest 
XMID_InfoRequestAck 
XMID_ReqFrameRates 
XMID_ReqFrameRatesAck 
XMID_StartRecording 
XMID_StartRecordingAck 
XMID_StopRecording 
XMID_StopRecordingAck 
XMID_ReqOutputConfiguration 
XMID_ReqOutputConfigurationAck 
XMID_SetOutputConfiguration 
XMID_SetOutputConfigurationAck 
XMID_ReqOutputMode 
XMID_ReqOutputModeAck 
XMID_SetOutputMode 
XMID_SetOutputModeAck 
XMID_ReqOutputSettings 
XMID_ReqOutputSettingsAck 
XMID_SetOutputSettings 
XMID_SetOutputSettingsAck 
XMID_ReqOutputSkipFactor 
XMID_ReqOutputSkipFactorAck 
XMID_SetOutputSkipFactor 
XMID_SetOutputSkipFactorAck 
XMID_SetInitialHeading 
XMID_SetInitialHeadingAck 
XMID_ReqErrorMode 
XMID_ReqErrorModeAck 
XMID_SetErrorMode 
XMID_SetErrorModeAck 
XMID_ReqTransmitDelay 
XMID_ReqTransmitDelayAck 
XMID_SetTransmitDelay 
XMID_SetTransmitDelayAck 
XMID_SetMfmResults 
XMID_SetMfmResultsAck 
XMID_ReqObjectAlignment 
XMID_ReqObjectAlignmentAck 
XMID_SetObjectAlignment 
XMID_SetObjectAlignmentAck 
XMID_ForwardGnssData 
XMID_ForwardGnssDataAck 
XMID_ReqCanConfig 
XMID_SetCanConfig 
XMID_CanConfig 
XMID_SetCanConfigAck 
XMID_ReqCanOutputConfig 
XMID_SetCanOutputConfig 
XMID_CanOutputConfig 
XMID_SetCanOutputConfigAck 
XMID_ReqAlignmentRotation 
XMID_ReqAlignmentRotationAck 
XMID_SetAlignmentRotation 
XMID_SetAlignmentRotationAck 
XMID_ExtensionReserved1 
XMID_ExtensionReserved2 
XMID_SetDeviceIdContext 
XMID_SetDeviceIdContextAck 

Definition at line 73 of file xsxbusmessageid.h.



xsens_mti_driver
Author(s):
autogenerated on Sun Sep 3 2023 02:43:21