Public Member Functions | Static Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes | Friends | List of all members
XsDevice Struct Reference

#include <xsdevice_def.h>

Inheritance diagram for XsDevice:
Inheritance graph
[legend]

Public Member Functions

virtual bool abortFlushing ()
 Abort the wireless flushing operation and finalize the recording. More...
 
virtual bool abortLoadLogFile ()
 Aborts loading a logfile. More...
 
virtual double accelerometerRange () const
 Returns the maximum official value of the accelerometers in the device. More...
 
virtual bool acceptConnection ()
 Accept connections from the device on the parent/master device. More...
 
virtual XsAccessControlMode accessControlMode () const
 Request the access control mode of the master device. More...
 
virtual void addRef ()
 Increase reference count of XsDevice pointer XsDevice pointers stay alive while reference counter is not zero Also increases the reference count of each child device with 1. More...
 
virtual std::shared_ptr< ReplyObjectaddReplyObject (XsXbusMessageId messageId, uint8_t data)
 
virtual XsMatrix alignmentRotationMatrix (XsAlignmentFrame frame) const
 Retrieve the alignment rotation matrix to rotate S to the chosen frame S'. More...
 
virtual XsQuaternion alignmentRotationQuaternion (XsAlignmentFrame frame) const
 Retrieve the alignment rotation quaternion. More...
 
virtual XsResultValue applyConfigFile (const XsString &filename)
 Loads a config file(.xsa) and configures the device accordingly. More...
 
virtual bool areOptionsEnabled (XsOption options) const
 Returns true when all the specified processing options are enabled. More...
 
virtual XsFilterProfileArray availableOnboardFilterProfiles () const
 Return the list of filter profiles available on the device. More...
 
virtual XsFilterProfileArray availableXdaFilterProfiles () const
 Return the list of filter profiles available on the host PC. More...
 
virtual int batteryLevel () const
 Get the batterylevel of this device The battery level is a value between 0 and 100 that indicates the remaining capacity as a percentage. Due to battery characteristics, this is not directly the remaining time, but just a rough indication. More...
 
virtual XsTimeStamp batteryLevelTime ()
 Requests the time the battery level was last updated. More...
 
virtual XsBaudRate baudRate () const
 Get the baud rate (communication speed) of the serial port on which the given deviceId is connected. More...
 
virtual int busId () const
 The bus ID for this device. More...
 
int cacheSize () const
 Get the number of items currently in the slow data cache for the device. More...
 
virtual uint32_t canConfiguration () const
 Returns the currently configured CAN configuration of the device. More...
 
virtual XsCanOutputConfigurationArray canOutputConfiguration () const
 Returns the currently configured CAN output of the device. More...
 
virtual void XSNOEXPORT checkDataCache ()
 
virtual int childCount () const
 Return the number of child-devices this device has. For standalone devices this is always 0. More...
 
virtual std::vector< XsDevice * > children () const
 Return a managed array containing the child-devices this device has. For standalone devices this is always an empty array. More...
 
virtual bool closeLogFile ()
 Close the log file. More...
 
Communicator XSNOEXPORTcommunicator () const
 
virtual XsConnectivityState connectivityState () const
 Returns the connectivity state of the device. More...
 
virtual XsResultValue createConfigFile (const XsString &filename)
 Stores the current device configuration in a config file(.xsa) More...
 
XsResultValue createLogFile (const XsString &filename)
 Create a log file for logging. More...
 
virtual XsDeviceIdArray currentAccessControlList () const
 Request the access control list of the master device. More...
 
virtual int dataLength () const
 Returns the length of the data in the legacy MTData packets that the device will send in measurement mode. More...
 
virtual void XSNOEXPORT deinitializeSoftwareCalibration ()
 
virtual XsDevicedeviceAtBusId (int busid)
 Return the device with bus ID busid. More...
 
const XsDevicedeviceAtBusIdConst (int busid) const
 Return the device with bus ID busid. More...
 
virtual uint32_t deviceBufferSize ()
 Request the size of the interal buffer. More...
 
XsDeviceConfiguration deviceConfiguration () const
 Returns the device configuration. More...
 
virtual XsDeviceConfiguration const &XSNOEXPORT deviceConfigurationConst () const
 
XsDeviceConfiguration &XSNOEXPORT deviceConfigurationRef ()
 
XsDeviceId const & deviceId () const
 Return the device ID of the device. More...
 
virtual bool deviceIsDocked (XsDevice *dev) const
 Check if the device is docked. More...
 
virtual XsDeviceOptionFlag deviceOptionFlags () const
 Returns the device option flags. More...
 
virtual XsResultValue deviceParameter (XsDeviceParameter &parameter) const
 Retrieves the requested parameter's current value. More...
 
virtual XsDeviceState deviceState () const
 Return the state of this device. More...
 
virtual bool disableProtocol (XsProtocolType protocol)
 Disable a communication protocol previously added by XsDevice::enableProtocol. More...
 
virtual bool disableRadio ()
 Disables the radio for this station, resetting all children to disconnected state. More...
 
virtual void discardRetransmissions (int64_t firstNewPacketId)
 Tell XDA and the device that any data from before firstNewPacketId may be lossy. More...
 
virtual bool enableProtocol (XsProtocolType protocol)
 Enable an additional communication protocol when reading messages. More...
 
virtual bool enableRadio (int channel)
 Set the radio channel to use for wireless communication. More...
 
virtual XsErrorMode errorMode () const
 Returns the error mode of the device. More...
 
virtual XsDevicefindDevice (XsDeviceId const &deviceid) const
 Find the child device with deviceid. More...
 
XsDevice const * findDeviceConst (XsDeviceId const &deviceid) const
 Find the child device with deviceid. More...
 
virtual XsVersion firmwareVersion () const
 Return the firmware version. More...
 
virtual void flushInputBuffers ()
 Clear the inbound data buffers of the device. More...
 
virtual XsDataPacket getDataPacketByIndex (XsSize index) const
 Return the cached data packet with index. More...
 
XsSize getDataPacketCount () const
 Return the current size of the retained data packet cache. More...
 
virtual XsDevicegetDeviceFromLocationId (uint16_t locId)
 Get the device given locId. More...
 
XsOption getOptions () const
 Return the currently enabled options. More...
 
int64_t getStartRecordingPacketId () const
 Return the ID of the first packet that should be recorded. More...
 
int64_t getStopRecordingPacketId () const
 Return the ID of the last packet that should be recorded. More...
 
virtual XsVector gnssLeverArm () const
 
XSNOEXPORT XSDEPRECATED XsGnssPlatform gnssPlatform () const
 
virtual XsIntArray gnssReceiverSettings () const
 Gets some GNSS receiver settings. More...
 
virtual bool gotoConfig ()
 Put the device in config mode. More...
 
virtual bool gotoMeasurement ()
 Put this device in measurement mode. More...
 
virtual double gravityMagnitude () const
 Returns the 'Gravity Magnitude' of the device. More...
 
virtual double gyroscopeRange () const
 Returns the maximum official value of the gyroscopes in the device. More...
 
virtual XSNOEXPORT void handleDataPacket (const XsDataPacket &packet)
 
virtual XSNOEXPORT void handleErrorMessage (const XsMessage &msg)
 
virtual XSNOEXPORT void handleMasterIndication (const XsMessage &message)
 
virtual XSNOEXPORT void handleMessage (const XsMessage &msg)
 
virtual XSNOEXPORT void handleNonDataMessage (const XsMessage &msg)
 
virtual XSNOEXPORT void handleUnavailableData (int64_t frameNumber)
 
virtual XSNOEXPORT void handleWakeupMessage (const XsMessage &msg)
 
virtual XSNOEXPORT void handleWarningMessage (const XsMessage &msg)
 
virtual XsVersion hardwareVersion () const
 Return the hardware version of the device. More...
 
virtual bool hasDataEnabled (XsDataIdentifier dataType) const
 Returns if the currently configured output contains dataType. More...
 
virtual bool hasProcessedDataEnabled (XsDataIdentifier dataType) const
 Returns if the currently configured output contains dataType after processing on the host. More...
 
virtual double headingOffset () const
 Return the 'heading offset' setting of the device. More...
 
virtual bool XSNOEXPORT initialize ()
 
virtual bool XSNOEXPORT initializeSoftwareCalibration ()
 
virtual XsVector initialPositionLLA () const
 Gets the 'Latitude Longitude Altitude' setting of the device. More...
 
virtual bool isBlueToothEnabled () const
 Returns true if the device has its BlueTooth radio enabled. More...
 
virtual bool isBusPowerEnabled () const
 Returns if the Xbus is powering its child devices or not. More...
 
virtual bool isContainerDevice () const
 Returns true if this device can have child devices. More...
 
virtual bool isFixedGravityEnabled () const
 Returns if the fixed gravity value should be used or if it should be computed from the initialPositionLLA value. More...
 
virtual bool isInitialBiasUpdateEnabled () const
 Returns if the device does gyroscope bias estimation when switching to measurement mode. More...
 
bool isInitialized () const
 Returns true when the device is initialized. More...
 
virtual bool isInStringOutputMode () const
 Returns if the device is outputting data in string mode. More...
 
virtual bool isInSyncStationMode ()
 
bool isLoadLogFileInProgress () const
 Returns true if the file operation started by loadLogFile is still in progress. More...
 
bool isMasterDevice () const
 Returns true if this is the master device (not a child of another device) More...
 
virtual bool isMeasuring () const
 Returns true if the device is currently in a measuring state. More...
 
virtual bool isMotionTracker () const
 Returns true if this is a motion tracker. More...
 
virtual bool isOperational () const
 
virtual bool isProtocolEnabled (XsProtocolType protocol) const
 
virtual bool isRadioEnabled () const
 Returns if the radio is enabled. More...
 
virtual bool isReadingFromFile () const
 Returns true if the device is reading from a file. More...
 
virtual bool isRecording () const
 Returns true if the device is currently in a recording state. More...
 
bool isStandaloneDevice () const
 Returns true if this is a standalone device (not a child of another device and not a container device) More...
 
virtual bool isSyncMaster () const
 returns whether this device is in a master role regarding the device synchronization More...
 
virtual bool isSyncSlave () const
 returns whether this device is in a slave role regarding the device synchronization More...
 
XsDataPacket lastAvailableLiveData () const
 Return the last available live data. More...
 
virtual int16_t lastKnownRssi () const
 Returns the last known RSSI value of the device. More...
 
XsResultValue lastResult () const
 Get the result value of the last operation. More...
 
XsString lastResultText () const
 Get the accompanying error text for the value returned by lastResult() It may provide situation-specific information instead. More...
 
virtual bool loadLogFile ()
 Load a complete logfile. More...
 
virtual int locationId () const
 Get the location ID of the device. More...
 
virtual DataLogger XSNOEXPORTlogFileInterface (std::unique_ptr< xsens::Lock > &myLock) const
 
virtual XsString logFileName () const
 Get the name of the log file the device is reading from. More...
 
XsFilePos logFileReadPosition () const
 Get the current read position of the open log file. More...
 
XsFilePos logFileSize () const
 Get the size of the log file the device is reading from. More...
 
virtual bool makeOperational ()
 Sets the Awinda station to operational state. More...
 
virtual XsDevicemaster () const
 Return the master device of this device. More...
 
virtual int maximumUpdateRate () const
 Get the maximum update rate for the device. More...
 
virtual XSNOEXPORT bool messageLooksSane (const XsMessage &msg) const
 
xsens::GuardedMutexmutex () const
 
virtual XsMatrix objectAlignment () const
 Returns the object alignment matrix of the device. More...
 
virtual XsFilterProfile onboardFilterProfile () const
 Gets the filter profile in use by the device for computing orientations. More...
 
virtual XsOperationalMode operationalMode () const
 Returns the operational mode. More...
 
bool operator< (const XsDevice &dev) const
 Compare device ID with that of dev. More...
 
bool operator< (XsDeviceId const &devId) const
 Compare device ID with devId. More...
 
bool operator== (const XsDevice &dev) const
 Compare device ID with that of dev. More...
 
bool operator== (XsDeviceId const &devId) const
 Compare device ID with devId. More...
 
virtual XsOutputConfigurationArray outputConfiguration () const
 Returns the currently configured output of the device. More...
 
virtual int packetErrorRate () const
 Returns the packet error rate for the for the device. More...
 
virtual XsIntArray portConfiguration () const
 Get the current port configuration of a device. More...
 
virtual XsPortInfo portInfo () const
 The port information of the connection. More...
 
virtual XsString portName () const
 The port name of the connection. More...
 
virtual bool powerDown ()
 Tell the device to power down completely. More...
 
virtual XSNOEXPORT void prepareForTermination ()
 
virtual XsOutputConfigurationArray processedOutputConfiguration () const
 Return the full output configuration including post processing outputs. More...
 
virtual XsString productCode () const
 Return the product code of the device. More...
 
virtual int radioChannel () const
 Returns the radio channel used for wireless communication. More...
 
virtual XSNOEXPORT bool readEmtsAndDeviceConfiguration ()
 
virtual XsByteArray readMetaDataFromLogFile ()
 Returns internal meta-data about the recording that some devices store in the mtb logfile. More...
 
int recordingQueueLength () const
 Get the number of packets currently waiting in the slow data cache for the device based. More...
 
XsSize refCounter () const
 The current reference counter. More...
 
virtual bool reinitialize ()
 Reinitialize the XsDevice. More...
 
virtual bool rejectConnection ()
 Reject connections from the device on the parent/master device. More...
 
virtual XsRejectReason rejectReason () const
 Returns the reason why a device's connection was rejected. More...
 
virtual void removeRef ()
 Decrease this XsDevices reference counter with 1. More...
 
virtual bool reopenPort (bool gotoConfig, bool skipDeviceIdCheck=false)
 Reopens a port Uses rescan method to redetect a device. Also if USB descriptor has changed. More...
 
virtual bool replaceFilterProfile (XsFilterProfile const &profileCurrent, XsFilterProfile const &profileNew)
 Replaces profileCurrent by profileNew in the device. More...
 
virtual bool representativeMotionState ()
 Retrieves the active representative motion state for the In-Run Compass Calibration. More...
 
virtual bool requestBatteryLevel ()
 Request the battery level from the device. More...
 
virtual bool requestData ()
 Request data when configured in legacy mode with infinite skip factor. More...
 
virtual XSNOEXPORT bool requestUtcTime ()
 
virtual bool reset ()
 Reset the device. More...
 
virtual XSNOEXPORT bool reset (bool skipDeviceIdCheck)
 
virtual bool resetLogFileReadPosition ()
 Set the read position of the open log file to the start of the file. More...
 
virtual bool resetOrientation (XsResetMethod resetmethod)
 Perform an orientation reset on the device using the given resetMethod. More...
 
virtual void restartFilter ()
 Restart the software filter used by this device. More...
 
virtual bool restoreFactoryDefaults ()
 Restore the device to its factory default settings. More...
 
virtual uint16_t rs485TransmissionDelay () const
 Returns the transmission delay used for RS485 transmissions. More...
 
virtual XsSelfTestResult runSelfTest ()
 Run the self test for the device. More...
 
virtual bool sendCustomMessage (const XsMessage &messageSend, bool waitForResult, XsMessage &messageReceive, int timeout=0)
 Send a custom message messageSend to the device and possibly wait for a result. More...
 
virtual XSNOEXPORT bool sendCustomMessage (const XsMessage &messageSend, bool waitForResult, XsXbusMessageId messageId, XsMessage &messageReceive, int timeout=0)
 
virtual bool sendRawMessage (const XsMessage &message)
 Send a message directly to the communicator. More...
 
virtual XsBaudRate serialBaudRate () const
 The baud rate configured for cabled connection. More...
 
virtual bool setAccessControlMode (XsAccessControlMode mode, const XsDeviceIdArray &initialList)
 Set the access control mode of the master device. More...
 
virtual bool setAlignmentRotationMatrix (XsAlignmentFrame frame, const XsMatrix &matrix)
 Set an arbitrary alignment rotation matrix Use to rotate either L to the chosen frame L' or S to the chosen frame S'. More...
 
virtual bool setAlignmentRotationQuaternion (XsAlignmentFrame frame, const XsQuaternion &quat)
 Set an arbitrary alignment rotation quaternion. Use to rotate either L to the chosen frame L' or S to the chosen frame S'. More...
 
virtual bool setBlueToothEnabled (bool enabled)
 Enable or disable the BlueTooth radio of the device. More...
 
virtual bool setBusPowerEnabled (bool enabled)
 Tell the Xbus to provide power to its child devices or not. More...
 
virtual bool setCanConfiguration (uint32_t config)
 Set the CAN configuration for this device. More...
 
virtual bool setCanOutputConfiguration (XsCanOutputConfigurationArray &config)
 Set the CAN output configuration for this device. More...
 
virtual bool setDeviceAccepted (const XsDeviceId &deviceId)
 Accepts a device. More...
 
virtual bool setDeviceBufferSize (uint32_t frames)
 Request the device to set it's internal buffer to the specified size. More...
 
virtual bool setDeviceOptionFlags (XsDeviceOptionFlag setFlags, XsDeviceOptionFlag clearFlags)
 Set the device option flags. More...
 
virtual XsResultValue setDeviceParameter (XsDeviceParameter const &parameter)
 Sets the given parameter for the device. More...
 
virtual bool setDeviceRejected (const XsDeviceId &deviceId)
 Rejects a device. More...
 
virtual bool setErrorMode (XsErrorMode errormode)
 Sets the error mode of the device. More...
 
virtual bool setFixedGravityEnabled (bool enable)
 Sets whether the fixed gravity value should be used or if it should be computed from the initialPositionLLA value. More...
 
virtual bool setGnssLeverArm (const XsVector &arm)
 Sets the GNSS Lever Arm vector. More...
 
XSNOEXPORT virtual XSDEPRECATED bool setGnssPlatform (XsGnssPlatform gnssPlatform)
 
virtual bool setGnssReceiverSettings (const XsIntArray &gnssReceiverSettings)
 Sets some GNSS receiver settings. More...
 
void setGotoConfigOnClose (bool gotoConfigOnClose)
 On closePort the device will go to config by default, with this function it is possible to prevent that. More...
 
virtual bool setGravityMagnitude (double mag)
 Sets the 'Gravity Magnitude' of the device to the given value mag. More...
 
virtual bool setHeadingOffset (double offset)
 Set the 'heading offset' setting of the device. More...
 
virtual bool setInitialBiasUpdateEnabled (bool enable)
 Set if the device does gyroscope bias estimation when switching to measurement mode. More...
 
virtual bool setInitialPositionLLA (const XsVector &lla)
 Sets the 'Latitude Longitude Altitude' setting of the device to the given vector. More...
 
virtual bool setLocationId (int id)
 Set the location ID of the device. More...
 
virtual bool setNoRotation (uint16_t duration)
 Set the no rotation period to duration. More...
 
virtual bool setObjectAlignment (const XsMatrix &matrix)
 Sets the object alignment of the device to the given matrix. More...
 
virtual bool setOnboardFilterProfile (int profileType)
 Sets the filter profile to use for computing orientations on the device. More...
 
virtual bool setOnboardFilterProfile (XsString const &profileType)
 Sets the filter profile to use for computing orientations on the device. More...
 
virtual bool setOperationalMode (XsOperationalMode mode)
 Set the device in the given operational mode. More...
 
virtual void setOptions (XsOption enable, XsOption disable)
 Enable and disable processing options. More...
 
bool setOutputConfiguration (XsOutputConfigurationArray &config)
 Set the output configuration for this device. More...
 
virtual XSNOEXPORT void setPacketErrorRate (int per)
 
virtual bool setPortConfiguration (XsIntArray &config)
 Change the port configuration of a device. More...
 
virtual bool setRs485TransmissionDelay (uint16_t delay)
 Set the transmission delay used for RS485 transmissions. More...
 
virtual bool setSerialBaudRate (XsBaudRate baudrate)
 Change the serial baudrate to baudrate. More...
 
XSNOEXPORT void setSkipEmtsReadOnInit (bool skip)
 
virtual bool setStealthMode (bool enabled)
 Enable or disable stealth mode. More...
 
virtual bool setStringOutputMode (uint16_t type, uint16_t period, uint16_t skipFactor)
 Sets the string output mode for this device. More...
 
virtual bool setSyncSettings (const XsSyncSettingArray &settingList)
 Set the synchronization settings of the device. More...
 
virtual bool setSyncStationMode (bool enabled)
 Set the Sync Station mode of the Awinda Station device. More...
 
virtual bool setTransportMode (bool transportModeEnabled)
 Enable or disable the transport mode for the device. More...
 
virtual bool setUbloxGnssPlatform (XsUbloxGnssPlatform ubloxGnssPlatform)
 Set the device GNSS platform for u-blox GNSS receivers. More...
 
virtual bool setUpdateRate (int rate)
 Set the legacy update rate of the device. More...
 
virtual bool setUtcTime (const XsTimeInfo &time)
 Sets the 'UTC Time' setting of the device to the given time. More...
 
virtual bool setWirelessPriority (int priority)
 Sets the wireless priority of the device. More...
 
virtual bool setXdaFilterProfile (int profileType)
 Sets the filter profile to use for computing orientations on the host PC. More...
 
virtual bool setXdaFilterProfile (XsString const &profileType)
 Sets the filter profile to use for computing orientations on the host PC. More...
 
virtual XsString shortProductCode () const
 Return the shortened product code of the device suitable for display. More...
 
virtual bool startRecording ()
 Start recording incoming data. More...
 
virtual bool startRepresentativeMotion ()
 Let the user indicate that he is starting the representative motion for the In-Run Compass Calibration. More...
 
virtual bool stealthMode () const
 Return the state of the stealth mode setting. More...
 
virtual bool stopRecording ()
 Stop recording incoming data. More...
 
virtual XsIccRepMotionResult stopRepresentativeMotion ()
 Let the user indicate that he stopped the representative motion. More...
 
virtual bool storeFilterState ()
 Store orientation filter state in the device. More...
 
virtual bool storeIccResults ()
 Store the onboard ICC results for use by the device. More...
 
virtual uint16_t stringOutputType () const
 Returns the string output type. More...
 
virtual uint16_t stringSamplePeriod () const
 Returns the sample period for string output. More...
 
virtual uint16_t stringSkipFactor () const
 Returns the skipfactor for string output. More...
 
virtual XsDevicesubDevice (int subDeviceId) const
 Returns the sub-device at index index. More...
 
virtual int subDeviceCount () const
 Returns the number of sub-devices of this device. More...
 
virtual uint32_t supportedStatusFlags () const
 Returns a bitmask with all the status flags supported by this device. More...
 
virtual XsStringOutputTypeArray supportedStringOutputTypes () const
 Ask the device for its supported string output types. More...
 
virtual XsSyncSettingArray supportedSyncSettings () const
 Get all supported synchronization settings available on the device. More...
 
virtual std::vector< int > supportedUpdateRates (XsDataIdentifier dataType=XDI_None) const
 Ask the device for its supported update rates for the given dataType. More...
 
virtual XsSyncRole syncRole () const
 Returns the synchronization role of the device. More...
 
virtual XsSyncSettingArray syncSettings () const
 Get all the current synchronization settings of the device. More...
 
XsDataPacket takeFirstDataPacketInQueue ()
 Return the first packet in the packet queue or an empty packet if the queue is empty. More...
 
template<typename T >
XSNOEXPORT T * toType ()
 
virtual bool transportMode ()
 Returns the current state of the transport mode feature. More...
 
virtual bool triggerStartRecording ()
 Start recording incoming data through generating a virtual input trigger. More...
 
virtual XsUbloxGnssPlatform ubloxGnssPlatform () const
 Returns the device GNSS platform for u-blox GNSS receivers. More...
 
virtual bool updateCachedDeviceInformation ()
 Updates the cached device information for all devices connected to this port. More...
 
virtual XsResultValue updatePortInfo (XsPortInfo const &newInfo)
 Update the connection information, this is only useful for devices communicating over a dynamic link such as a TCP/IP connection. More...
 
virtual int updateRate () const
 Get the legacy update rate of the device. More...
 
virtual int updateRateForDataIdentifier (XsDataIdentifier dataType) const
 Returns the currently configured update rate for the supplied dataType. More...
 
virtual int updateRateForProcessedDataIdentifier (XsDataIdentifier dataType) const
 Returns the currently configured update rate for the supplied dataType. More...
 
virtual bool usesLegacyDeviceMode () const
 Returns whether the device uses legacy device mode. More...
 
virtual XsTimeInfo utcTime () const
 Gets the 'UTC Time' setting of the device. More...
 
virtual void waitForAllDevicesInitialized ()
 Wait until are known devices are initialized. More...
 
virtual XSNOEXPORT bool waitForCustomMessage (std::shared_ptr< ReplyObject > reply, XsMessage &messageReceive, int timeout)
 
virtual XSNOEXPORT bool waitForCustomMessage (XsXbusMessageId messageId, XsMessage &messageReceive, int timeout=0)
 
void waitForLoadLogFileDone () const
 Wait for the file operation started by loadLogFile to complete. More...
 
virtual int wirelessPriority () const
 Returns the wireless priority of the device. More...
 
virtual void writeDeviceSettingsToFile ()
 Write the emts/wms/xms of the device and all its children to the open logfile. More...
 
virtual XSNOEXPORT bool writeEmtsPage (uint8_t const *data, int pageNr, int bankNr)
 
virtual XsFilterProfile xdaFilterProfile () const
 Gets the filter profile in use for computing orientations on the host PC. More...
 
virtual XSNOEXPORT ~XsDevice ()
 Destroy the device. More...
 
- Public Member Functions inherited from CallbackManagerXda
void addCallbackHandler (XsCallbackPlainC *cb, bool chain=true)
 Add a handler to the list. More...
 
void addChainedManager (CallbackManagerXda *cm)
 Add a chained manager to the list. More...
 
 CallbackManagerXda ()
 Constructor, initializes the callback list. More...
 
void clearCallbackHandlers (bool chain=true)
 Clear the callback list. More...
 
void clearChainedManagers ()
 Clear the chained manager list. More...
 
void copyCallbackHandlersFrom (CallbackManagerXda *cm, bool chain=true)
 Copy all handlers from cm into this manager. More...
 
void copyCallbackHandlersTo (CallbackManagerXda *cm, bool chain=true)
 Copy all handlers from this manager into cm. More...
 
void onAllBufferedDataAvailable (XsDevicePtrArray *devs, const XsDataPacketPtrArray *packets) override
 The XsCallback::onAllBufferedDataAvailable() callback forwarding function. More...
 
void onAllDataAvailable (XsDevicePtrArray *devs, const XsDataPacketPtrArray *packets) override
 The XsCallback::onAllDataAvailable() callback forwarding function. More...
 
void onAllLiveDataAvailable (XsDevicePtrArray *devs, const XsDataPacketPtrArray *packets) override
 The XsCallback::onAllLiveDataAvailable() callback forwarding function. More...
 
void onAllRecordedDataAvailable (XsDevicePtrArray *devs, const XsDataPacketPtrArray *packets) override
 The XsCallback::onAllRecordedDataAvailable() callback forwarding function. More...
 
void onBufferedDataAvailable (XsDevice *dev, const XsDataPacket *data) override
 The XsCallback::onBufferedDataAvailable() callback forwarding function. More...
 
void onConnectivityChanged (XsDevice *dev, XsConnectivityState newState) override
 The XsCallback::onConnectivityChanged() callback forwarding function. More...
 
void onDataAvailable (XsDevice *dev, const XsDataPacket *data) override
 The XsCallback::onDataAvailable() callback forwarding function. More...
 
void onDataUnavailable (XsDevice *dev, int64_t packetId) override
 The XsCallback::onDataUnavailable() callback forwarding function. More...
 
void onDeviceStateChanged (XsDevice *dev, XsDeviceState newState, XsDeviceState oldState) override
 The XsCallback::onDeviceStateChanged() callback forwarding function. More...
 
void onError (XsDevice *dev, XsResultValue error) override
 The Xscallback::onError() callback forwarding function. More...
 
void onInfoResponse (XsDevice *dev, XsInfoRequest request) override
 The XsCallback::onInfoResponse() callback forwarding function. More...
 
void onLiveDataAvailable (XsDevice *dev, const XsDataPacket *packet) override
 The XsCallback::onLiveDataAvailable() callback forwarding function. More...
 
void onMessageDetected (XsDevice *dev, XsProtocolType type, XsByteArray const *rawMessage) override
 The Xscallback::onMessageReceivedFromDevice() callback forwarding function. More...
 
void onMessageReceivedFromDevice (XsDevice *dev, XsMessage const *message) override
 The Xscallback::onMessageReceivedFromDevice() callback forwarding function. More...
 
void onMessageSentToDevice (XsDevice *dev, XsMessage const *message) override
 The Xscallback::onMessageSentToDevice() callback forwarding function. More...
 
void onMissedPackets (XsDevice *dev, int count, int first, int last) override
 The XsCallback::onMissedPackets() callback forwarding function. More...
 
void onNonDataMessage (XsDevice *dev, XsMessage const *message) override
 The Xscallback::onNonDataMessage() callback forwarding function. More...
 
void onProgressUpdated (XsDevice *dev, int current, int total, const XsString *identifier) override
 The XsCallback::onProgressUpdated() callback forwarding function. More...
 
void onRecordedDataAvailable (XsDevice *dev, const XsDataPacket *data) override
 The XsCallback::onRecordedDataAvailable() callback forwarding function. More...
 
void onRestoreCommunication (const XsString *portName, XsResultValue result) override
 The Xscallback::onRestoreCommunication callback forwarding function. More...
 
void onTransmissionRequest (int channelId, const XsByteArray *data) override
 
void onWakeupReceived (XsDevice *dev) override
 The XsCallback::onWakeupReceived() callback forwarding function. More...
 
int onWriteMessageToLogFile (XsDevice *dev, const XsMessage *message) override
 The XsCallback::onWriteMessageToLogFile() callback forwarding function. More...
 
void removeCallbackHandler (XsCallbackPlainC *cb, bool chain=true)
 Remove a handler from the list. More...
 
void removeChainedManager (CallbackManagerXda *cm)
 Remove achained manager from the list. More...
 
 ~CallbackManagerXda ()
 Destructor, clears the callback list. More...
 

Static Public Member Functions

static bool isCompatibleSyncSetting (XsDeviceId const &deviceId, XsSyncSetting const &setting1, XsSyncSetting const &setting2)
 Determines whether setting1 is compatible with setting2 for deviceId deviceId. More...
 
static XsSyncSettingArray supportedSyncSettings (XsDeviceId const &deviceId)
 Return the supported synchronization settings for a specified deviceId or deviceId mask. More...
 
static bool supportsSyncSettings (XsDeviceId const &deviceId)
 Determines whether the device specified by deviceId supports sync settings. More...
 
static unsigned int syncSettingsTimeResolutionInMicroSeconds (XsDeviceId const &deviceId)
 

Protected Member Functions

virtual void clearExternalPacketCaches ()
 
virtual XsDevice const * firstChild () const
 
virtual bool interpolateMissingData (XsDataPacket const &pack, XsDataPacket const &prev, std::function< void(XsDataPacket *)> packetHandler)
 
void retainPacket (XsDataPacket const &pack)
 
void setCommunicator (Communicator *comm)
 
virtual void setRecordingStartFrame (uint16_t startFrame)
 
virtual void setRecordingStopFrame (uint16_t stopFrame)
 
virtual bool shouldDataMsgBeRecorded (const XsMessage &msg) const
 
virtual bool shouldDoRecordedCallback (XsDataPacket const &packet) const
 
bool skipEmtsReadOnInit () const
 
void updateLastAvailableLiveDataCache (XsDataPacket const &pack)
 
void useLogInterface (DataLogger *logger)
 Uses log interface for a given data logger. More...
 
 XSENS_DISABLE_COPY (XsDevice)
 

Static Protected Member Functions

static bool checkDataEnabled (XsDataIdentifier dataType, XsOutputConfigurationArray const &configurations)
 
static bool packetContainsRetransmission (XsDataPacket const &pack)
 

Protected Attributes

Communicatorm_communicator
 A communicator. More...
 
XsDeviceConfiguration m_config
 A device configuration. More...
 
XsConnectivityState m_connectivity
 A current device connectivity state. More...
 
DataPacketCache m_dataCache
 A data cache. More...
 
XsDeviceId m_deviceId
 An ID of the device. More...
 
xsens::GuardedMutex m_deviceMutex
 The mutex for guarding state changes of the device. More...
 
XsMessage m_emtsBlob
 An EMTS blob from device. More...
 
XsVersion m_firmwareVersion
 A firmware version. More...
 
bool m_gotoConfigOnClose
 Go to confing on close boolean variable. More...
 
bool m_isInitialized
 Is intialized boolean variable. More...
 
bool m_justWriteSetting
 Just write setting boolean variable. More...
 
XsDataPacketm_lastAvailableLiveDataCache
 A last available live data cache. More...
 
XsTimeStamp m_lastDataOkStamp
 A time stamp for an OK last data. More...
 
LastResultManager m_lastResult
 The last result of an operation. More...
 
XsDataPacketm_latestBufferedPacket
 A copy of the latest ready recording packet. This is the last packet that was popped off the front of m_dataCache. Use latestBufferedPacket() to access. More...
 
XsDataPacketm_latestLivePacket
 A copy of the latest ready live packet. This is the packet with the highest 64-bit sample counter so far. Use latestLivePacket() to access. More...
 
std::deque< XsDataPacket * > m_linearPacketCache
 A linear data packet cache. More...
 
DataLoggerm_logFileInterface
 A data logger for a file interface. More...
 
xsens::Mutex m_logFileMutex
 The mutex for guarding access to the log file. More...
 
XsDevicem_master
 A device object. More...
 
XsOption m_options
 The options. More...
 
XsOutputConfigurationArray m_outputConfiguration
 A devices output configuration. More...
 
PacketStamper m_packetStamper
 A packet stamper. More...
 
volatile std::atomic_int m_refCounter
 A reference counter. More...
 
bool m_skipEmtsReadOnInit
 Skip EMTS read on init boolean variable. More...
 
int64_t m_startRecordingPacketId
 The ID of the first packet that should be / was recorded. More...
 
XsDeviceState m_state
 A current device state. More...
 
int64_t m_stoppedRecordingPacketId
 The ID of the last packet that was recorded. Remains valid after Flushing has ended, until a new recording is started. More...
 
int64_t m_stopRecordingPacketId
 The ID of the last packet that should be / was recorded. Only valid in Recording/Flushing states. More...
 
bool m_terminationPrepared
 Termination prepared boolean variable. More...
 
DebugFileTypem_toaDumpFile
 To a dump file. More...
 
int64_t m_unavailableDataBoundary
 A packet ID of the last sample we know to be unavailable. More...
 
bool m_writeToFile
 Write to file boolean variable. More...
 

Friends

struct XsDeviceEx
 
class MtContainer
 
virtual XSNOEXPORT void onMessageSent (const XsMessage &message)
 
virtual XSNOEXPORT void onMessageReceived (const XsMessage &message)
 
virtual XSNOEXPORT void onMessageDetected2 (XsProtocolType type, const XsByteArray &rawMessage)
 
virtual XSNOEXPORT void onSessionRestarted ()
 
virtual XSNOEXPORT void onConnectionLost ()
 
virtual XSNOEXPORT void onEofReached ()
 
virtual XSNOEXPORT void onWirelessConnectionLost ()
 
virtual XSNOEXPORT int64_t deviceRecordingBufferItemCount (int64_t &lastCompletePacketId) const
 
void extractFirmwareVersion (XsMessage const &message)
 
virtual void setDeviceState (XsDeviceState state)
 
virtual void updateDeviceState (XsDeviceState state)
 
void removeIfNoRefs ()
 
virtual bool scheduleOrientationReset (XsResetMethod method)
 
 XsDevice (XsDeviceId const &id)
 Construct an empty device with device id id. More...
 
 XsDevice (Communicator *comm)
 Construct a device using inf for communication. More...
 
 XsDevice (XsDevice *master, const XsDeviceId &childDeviceId)
 Construct a device with device id childDeviceId for master masterDevice. More...
 
const XsDeviceConfigurationdeviceConfig () const
 
void setDeviceId (const XsDeviceId &deviceId)
 
XsOutputConfiguration findConfiguration (XsDataIdentifier dataType) const
 
virtual void writeMessageToLogFile (const XsMessage &message)
 
virtual void writeFilterStateToFile ()
 
virtual void processLivePacket (XsDataPacket &pack)
 
virtual void processBufferedPacket (XsDataPacket &pack)
 
virtual bool readDeviceConfiguration ()
 
XsDataPacketlatestLivePacket ()
 
XsDataPacketlatestBufferedPacket ()
 
XsDataPacket const & latestLivePacketConst () const
 
XsDataPacket const & latestBufferedPacketConst () const
 
virtual int64_t latestLivePacketId () const
 
virtual int64_t latestBufferedPacketId () const
 
virtual void resetPacketStamping ()
 
void updateConnectivityState (XsConnectivityState newState)
 
virtual XsConnectivityState defaultChildConnectivityState () const
 
void setInitialized (bool initialized)
 Set the initialized state to initialized. More...
 
void setTerminationPrepared (bool prepared) NOEXCEPT
 Set the "termination prepared" state to prepared. More...
 
virtual bool shouldWriteMessageToLogFile (const XsMessage &msg) const
 
virtual bool shouldWriteMessageToLogFile (const XsDevice *dev, const XsMessage &message) const
 
virtual XsResultValue setOutputConfigurationInternal (XsOutputConfigurationArray &config)
 
bool doTransaction (const XsMessage &snd) const
 
bool doTransaction (const XsMessage &snd, XsMessage &rcv) const
 
bool doTransaction (const XsMessage &snd, XsMessage &rcv, uint32_t timeout) const
 
bool doTransaction (const XsMessage &snd, uint32_t timeout) const
 
bool justWriteSetting () const
 
virtual void clearProcessors ()
 
virtual void clearDataCache ()
 
virtual void insertIntoDataCache (int64_t pid, XsDataPacket *pack)
 
virtual void reinitializeProcessors ()
 
virtual bool expectingRetransmissionForPacket (int64_t packetId) const
 
virtual bool resetRemovesPort () const
 
virtual bool isSoftwareFilteringEnabled () const
 
virtual bool isSoftwareCalibrationEnabled () const
 
virtual void setStartRecordingPacketId (int64_t startFrame)
 
virtual void setStopRecordingPacketId (int64_t stopFrame)
 
virtual void endRecordingStream ()
 
virtual void clearCacheToRecordingStart ()
 
void setFirmwareVersion (const XsVersion &version)
 

Detailed Description

Definition at line 164 of file xsdevice_def.h.

Constructor & Destructor Documentation

◆ ~XsDevice()

XsDevice::~XsDevice ( )
virtual

Destroy the device.

Definition at line 274 of file xsdevice_def.cpp.

◆ XsDevice() [1/3]

XsDevice::XsDevice ( XsDeviceId const &  id)
explicitprotected

Construct an empty device with device id id.

Parameters
idThe device ID to construct with

Definition at line 165 of file xsdevice_def.cpp.

◆ XsDevice() [2/3]

XsDevice::XsDevice ( Communicator comm)
explicitprotected

Construct a device using inf for communication.

Using this constructor implies that this device is a master device (master() returns this).

Parameters
commThe Communicator to use for this device

Definition at line 197 of file xsdevice_def.cpp.

◆ XsDevice() [3/3]

XsDevice::XsDevice ( XsDevice masterDevice,
const XsDeviceId childDeviceId 
)
explicitprotected

Construct a device with device id childDeviceId for master masterDevice.

Parameters
masterDeviceThe master device ID to construct for
childDeviceIdThe child device ID to construct with

Communication uses masterDevice's channel

Definition at line 245 of file xsdevice_def.cpp.

Member Function Documentation

◆ abortFlushing()

bool XsDevice::abortFlushing ( )
virtual

Abort the wireless flushing operation and finalize the recording.

Returns
true if no flushing is in progress when the function exits
Note
Awinda Station only

Reimplemented in BroadcastDevice.

Definition at line 3537 of file xsdevice_def.cpp.

◆ abortLoadLogFile()

bool XsDevice::abortLoadLogFile ( )
virtual

Aborts loading a logfile.

Returns
true if loading is aborted successfully
Note
if no file was currently loading returns false

Definition at line 3062 of file xsdevice_def.cpp.

◆ accelerometerRange()

double XsDevice::accelerometerRange ( ) const
virtual

Returns the maximum official value of the accelerometers in the device.

The actual official range is -accelerometerRange() .. accelerometerRange(). The device may send out higher values than this for extreme movements, but then the data quality can not be guaranteed.

Returns
The maximum value of the accelerometers in m/s^2

Reimplemented in MtDevice.

Definition at line 2716 of file xsdevice_def.cpp.

◆ acceptConnection()

bool XsDevice::acceptConnection ( )
virtual

Accept connections from the device on the parent/master device.

This function can be used to accept connections from a device that has been rejected. Call this function from within the onConnectivityChanged callback.

Returns
true if the device will be accepted next time it tries to connect
Note
MTw rejected to Awinda Station only

Definition at line 3548 of file xsdevice_def.cpp.

◆ accessControlMode()

XsAccessControlMode XsDevice::accessControlMode ( ) const
virtual

Request the access control mode of the master device.

Returns
The currently configured access control mode
See also
setAccessControlMode
currentAccessControlList

Definition at line 3760 of file xsdevice_def.cpp.

◆ addRef()

void XsDevice::addRef ( )
virtual

Increase reference count of XsDevice pointer XsDevice pointers stay alive while reference counter is not zero Also increases the reference count of each child device with 1.

Definition at line 3810 of file xsdevice_def.cpp.

◆ addReplyObject()

virtual std::shared_ptr<ReplyObject> XsDevice::addReplyObject ( XsXbusMessageId  messageId,
uint8_t  data 
)
virtual

◆ alignmentRotationMatrix()

XsMatrix XsDevice::alignmentRotationMatrix ( XsAlignmentFrame  frame) const
virtual

Retrieve the alignment rotation matrix to rotate S to the chosen frame S'.

Parameters
frameThe frame of which to return the alignment rotation
Returns
The alignment rotation
See also
setAlignmentRotationQuaternion, alignmentRotationQuaternion, setAlignmentRotationMatrix

Reimplemented in MtiBaseDevice.

Definition at line 2132 of file xsdevice_def.cpp.

◆ alignmentRotationQuaternion()

XsQuaternion XsDevice::alignmentRotationQuaternion ( XsAlignmentFrame  frame) const
virtual

Retrieve the alignment rotation quaternion.

Parameters
frameThe frame of which to return the alignment rotation
Returns
The alignment rotation
See also
setAlignmentRotationQuaternion, setAlignmentRotationMatrix, alignmentRotationMatrix

Reimplemented in MtiBaseDevice.

Definition at line 2106 of file xsdevice_def.cpp.

◆ applyConfigFile()

XsResultValue XsDevice::applyConfigFile ( const XsString filename)
virtual

Loads a config file(.xsa) and configures the device accordingly.

Parameters
[in]filenameThe desired path and filename of the config file
Returns
Result value indicating success (XRV_OK) or failure

Definition at line 2142 of file xsdevice_def.cpp.

◆ areOptionsEnabled()

bool XsDevice::areOptionsEnabled ( XsOption  options) const
virtual

Returns true when all the specified processing options are enabled.

Parameters
optionsThe options to check
Returns
true if the options are enabled
See also
setOptions

Definition at line 3434 of file xsdevice_def.cpp.

◆ availableOnboardFilterProfiles()

XsFilterProfileArray XsDevice::availableOnboardFilterProfiles ( ) const
virtual

Return the list of filter profiles available on the device.

Returns
The list of filter profiles available for computing orientations on the device
See also
availableXdaFilterProfiles
onboardFilterProfile
setOnboardFilterProfile

Reimplemented in MtDevice.

Definition at line 2696 of file xsdevice_def.cpp.

◆ availableXdaFilterProfiles()

XsFilterProfileArray XsDevice::availableXdaFilterProfiles ( ) const
virtual

Return the list of filter profiles available on the host PC.

Returns
The list of filter profiles available for computing orientations on the host PC
See also
availableOnboardFilterProfiles
xdaFilterProfile
setXdaFilterProfile

Definition at line 2705 of file xsdevice_def.cpp.

◆ batteryLevel()

int XsDevice::batteryLevel ( ) const
virtual

Get the batterylevel of this device The battery level is a value between 0 and 100 that indicates the remaining capacity as a percentage. Due to battery characteristics, this is not directly the remaining time, but just a rough indication.

Bodypack: The amount of time remaining for measurement given any battery level greatly depends on the type of batteries used, the number of sensors attached to the Bodypack and the used output options. Mtw: The last known battery level for this motion tracker. First call

See also
requestBatteryLevel to have a battery level available. The callback
onInfoResponse with ID XIR_BatteryLevel will indicate when the requested battery level is available. This function is available in both config and measurement mode. For devices in wired mode this function can be called without calling
requestBatteryLevel first
Returns
The battery level in the range 0-100

Definition at line 535 of file xsdevice_def.cpp.

◆ batteryLevelTime()

XsTimeStamp XsDevice::batteryLevelTime ( )
virtual

Requests the time the battery level was last updated.

Returns
the XsTimeStamp the battery level was last set

Reimplemented in BroadcastDevice.

Definition at line 2981 of file xsdevice_def.cpp.

◆ baudRate()

XsBaudRate XsDevice::baudRate ( ) const
virtual

Get the baud rate (communication speed) of the serial port on which the given deviceId is connected.

This differs from the serialBaudRate() function in that it will only return the baud rate of the current connection, whereas the serialBaudRate() function will return the configured value for a serial connection even if the device is currently not configured for serial communication (ie when it is connected with a direct USB cable or wirelessly).

Returns
The baud rate of the serial connection or XBR_Invalid

Definition at line 849 of file xsdevice_def.cpp.

◆ busId()

int XsDevice::busId ( ) const
virtual

The bus ID for this device.

Returns
The bus ID of the device

Definition at line 860 of file xsdevice_def.cpp.

◆ cacheSize()

int XsDevice::cacheSize ( ) const

Get the number of items currently in the slow data cache for the device.

Returns
The actual number of items in the cache, which may contain huge gaps in packet ids

Definition at line 3131 of file xsdevice_def.cpp.

◆ canConfiguration()

uint32_t XsDevice::canConfiguration ( ) const
virtual

Returns the currently configured CAN configuration of the device.

Returns
The can configuration of the device

Reimplemented in Mti6X0Device, and Mti8X0Device.

Definition at line 3396 of file xsdevice_def.cpp.

◆ canOutputConfiguration()

XsCanOutputConfigurationArray XsDevice::canOutputConfiguration ( ) const
virtual

Returns the currently configured CAN output of the device.

Returns
The can output configuration of the device

Reimplemented in Mti6X0Device, and Mti8X0Device.

Definition at line 3388 of file xsdevice_def.cpp.

◆ checkDataCache()

virtual void XSNOEXPORT XsDevice::checkDataCache ( )
virtual

◆ checkDataEnabled()

static bool XsDevice::checkDataEnabled ( XsDataIdentifier  dataType,
XsOutputConfigurationArray const &  configurations 
)
staticprotected

◆ childCount()

int XsDevice::childCount ( ) const
virtual

Return the number of child-devices this device has. For standalone devices this is always 0.

Returns
The number of child devices of the device

Definition at line 4085 of file xsdevice_def.cpp.

◆ children()

std::vector< XsDevice * > XsDevice::children ( ) const
virtual

Return a managed array containing the child-devices this device has. For standalone devices this is always an empty array.

Returns
An array of pointers to the child devices of the device

Reimplemented in BroadcastDevice.

Definition at line 4093 of file xsdevice_def.cpp.

◆ clearCacheToRecordingStart()

virtual void XsDevice::clearCacheToRecordingStart ( )
protectedvirtual

◆ clearDataCache()

virtual void XsDevice::clearDataCache ( )
protectedvirtual

◆ clearExternalPacketCaches()

virtual void XsDevice::clearExternalPacketCaches ( )
protectedvirtual

◆ clearProcessors()

virtual void XsDevice::clearProcessors ( )
protectedvirtual

◆ closeLogFile()

bool XsDevice::closeLogFile ( )
virtual

Close the log file.

Returns
true if the log file was successfully closed or never open

Reimplemented in BroadcastDevice.

Definition at line 2150 of file xsdevice_def.cpp.

◆ communicator()

Communicator XSNOEXPORT* XsDevice::communicator ( ) const

◆ connectivityState()

XsConnectivityState XsDevice::connectivityState ( ) const
virtual

Returns the connectivity state of the device.

The connectivity describes how and if the device is connected to XDA.

Returns
The current connectivity of the device
See also
XsConnectivityState

Definition at line 3663 of file xsdevice_def.cpp.

◆ createConfigFile()

XsResultValue XsDevice::createConfigFile ( const XsString filename)
virtual

Stores the current device configuration in a config file(.xsa)

Parameters
[in]filenameThe desired path and filename of the config file
Returns
Result value indicating success (XRV_OK) or failure

Definition at line 2082 of file xsdevice_def.cpp.

◆ createLogFile()

XsResultValue XsDevice::createLogFile ( const XsString filename)

Create a log file for logging.

Parameters
filenameThe desired path and filename of the log file
Returns
Result value indicating success (XRV_OK) or failure

Definition at line 2038 of file xsdevice_def.cpp.

◆ currentAccessControlList()

XsDeviceIdArray XsDevice::currentAccessControlList ( ) const
virtual

Request the access control list of the master device.

Returns
The currently configured access control list. This can be either a blacklist or a whitelist.
See also
setAccessControlMode
accessControlMode

Definition at line 3769 of file xsdevice_def.cpp.

◆ dataLength()

int XsDevice::dataLength ( ) const
virtual

Returns the length of the data in the legacy MTData packets that the device will send in measurement mode.

This function will only return a value when the device is configured for legacy output, otherwise it will return 0.

Returns
The data size of the MTData packets that will be sent by the device
See also
setDeviceMode
deviceMode

Definition at line 825 of file xsdevice_def.cpp.

◆ defaultChildConnectivityState()

virtual XsConnectivityState XsDevice::defaultChildConnectivityState ( ) const
protectedvirtual

◆ deinitializeSoftwareCalibration()

virtual void XSNOEXPORT XsDevice::deinitializeSoftwareCalibration ( )
virtual

◆ deviceAtBusId()

XsDevice * XsDevice::deviceAtBusId ( int  busid)
virtual

Return the device with bus ID busid.

Parameters
busidThe busid to serach for
Returns
The XsDevice corresponding to the supplied busid

Definition at line 767 of file xsdevice_def.cpp.

◆ deviceAtBusIdConst()

const XsDevice * XsDevice::deviceAtBusIdConst ( int  busid) const

Return the device with bus ID busid.

Parameters
busidThe busid to serach for
Returns
The const XsDevice corresponding to the supplied busid

Definition at line 778 of file xsdevice_def.cpp.

◆ deviceBufferSize()

uint32_t XsDevice::deviceBufferSize ( )
virtual

Request the size of the interal buffer.

Returns
Buffer size in number of frames

Definition at line 4319 of file xsdevice_def.cpp.

◆ deviceConfig()

const XsDeviceConfiguration& XsDevice::deviceConfig ( ) const
inlineprotected
Returns
A const reference to the cached device configuration

Definition at line 556 of file xsdevice_def.h.

◆ deviceConfiguration()

XsDeviceConfiguration XsDevice::deviceConfiguration ( ) const

Returns the device configuration.

The device configuration contains a summary of the devices connected to the same port. The function will always return the configuration for the port's main device.

Returns
A copy of the device configuration of the port

Definition at line 1945 of file xsdevice_def.cpp.

◆ deviceConfigurationConst()

virtual XsDeviceConfiguration const& XSNOEXPORT XsDevice::deviceConfigurationConst ( ) const
virtual

◆ deviceConfigurationRef()

XsDeviceConfiguration& XSNOEXPORT XsDevice::deviceConfigurationRef ( )

◆ deviceId()

XsDeviceId const & XsDevice::deviceId ( ) const

Return the device ID of the device.

Each Xsens device has a unique ID. The ID identifies the device as well as the product family it belongs to.

Returns
The device ID

Definition at line 742 of file xsdevice_def.cpp.

◆ deviceIsDocked()

bool XsDevice::deviceIsDocked ( XsDevice dev) const
virtual

Check if the device is docked.

Checks if device dev is docked in this device

Parameters
devThe device to check
Returns
true if the device is docked in this device

Definition at line 3673 of file xsdevice_def.cpp.

◆ deviceOptionFlags()

XsDeviceOptionFlag XsDevice::deviceOptionFlags ( ) const
virtual

Returns the device option flags.

Returns
The current configured device option flags

Reimplemented in MtDevice.

Definition at line 562 of file xsdevice_def.cpp.

◆ deviceParameter()

XsResultValue XsDevice::deviceParameter ( XsDeviceParameter parameter) const
virtual

Retrieves the requested parameter's current value.

Retrieving device parameters is only valid after initialization

Parameters
parametera parameter object, corresponding to a row in the table listed under XsDevice::setParameter
Returns
Result value indicating success (XRV_OK) or unsupported with current or current firmware version (XRV_UNSUPPORTED)
See also
XsDevice::setParameter

Definition at line 4468 of file xsdevice_def.cpp.

◆ deviceRecordingBufferItemCount()

virtual XSNOEXPORT int64_t XsDevice::deviceRecordingBufferItemCount ( int64_t &  lastCompletePacketId) const
virtual

◆ deviceState()

XsDeviceState XsDevice::deviceState ( ) const
virtual

Return the state of this device.

The device state indiciates whether the device is in config mode, measuring, recording, etc

Returns
The state of the device

Definition at line 1064 of file xsdevice_def.cpp.

◆ disableProtocol()

bool XsDevice::disableProtocol ( XsProtocolType  protocol)
virtual

Disable a communication protocol previously added by XsDevice::enableProtocol.

Parameters
protocolThe type of protocol-support to remove.
Returns
true if the removal was successful
Note
This is a per port or per file setting

Definition at line 3304 of file xsdevice_def.cpp.

◆ disableRadio()

bool XsDevice::disableRadio ( )
virtual

Disables the radio for this station, resetting all children to disconnected state.

Returns
true if the radio was successfully disabled
Note
Awinda Station only

Definition at line 3488 of file xsdevice_def.cpp.

◆ discardRetransmissions()

void XsDevice::discardRetransmissions ( int64_t  firstNewPacketId)
virtual

Tell XDA and the device that any data from before firstNewPacketId may be lossy.

Tell the device to not request retransmissions of missed data older than the supplied firstNewPacketId. If firstNewPacketId is beyond the end of the recording or beyond the highest received packet ID, the lower value is used instead. This means that you can't set this for future packets.

Parameters
firstNewPacketIdThe first packet that (if missing) should be retransmitted.
Note
This applies to master devices that support retransmissions only: Awinda and Bodypack.

Definition at line 4598 of file xsdevice_def.cpp.

◆ doTransaction() [1/4]

bool XsDevice::doTransaction ( const XsMessage snd) const
protected

◆ doTransaction() [2/4]

bool XsDevice::doTransaction ( const XsMessage snd,
uint32_t  timeout 
) const
protected

◆ doTransaction() [3/4]

bool XsDevice::doTransaction ( const XsMessage snd,
XsMessage rcv 
) const
protected

◆ doTransaction() [4/4]

bool XsDevice::doTransaction ( const XsMessage snd,
XsMessage rcv,
uint32_t  timeout 
) const
protected

◆ enableProtocol()

bool XsDevice::enableProtocol ( XsProtocolType  protocol)
virtual

Enable an additional communication protocol when reading messages.

Parameters
protocolThe type of protocol-support to add.
Returns
true if the addition was successful
Note
This is a per port or per file setting

Definition at line 3280 of file xsdevice_def.cpp.

◆ enableRadio()

bool XsDevice::enableRadio ( int  channel)
virtual

Set the radio channel to use for wireless communication.

This function can be used to enable or disable the radio of an Awinda Station.

Parameters
channelA valid channel number in the range [11..25] or -1 to disable the radio
Returns
true if the radio was successfully reconfigured
Note
Awinda Station only

Definition at line 3478 of file xsdevice_def.cpp.

◆ endRecordingStream()

virtual void XsDevice::endRecordingStream ( )
protectedvirtual

◆ errorMode()

XsErrorMode XsDevice::errorMode ( ) const
virtual

Returns the error mode of the device.

The error mode tells the device what to do if a problem occurs.

Returns
The currently configured error mode of the device
See also
setErrorMode

Reimplemented in MtiBaseDevice, and MtDevice.

Definition at line 2463 of file xsdevice_def.cpp.

◆ expectingRetransmissionForPacket()

virtual bool XsDevice::expectingRetransmissionForPacket ( int64_t  packetId) const
protectedvirtual

◆ extractFirmwareVersion()

void XsDevice::extractFirmwareVersion ( XsMessage const &  message)
protected

◆ findConfiguration()

XsOutputConfiguration XsDevice::findConfiguration ( XsDataIdentifier  dataType) const
protected

◆ findDevice()

XsDevice * XsDevice::findDevice ( XsDeviceId const &  deviceid) const
virtual

Find the child device with deviceid.

This function returns the child device of the current device that matches the given ID.

Parameters
deviceidThe device ID to search for
Returns
A pointer to the found XsDevice or 0 if the device could not be found

Definition at line 500 of file xsdevice_def.cpp.

◆ findDeviceConst()

XsDevice const * XsDevice::findDeviceConst ( XsDeviceId const &  deviceid) const

Find the child device with deviceid.

This function returns the child device of the current device that matches the given ID.

Parameters
deviceidThe device ID to search for
Returns
A pointer to the found XsDevice or 0 if the device could not be found

Definition at line 512 of file xsdevice_def.cpp.

◆ firmwareVersion()

XsVersion XsDevice::firmwareVersion ( ) const
virtual

Return the firmware version.

Returns
The firmware version of the live device
Note
The firmware version is not stored in mtb files, so when reading from file this function will return an empty XsVersion object

Definition at line 675 of file xsdevice_def.cpp.

◆ firstChild()

virtual XsDevice const* XsDevice::firstChild ( ) const
protectedvirtual

◆ flushInputBuffers()

void XsDevice::flushInputBuffers ( )
virtual

Clear the inbound data buffers of the device.

Reimplemented in BroadcastDevice.

Definition at line 1807 of file xsdevice_def.cpp.

◆ getDataPacketByIndex()

XsDataPacket XsDevice::getDataPacketByIndex ( XsSize  index) const
virtual

Return the cached data packet with index.

Parameters
indexThe requested index, this does not have to be the same as the packet counter
Returns
The requested packet or an empty packet if index is out of range
Note
This only works if XSO_RetainLiveData or XSO_RetainBufferedData was set before the data was read
See also
getDataPacketCount
setOptions

Definition at line 4193 of file xsdevice_def.cpp.

◆ getDataPacketCount()

XsSize XsDevice::getDataPacketCount ( ) const

Return the current size of the retained data packet cache.

Returns
The current size of the cache
See also
getDataPacketCount
setOptions

Definition at line 4206 of file xsdevice_def.cpp.

◆ getDeviceFromLocationId()

XsDevice * XsDevice::getDeviceFromLocationId ( uint16_t  locId)
virtual

Get the device given locId.

\param locId the location ID of the device we're looking for
\returns a pointer to the device if found, nullptr otherwise.

Definition at line 2527 of file xsdevice_def.cpp.

◆ getOptions()

XsOption XsDevice::getOptions ( ) const

Return the currently enabled options.

Returns
The options that are enabled for this device and its child devices (if any)
See also
setOptions
areOptionsEnabled

Definition at line 3443 of file xsdevice_def.cpp.

◆ getStartRecordingPacketId()

int64_t XsDevice::getStartRecordingPacketId ( ) const

Return the ID of the first packet that should be recorded.

This is only valid in Recording or Flushing states

Returns
The ID of the first packet that should be recorded

Definition at line 4374 of file xsdevice_def.cpp.

◆ getStopRecordingPacketId()

int64_t XsDevice::getStopRecordingPacketId ( ) const

Return the ID of the last packet that should be recorded.

This is only valid in Recording or Flushing states or in Measurement after a recording has finished

Returns
The ID of the last packet that should be / was recorded

Definition at line 4383 of file xsdevice_def.cpp.

◆ gnssLeverArm()

XsVector XsDevice::gnssLeverArm ( ) const
virtual
Returns
The GNSS Lever Arm vector.

Reimplemented in Mti6X0Device, and MTi7_MTi8Device.

Definition at line 2953 of file xsdevice_def.cpp.

◆ gnssPlatform()

XSNOEXPORT XSDEPRECATED XsGnssPlatform XsDevice::gnssPlatform ( ) const

◆ gnssReceiverSettings()

XsIntArray XsDevice::gnssReceiverSettings ( ) const
virtual

Gets some GNSS receiver settings.

Returns
XsIntArray containing the receiver settings

Reimplemented in MtDevice.

Definition at line 4520 of file xsdevice_def.cpp.

◆ gotoConfig()

bool XsDevice::gotoConfig ( )
virtual

Put the device in config mode.

Device settings can only be changed in config mode, since changing anything during measurement would mess up the sample timing.

Returns
true if the device was successfully put in config mode or was already in config mode
See also
gotoMeasurement

Reimplemented in BroadcastDevice.

Definition at line 1014 of file xsdevice_def.cpp.

◆ gotoMeasurement()

bool XsDevice::gotoMeasurement ( )
virtual

Put this device in measurement mode.

Measurement mode is where the device is sampling data and producing inertial and orientation output.

Returns
true if the device was successfully put in measurement mode or was already in measurement mode
See also
gotoConfig

Reimplemented in BroadcastDevice.

Definition at line 960 of file xsdevice_def.cpp.

◆ gravityMagnitude()

double XsDevice::gravityMagnitude ( ) const
virtual

Returns the 'Gravity Magnitude' of the device.

The Gravity Magnitude is the strength of the gravity where the measurements are done. Setting this value precisely allows for more accurate measurements.

Returns
The current 'Gravity Magnitude' setting of the device.
See also
setGravityMagnitude
setInitialPositionLLA
initialPositionLLA

Definition at line 2566 of file xsdevice_def.cpp.

◆ gyroscopeRange()

double XsDevice::gyroscopeRange ( ) const
virtual

Returns the maximum official value of the gyroscopes in the device.

The actual official range is -gyroscopeRange() .. gyroscopeRange(). The device may send out higher values than this for extreme movements, but then the data quality can not be guaranteed.

Returns
The maximum value of the gyroscopes in degrees/s

Reimplemented in MtDevice.

Definition at line 2727 of file xsdevice_def.cpp.

◆ handleDataPacket()

virtual XSNOEXPORT void XsDevice::handleDataPacket ( const XsDataPacket packet)
virtual

◆ handleErrorMessage()

virtual XSNOEXPORT void XsDevice::handleErrorMessage ( const XsMessage msg)
virtual

◆ handleMasterIndication()

virtual XSNOEXPORT void XsDevice::handleMasterIndication ( const XsMessage message)
virtual

◆ handleMessage()

virtual XSNOEXPORT void XsDevice::handleMessage ( const XsMessage msg)
virtual

◆ handleNonDataMessage()

virtual XSNOEXPORT void XsDevice::handleNonDataMessage ( const XsMessage msg)
virtual

◆ handleUnavailableData()

virtual XSNOEXPORT void XsDevice::handleUnavailableData ( int64_t  frameNumber)
virtual

◆ handleWakeupMessage()

virtual XSNOEXPORT void XsDevice::handleWakeupMessage ( const XsMessage msg)
virtual

◆ handleWarningMessage()

virtual XSNOEXPORT void XsDevice::handleWarningMessage ( const XsMessage msg)
virtual

◆ hardwareVersion()

XsVersion XsDevice::hardwareVersion ( ) const
virtual

Return the hardware version of the device.

Returns
The hardware version of the device

Reimplemented in BroadcastDevice, and MtDevice.

Definition at line 3467 of file xsdevice_def.cpp.

◆ hasDataEnabled()

bool XsDevice::hasDataEnabled ( XsDataIdentifier  dataType) const
virtual

Returns if the currently configured output contains dataType.

Parameters
dataTypeThe type of data to check the output for.
Returns
true if dataType is configured for output
See also
outputConfiguration
hasProcessedDataEnabled
updateRateForDataIdentifier

Definition at line 632 of file xsdevice_def.cpp.

◆ hasProcessedDataEnabled()

bool XsDevice::hasProcessedDataEnabled ( XsDataIdentifier  dataType) const
virtual

Returns if the currently configured output contains dataType after processing on the host.

Where hasDataEnabled() only checks the outputs configured in the device, this function also checks what can and will be computed from the data.

Parameters
dataTypeThe type of data to check the output for.
Returns
true if dataType is configured for output
See also
hasDataEnabled
processedOutputConfiguration
updateRateForDataIdentifier

Definition at line 665 of file xsdevice_def.cpp.

◆ headingOffset()

double XsDevice::headingOffset ( ) const
virtual

Return the 'heading offset' setting of the device.

Returns
The currently configured heading offset in degrees

Reimplemented in MtDevice.

Definition at line 2495 of file xsdevice_def.cpp.

◆ initialize()

virtual bool XSNOEXPORT XsDevice::initialize ( )
virtual

Reimplemented in MtDevice, and BroadcastDevice.

◆ initializeSoftwareCalibration()

virtual bool XSNOEXPORT XsDevice::initializeSoftwareCalibration ( )
virtual

◆ initialPositionLLA()

XsVector XsDevice::initialPositionLLA ( ) const
virtual

Gets the 'Latitude Longitude Altitude' setting of the device.

The Latitude Longitude Altitude contains the location on earth where the measurements are done. Setting this value allows for more accurate measurements. Note: this XDA data type is the setting initialPositionLLA, which is set by setInitialPositionLLA. It's value is therefore static. Use LatitudeLongitude to retrieve the live position data from the MTi.

Returns
lla The desired 'Latitude Longitude Altitude' setting for the device.
See also
setInitialPositionLLA
gravityMagnitude

Reimplemented in MtDevice.

Definition at line 2793 of file xsdevice_def.cpp.

◆ insertIntoDataCache()

virtual void XsDevice::insertIntoDataCache ( int64_t  pid,
XsDataPacket pack 
)
protectedvirtual

◆ interpolateMissingData()

virtual bool XsDevice::interpolateMissingData ( XsDataPacket const &  pack,
XsDataPacket const &  prev,
std::function< void(XsDataPacket *)>  packetHandler 
)
protectedvirtual

◆ isBlueToothEnabled()

bool XsDevice::isBlueToothEnabled ( ) const
virtual

Returns true if the device has its BlueTooth radio enabled.

Returns
true if the device has its BlueTooth radio enabled
See also
setBlueToothEnabled

Definition at line 2413 of file xsdevice_def.cpp.

◆ isBusPowerEnabled()

bool XsDevice::isBusPowerEnabled ( ) const
virtual

Returns if the Xbus is powering its child devices or not.

When the bus power is off, the child devices are disabled

Returns
true If the Xbus is currently providing power to its child devices

Definition at line 2432 of file xsdevice_def.cpp.

◆ isCompatibleSyncSetting()

bool XsDevice::isCompatibleSyncSetting ( XsDeviceId const &  deviceId,
XsSyncSetting const &  setting1,
XsSyncSetting const &  setting2 
)
static

Determines whether setting1 is compatible with setting2 for deviceId deviceId.

Parameters
[in]deviceIdThe device id
[in]setting1Setting 1
[in]setting2Setting 2
Returns
true when setting1 is compatible with setting2 for deviceId deviceId

Definition at line 4068 of file xsdevice_def.cpp.

◆ isContainerDevice()

bool XsDevice::isContainerDevice ( ) const
virtual

Returns true if this device can have child devices.

Returns
true if this is a container device

Definition at line 1094 of file xsdevice_def.cpp.

◆ isFixedGravityEnabled()

bool XsDevice::isFixedGravityEnabled ( ) const
virtual

Returns if the fixed gravity value should be used or if it should be computed from the initialPositionLLA value.

Returns
true if the option is enabled
See also
setFixedGravityEnabled
gravityMagnitude
initialPositionLLA

Definition at line 2923 of file xsdevice_def.cpp.

◆ isInitialBiasUpdateEnabled()

bool XsDevice::isInitialBiasUpdateEnabled ( ) const
virtual

Returns if the device does gyroscope bias estimation when switching to measurement mode.

When this option is enabled, the device will automatically run the 'no rotation' algorithm every time it switches to measurement mode.

Returns
true if the option is enabled
See also
setNoRotation
setInitialBiasUpdateEnabled

Definition at line 2900 of file xsdevice_def.cpp.

◆ isInitialized()

bool XsDevice::isInitialized ( ) const

Returns true when the device is initialized.

Returns
true when the device has been initialized

Definition at line 3721 of file xsdevice_def.cpp.

◆ isInStringOutputMode()

bool XsDevice::isInStringOutputMode ( ) const
virtual

Returns if the device is outputting data in string mode.

In string mode only NMEA packets are transmitted at the legacy update rate

Returns
true if the device is configured for string mode output.

Definition at line 3014 of file xsdevice_def.cpp.

◆ isInSyncStationMode()

bool XsDevice::isInSyncStationMode ( )
virtual
Returns
true when the device is in Sync Station mode (Awinda Station and Sync Station only)

Definition at line 3792 of file xsdevice_def.cpp.

◆ isLoadLogFileInProgress()

bool XsDevice::isLoadLogFileInProgress ( ) const

Returns true if the file operation started by loadLogFile is still in progress.

Returns
true if the file operation started by loadLogFile is still in progress
See also
loadLogFile
waitForLoadLogFileDone

Definition at line 4349 of file xsdevice_def.cpp.

◆ isMasterDevice()

bool XsDevice::isMasterDevice ( ) const

Returns true if this is the master device (not a child of another device)

Returns
true if this is the master device

Definition at line 1086 of file xsdevice_def.cpp.

◆ isMeasuring()

bool XsDevice::isMeasuring ( ) const
virtual

Returns true if the device is currently in a measuring state.

Returns
true if the device is currently in a measuring state

Reimplemented in BroadcastDevice.

Definition at line 1741 of file xsdevice_def.cpp.

◆ isMotionTracker()

bool XsDevice::isMotionTracker ( ) const
virtual

Returns true if this is a motion tracker.

Returns
true if this is a motion tracker or false if it is a master device such as an Awinda Station or a Bodypack

Reimplemented in MtDevice.

Definition at line 813 of file xsdevice_def.cpp.

◆ isOperational()

bool XsDevice::isOperational ( ) const
virtual
Returns
true when the device is operational
See also
AwindaStationDevice::makeOperational()

Definition at line 3786 of file xsdevice_def.cpp.

◆ isProtocolEnabled()

bool XsDevice::isProtocolEnabled ( XsProtocolType  protocol) const
virtual
Returns
true when a protocol with type type has been added
Parameters
[in]protocolThe protocol type to check

Definition at line 3326 of file xsdevice_def.cpp.

◆ isRadioEnabled()

bool XsDevice::isRadioEnabled ( ) const
virtual

Returns if the radio is enabled.

Returns
true if the radio is enabled
Note
Awinda Sation only

Definition at line 3497 of file xsdevice_def.cpp.

◆ isReadingFromFile()

bool XsDevice::isReadingFromFile ( ) const
virtual

Returns true if the device is reading from a file.

Returns
true if the device is reading from a file

Reimplemented in BroadcastDevice.

Definition at line 1783 of file xsdevice_def.cpp.

◆ isRecording()

bool XsDevice::isRecording ( ) const
virtual

Returns true if the device is currently in a recording state.

Returns
true if the device is currently in a recording state

Reimplemented in BroadcastDevice.

Definition at line 1762 of file xsdevice_def.cpp.

◆ isSoftwareCalibrationEnabled()

virtual bool XsDevice::isSoftwareCalibrationEnabled ( ) const
protectedvirtual

◆ isSoftwareFilteringEnabled()

virtual bool XsDevice::isSoftwareFilteringEnabled ( ) const
protectedvirtual

◆ isStandaloneDevice()

bool XsDevice::isStandaloneDevice ( ) const

Returns true if this is a standalone device (not a child of another device and not a container device)

Returns
true if this is a standalone device, equivalent to !isContainerDevice() && isMasterDevice()

Definition at line 1102 of file xsdevice_def.cpp.

◆ isSyncMaster()

bool XsDevice::isSyncMaster ( ) const
virtual

returns whether this device is in a master role regarding the device synchronization

Returns
true if the device has a synchronization master role

Definition at line 750 of file xsdevice_def.cpp.

◆ isSyncSlave()

bool XsDevice::isSyncSlave ( ) const
virtual

returns whether this device is in a slave role regarding the device synchronization

Returns
true if the device has a synchronization slave role

Definition at line 758 of file xsdevice_def.cpp.

◆ justWriteSetting()

bool XsDevice::justWriteSetting ( ) const
inlineprotected
Returns
The value of the m_justWriteSetting flag, which is used in file-based processing

Definition at line 642 of file xsdevice_def.h.

◆ lastAvailableLiveData()

XsDataPacket XsDevice::lastAvailableLiveData ( ) const

Return the last available live data.

Returns
A packet containing the latest available live data. This packet will contain the latest data of each appropriate type, so it may contain old data mixed with new data if different data comes in at different speeds.
Note
This only works if XSO_KeepLastLiveData is set
See also
setOptions

Definition at line 4218 of file xsdevice_def.cpp.

◆ lastKnownRssi()

int16_t XsDevice::lastKnownRssi ( ) const
virtual

Returns the last known RSSI value of the device.

RSSI values are only relevant for wireless devices. Since the value is measured passively, any time an RSSI value is received by XDA, the last known value is updated.

Returns
The last known biased RSSI value or XS_RSSI_UNKNOWN if no RSSI value is available (yet)

Definition at line 3624 of file xsdevice_def.cpp.

◆ lastResult()

XsResultValue XsDevice::lastResult ( ) const

Get the result value of the last operation.

The result values are codes that describe a failure in more detail.

Returns
the last known error code
See also
resultText(XsResultValue), lastResultText()

Definition at line 794 of file xsdevice_def.cpp.

◆ lastResultText()

XsString XsDevice::lastResultText ( ) const

Get the accompanying error text for the value returned by lastResult() It may provide situation-specific information instead.

Returns
a human readable error description
See also
resultText(XsResultValue), lastResult()

Definition at line 804 of file xsdevice_def.cpp.

◆ latestBufferedPacket()

XsDataPacket& XsDevice::latestBufferedPacket ( )
inlineprotected
Returns
A reference to the cached latest buffered packet

Definition at line 582 of file xsdevice_def.h.

◆ latestBufferedPacketConst()

XsDataPacket const& XsDevice::latestBufferedPacketConst ( ) const
inlineprotected
Returns
A const reference to the cached latest buffered packet

Definition at line 596 of file xsdevice_def.h.

◆ latestBufferedPacketId()

virtual int64_t XsDevice::latestBufferedPacketId ( ) const
protectedvirtual

◆ latestLivePacket()

XsDataPacket& XsDevice::latestLivePacket ( )
inlineprotected
Returns
A reference to the cached latest received packet

Definition at line 575 of file xsdevice_def.h.

◆ latestLivePacketConst()

XsDataPacket const& XsDevice::latestLivePacketConst ( ) const
inlineprotected
Returns
A const reference to the cached latest received packet

Definition at line 589 of file xsdevice_def.h.

◆ latestLivePacketId()

virtual int64_t XsDevice::latestLivePacketId ( ) const
protectedvirtual

◆ loadLogFile()

bool XsDevice::loadLogFile ( )
virtual

Load a complete logfile.

Load the opened log file completely. This function loads all data from the open logfile in a separate thread, generating onProgressUpdated callbacks. This function will return true if the reading was scheduled.

Returns
true if the threaded loading was successfully started
See also
onProgressUpdated

Reimplemented in BroadcastDevice.

Definition at line 3045 of file xsdevice_def.cpp.

◆ locationId()

int XsDevice::locationId ( ) const
virtual

Get the location ID of the device.

The location ID is a custom 16-bit ID that can be assigned to a device.

Returns
The current location ID stord in the device
See also
setLocationId

Reimplemented in MtDevice.

Definition at line 2517 of file xsdevice_def.cpp.

◆ logFileInterface()

virtual DataLogger XSNOEXPORT* XsDevice::logFileInterface ( std::unique_ptr< xsens::Lock > &  myLock) const
virtual

◆ logFileName()

XsString XsDevice::logFileName ( ) const
virtual

Get the name of the log file the device is reading from.

Returns an empty string when not in file mode.

Returns
The name of the logfile

Definition at line 3078 of file xsdevice_def.cpp.

◆ logFileReadPosition()

XsFilePos XsDevice::logFileReadPosition ( ) const

Get the current read position of the open log file.

If the function encounters an error the function returns -1.

Returns
The current read position (in bytes) from the start of the file or -1
Note
This is a low-level file operation.
See also
logFileSize

Definition at line 3236 of file xsdevice_def.cpp.

◆ logFileSize()

XsFilePos XsDevice::logFileSize ( ) const

Get the size of the log file the device is reading from.

If the function encounters an error the function returns 0.

Returns
The size of the log file or 0
Note
This is a low-level file operation.
See also
logFileReadPosition

Definition at line 3219 of file xsdevice_def.cpp.

◆ makeOperational()

bool XsDevice::makeOperational ( )
virtual

Sets the Awinda station to operational state.

Note
this is considered an extension to the config state, not a new state.
Returns
true when the awindastation is put in operational mode.

Definition at line 3778 of file xsdevice_def.cpp.

◆ master()

XsDevice * XsDevice::master ( ) const
virtual

Return the master device of this device.

This function returns the master device of the current device. This may be the device itself

Returns
The master device of this device

Definition at line 332 of file xsdevice_def.cpp.

◆ maximumUpdateRate()

int XsDevice::maximumUpdateRate ( ) const
virtual

Get the maximum update rate for the device.

Returns
The maximum update rate of the device
See also
supportedUpdateRates

Definition at line 3102 of file xsdevice_def.cpp.

◆ messageLooksSane()

virtual XSNOEXPORT bool XsDevice::messageLooksSane ( const XsMessage msg) const
virtual

Reimplemented in MtDevice.

◆ mutex()

xsens::GuardedMutex* XsDevice::mutex ( ) const
inline
Returns
The device mutex.

Definition at line 498 of file xsdevice_def.h.

◆ objectAlignment()

XsMatrix XsDevice::objectAlignment ( ) const
virtual

Returns the object alignment matrix of the device.

Returns
The current 'object alignment matrix' setting of the device.
Note
This is legacy functionality to support backwards compatibility with older devices. For MT Mk4 devices it is suggested to use alignmentRotationQuaternion or alignmentRotationMatrix instead.
See also
setObjectAlignmentMatrix()
headingOffset()
setHeadingOffset()
alignmentRotationQuaternion
alignmentRotationMatrix

Definition at line 2541 of file xsdevice_def.cpp.

◆ onboardFilterProfile()

XsFilterProfile XsDevice::onboardFilterProfile ( ) const
virtual

Gets the filter profile in use by the device for computing orientations.

Returns
The filter profile in use when computing orientations is done on the device
See also
setOnboardFilterProfile
xdaFilterProfile

Reimplemented in MtDevice.

Definition at line 2646 of file xsdevice_def.cpp.

◆ onConnectionLost()

virtual XSNOEXPORT void XsDevice::onConnectionLost ( )
virtual

◆ onEofReached()

virtual XSNOEXPORT void XsDevice::onEofReached ( )
virtual

◆ onMessageDetected2()

virtual XSNOEXPORT void XsDevice::onMessageDetected2 ( XsProtocolType  type,
const XsByteArray rawMessage 
)
virtual

◆ onMessageReceived()

virtual XSNOEXPORT void XsDevice::onMessageReceived ( const XsMessage message)
virtual

◆ onMessageSent()

virtual XSNOEXPORT void XsDevice::onMessageSent ( const XsMessage message)
virtual

◆ onSessionRestarted()

virtual XSNOEXPORT void XsDevice::onSessionRestarted ( )
virtual

◆ onWirelessConnectionLost()

virtual XSNOEXPORT void XsDevice::onWirelessConnectionLost ( )
virtual

◆ operationalMode()

XsOperationalMode XsDevice::operationalMode ( ) const
virtual

Returns the operational mode.

Returns
The current operational mode of the device

Definition at line 3362 of file xsdevice_def.cpp.

◆ operator<() [1/2]

bool XsDevice::operator< ( const XsDevice dev) const
inline

Compare device ID with that of dev.

Parameters
devDevice to compare against
Returns
true if dev has a higher device ID
See also
deviceId()

Definition at line 226 of file xsdevice_def.h.

◆ operator<() [2/2]

bool XsDevice::operator< ( XsDeviceId const &  devId) const
inline

Compare device ID with devId.

Parameters
devIdDeviceId to compare against
Returns
true if devId is higher than the contained device ID
See also
deviceId()

Definition at line 236 of file xsdevice_def.h.

◆ operator==() [1/2]

bool XsDevice::operator== ( const XsDevice dev) const
inline

Compare device ID with that of dev.

Parameters
devDevice to compare against
Returns
true if dev has the same device ID
See also
deviceId()

Definition at line 231 of file xsdevice_def.h.

◆ operator==() [2/2]

bool XsDevice::operator== ( XsDeviceId const &  devId) const
inline

Compare device ID with devId.

Parameters
devIdDeviceId to compare against
Returns
true if devId is the same as the contained device ID
See also
deviceId()

Definition at line 241 of file xsdevice_def.h.

◆ outputConfiguration()

XsOutputConfigurationArray XsDevice::outputConfiguration ( ) const
virtual

Returns the currently configured output of the device.

Returns
The output configuration of the device

Reimplemented in MtDevice, and MtiBaseDevice.

Definition at line 3380 of file xsdevice_def.cpp.

◆ packetContainsRetransmission()

static bool XsDevice::packetContainsRetransmission ( XsDataPacket const &  pack)
staticprotected

◆ packetErrorRate()

int XsDevice::packetErrorRate ( ) const
virtual

Returns the packet error rate for the for the device.

The packet error rate indicates the proportion of data packets from the device that are lost or corrupted in some manner over some time window. Depending on the device the packet error rate may be updated actively or passively, and the time window may vary, so packet error rates cannot be compared directly between different types of device.

Note
Not all devices support packet error rate estimation. Those that don't will always report a 0% packet error rate.
Returns
The packet error rate as a percentage.

Definition at line 3653 of file xsdevice_def.cpp.

◆ portConfiguration()

XsIntArray XsDevice::portConfiguration ( ) const
virtual

Get the current port configuration of a device.

Remarks
Only Mti6x0 devices supported
Returns
The current port configurations of the device
See also
setPortConfiguration, XsBaudCode

Reimplemented in Mti6X0Device, and Mti8X0Device.

Definition at line 910 of file xsdevice_def.cpp.

◆ portInfo()

XsPortInfo XsDevice::portInfo ( ) const
virtual

The port information of the connection.

Returns
The port information object containing the information of the communication port or an empty structure if not connected to a communication port

Definition at line 3696 of file xsdevice_def.cpp.

◆ portName()

XsString XsDevice::portName ( ) const
virtual

The port name of the connection.

Returns
The name of the communication port or an empty string if not connected to a communication port

Definition at line 3683 of file xsdevice_def.cpp.

◆ powerDown()

bool XsDevice::powerDown ( )
virtual

Tell the device to power down completely.

This function can be used to tell the device to shut down completely, requiring a physical button press on the device to power up again.

Returns
true if the device was successfully powered down

Definition at line 2454 of file xsdevice_def.cpp.

◆ prepareForTermination()

virtual XSNOEXPORT void XsDevice::prepareForTermination ( )
virtual

◆ processBufferedPacket()

virtual void XsDevice::processBufferedPacket ( XsDataPacket pack)
protectedvirtual

◆ processedOutputConfiguration()

XsOutputConfigurationArray XsDevice::processedOutputConfiguration ( ) const
virtual

Return the full output configuration including post processing outputs.

This function return the list returned by outputConfiguration() and adds outputs that become available during post-processing.

Returns
The requested output configuration list

Definition at line 1209 of file xsdevice_def.cpp.

◆ processLivePacket()

virtual void XsDevice::processLivePacket ( XsDataPacket pack)
protectedvirtual

◆ productCode()

XsString XsDevice::productCode ( ) const
virtual

Return the product code of the device.

Returns
The product code of the device

Reimplemented in BroadcastDevice, and MtDevice.

Definition at line 3451 of file xsdevice_def.cpp.

◆ radioChannel()

int XsDevice::radioChannel ( ) const
virtual

Returns the radio channel used for wireless communication.

Returns
The radio channel used for wireless communication or -1 if the radio is disabled
Note
Awinda Sation only

Definition at line 3506 of file xsdevice_def.cpp.

◆ readDeviceConfiguration()

virtual bool XsDevice::readDeviceConfiguration ( )
protectedvirtual

◆ readEmtsAndDeviceConfiguration()

virtual XSNOEXPORT bool XsDevice::readEmtsAndDeviceConfiguration ( )
virtual

◆ readMetaDataFromLogFile()

XsByteArray XsDevice::readMetaDataFromLogFile ( )
virtual

Returns internal meta-data about the recording that some devices store in the mtb logfile.

Returns
Internal meta-data about the recording that some devices store in the mtb logfile

Definition at line 4652 of file xsdevice_def.cpp.

◆ recordingQueueLength()

int XsDevice::recordingQueueLength ( ) const

Get the number of packets currently waiting in the slow data cache for the device based.

Returns
The highest received packet ID minus the last reported packet id in the slow data callback

Definition at line 3118 of file xsdevice_def.cpp.

◆ refCounter()

XsSize XsDevice::refCounter ( ) const

The current reference counter.

Returns
The current reference count

Definition at line 3819 of file xsdevice_def.cpp.

◆ reinitialize()

bool XsDevice::reinitialize ( )
virtual

Reinitialize the XsDevice.

This function will read all configuration details freshly from the device and will reinitialize all filters. Especially when you have made changes to the device configuration outside XDA or through sendCustomMessage() it is advisable to call this function so XDA will show the correct state of the device.

Returns
true if the device was successfully reinitialized
Note
The device itself is not reset, but will be put in config mode while the settings are being updated.

Reimplemented in MtDevice.

Definition at line 2594 of file xsdevice_def.cpp.

◆ reinitializeProcessors()

virtual void XsDevice::reinitializeProcessors ( )
protectedvirtual

◆ rejectConnection()

bool XsDevice::rejectConnection ( )
virtual

Reject connections from the device on the parent/master device.

This function can be used to reject connections from a device that has connected. This function can be called from within the onConnectivityChanged callback or at other times when a device is connected.

Returns
true if the device will be rejected next time it tries to connect
Note
After the function returns, this XsDevice should no longer be used.
MTw connected to Awinda Station only
See also
rejectReason

Definition at line 3562 of file xsdevice_def.cpp.

◆ rejectReason()

XsRejectReason XsDevice::rejectReason ( ) const
virtual

Returns the reason why a device's connection was rejected.

This function is typically called from within the onConnectivityChanged callback when the connectivity has changed to XCS_Rejected.

Returns
The reason why the connection was rejected

Definition at line 3614 of file xsdevice_def.cpp.

◆ removeIfNoRefs()

void XsDevice::removeIfNoRefs ( )
protected

◆ removeRef()

void XsDevice::removeRef ( )
virtual

Decrease this XsDevices reference counter with 1.

Also decreases the reference count of each child with 1

  • If it is a child device, it will delete itself when the reference count reaches zero. It will also remove itself from its master's child list and ask the master if it can be deleted
  • If it is a master device, it will delete itself when the reference count reaches zero and the reference count of all children is zero.

Definition at line 3831 of file xsdevice_def.cpp.

◆ reopenPort()

bool XsDevice::reopenPort ( bool  gotoConfig,
bool  skipDeviceIdCheck = false 
)
virtual

Reopens a port Uses rescan method to redetect a device. Also if USB descriptor has changed.

Parameters
gotoConfigSet to true if the device should be put to config before port closure
skipDeviceIdCheckSet to true if the rescan should not verify the device id (not recommended)
Returns
true if successful

Definition at line 2017 of file xsdevice_def.cpp.

◆ replaceFilterProfile()

bool XsDevice::replaceFilterProfile ( XsFilterProfile const &  profileCurrent,
XsFilterProfile const &  profileNew 
)
virtual

Replaces profileCurrent by profileNew in the device.

Parameters
profileCurrentThe profile that should be replaced
profileNewThe new profile
Returns
true if successful, false otherwise
Note
The default implementation does nothing as this feature requires the full XDA

Definition at line 2685 of file xsdevice_def.cpp.

◆ representativeMotionState()

bool XsDevice::representativeMotionState ( )
virtual

Retrieves the active representative motion state for the In-Run Compass Calibration.

Returns
true if the reprensentation motion state is active, false otherwise

Reimplemented in MtiBaseDevice.

Definition at line 2762 of file xsdevice_def.cpp.

◆ requestBatteryLevel()

bool XsDevice::requestBatteryLevel ( )
virtual

Request the battery level from the device.

This is an asynchronous operation. The Awinda station or MTw sends the battery level when possible. For devices in wired mode the

See also
batteryLevel() function can be called without calling this function first.
Returns
true If the battery level request was successfully sent

Reimplemented in BroadcastDevice.

Definition at line 2973 of file xsdevice_def.cpp.

◆ requestData()

bool XsDevice::requestData ( )
virtual

Request data when configured in legacy mode with infinite skip factor.

When configured in legacy mode and an output skip factor of 0xFFFF, the device will not send data by itself, but will instead send the latest data after receiving an explicit request. This function is that request. After the request, the normal callback mechanism will take over.

Returns
true if the message was successfully sent.

Reimplemented in MtDevice.

Definition at line 2875 of file xsdevice_def.cpp.

◆ requestUtcTime()

virtual XSNOEXPORT bool XsDevice::requestUtcTime ( )
virtual

◆ reset() [1/2]

bool XsDevice::reset ( )
virtual

Reset the device.

This function tells the device to reboot itself.

Returns
true if the device was successfully reset

Definition at line 1971 of file xsdevice_def.cpp.

◆ reset() [2/2]

virtual XSNOEXPORT bool XsDevice::reset ( bool  skipDeviceIdCheck)
virtual

Reimplemented in BroadcastDevice.

◆ resetLogFileReadPosition()

bool XsDevice::resetLogFileReadPosition ( )
virtual

Set the read position of the open log file to the start of the file.

If software filtering is enabled, the appropriate filters will be restarted as if the file was just opened.

Returns
true if the read position was successfully reset to the start of the file
Note
This is a low-level file operation.

Reimplemented in MtDevice, and BroadcastDevice.

Definition at line 3198 of file xsdevice_def.cpp.

◆ resetOrientation()

bool XsDevice::resetOrientation ( XsResetMethod  resetmethod)
virtual

Perform an orientation reset on the device using the given resetMethod.

This function schedules an orientation reset command to be applied in the first available orientation filter update.

Parameters
resetmethodThe requested orientation reset method.
Returns
true if the orientation reset was successfully scheduled
Note
XRM_StoreAlignmentMatrix can only be used in config mode, the others only in measurement mode

Reimplemented in BroadcastDevice.

Definition at line 3187 of file xsdevice_def.cpp.

◆ resetPacketStamping()

virtual void XsDevice::resetPacketStamping ( )
protectedvirtual

◆ resetRemovesPort()

virtual bool XsDevice::resetRemovesPort ( ) const
protectedvirtual

Reimplemented in MtiBaseDevice.

◆ restartFilter()

void XsDevice::restartFilter ( )
virtual

Restart the software filter used by this device.

Definition at line 785 of file xsdevice_def.cpp.

◆ restoreFactoryDefaults()

bool XsDevice::restoreFactoryDefaults ( )
virtual

Restore the device to its factory default settings.

Returns
true if the settings have been successfully restored

Reimplemented in BroadcastDevice, and MtDevice.

Definition at line 1953 of file xsdevice_def.cpp.

◆ retainPacket()

void XsDevice::retainPacket ( XsDataPacket const &  pack)
protected

◆ rs485TransmissionDelay()

uint16_t XsDevice::rs485TransmissionDelay ( ) const
virtual

Returns the transmission delay used for RS485 transmissions.

See the low level documentation for more information on this function.

Returns
The currently configured RS485 transmission delay

Reimplemented in MtDevice, and MtiBaseDevice.

Definition at line 2841 of file xsdevice_def.cpp.

◆ runSelfTest()

XsSelfTestResult XsDevice::runSelfTest ( )
virtual

Run the self test for the device.

All Xsens devices have limited self-diagnostic functionality, which can be triggered by calling this function. The device automatically does some self tests during startup, but this function returns more information.

Returns
Results of the test
Note
This function is blocking and can take a few 100 ms

Reimplemented in MtDevice.

Definition at line 2864 of file xsdevice_def.cpp.

◆ scheduleOrientationReset()

virtual bool XsDevice::scheduleOrientationReset ( XsResetMethod  method)
protectedvirtual

Reimplemented in MtDevice.

◆ sendCustomMessage() [1/2]

bool XsDevice::sendCustomMessage ( const XsMessage messageSend,
bool  waitForResult,
XsMessage messageReceive,
int  timeout = 0 
)
virtual

Send a custom message messageSend to the device and possibly wait for a result.

If waitForResult is true, the function will wait for a result and put it in the given messageReceive. Otherwise the contents of messageReceive will not be altered. If an error message is received or the wait times out, messageReceive will contain an error message.

Parameters
messageSendThe message to send to the device
waitForResulttrue if it is required that the function waits for the appropriate reply. A valid reply always has a message ID that is one higher than the sent message ID.
messageReceiveWhen waitForResult is true, the reply will be put in this object.
timeoutOptional timeout in ms. When 0 is supplied (the default), the default timeout is used.
Returns
true if the message was successfully sent and when waitForResult is true the correct reply has been received

Definition at line 1302 of file xsdevice_def.cpp.

◆ sendCustomMessage() [2/2]

virtual XSNOEXPORT bool XsDevice::sendCustomMessage ( const XsMessage messageSend,
bool  waitForResult,
XsXbusMessageId  messageId,
XsMessage messageReceive,
int  timeout = 0 
)
virtual

◆ sendRawMessage()

bool XsDevice::sendRawMessage ( const XsMessage message)
virtual

Send a message directly to the communicator.

Parameters
[in]messageThe message that will be sent
Returns
true if the message was successfully sent

Definition at line 1311 of file xsdevice_def.cpp.

◆ serialBaudRate()

XsBaudRate XsDevice::serialBaudRate ( ) const
virtual

The baud rate configured for cabled connection.

This differs from the baudRate() function in that it will return the configured value for a serial connection even if the device is currently not configured for serial communication (ie when it is connected with a direct USB cable or wirelessly), whereas the baudRate() function will return the baud rate of the current connection.

Returns
The configured baud rate

Reimplemented in MtDevice.

Definition at line 837 of file xsdevice_def.cpp.

◆ setAccessControlMode()

bool XsDevice::setAccessControlMode ( XsAccessControlMode  mode,
const XsDeviceIdArray initialList 
)
virtual

Set the access control mode of the master device.

The access control mode determines which connections are allowed.

Parameters
modeThe access control mode to use, the choice is between blacklist or whitelist
initialListThe initial list to use for the selected access control mode
Returns
true if the access control mode was successfully changed
See also
accessControlMode()
currentAccessControlList

Definition at line 3751 of file xsdevice_def.cpp.

◆ setAlignmentRotationMatrix()

bool XsDevice::setAlignmentRotationMatrix ( XsAlignmentFrame  frame,
const XsMatrix matrix 
)
virtual

Set an arbitrary alignment rotation matrix Use to rotate either L to the chosen frame L' or S to the chosen frame S'.

Parameters
frameThe frame to rotate
matrixThe desired alignment rotation setting of the device. This should be an orthonormal 3x3 matrix.
Returns
true if the alignment rotation has been set successfully
See also
setAlignmentRotationQuaternion, alignmentRotationQuaternion, alignmentRotationMatrix

Reimplemented in MtiBaseDevice.

Definition at line 2120 of file xsdevice_def.cpp.

◆ setAlignmentRotationQuaternion()

bool XsDevice::setAlignmentRotationQuaternion ( XsAlignmentFrame  frame,
const XsQuaternion quat 
)
virtual

Set an arbitrary alignment rotation quaternion. Use to rotate either L to the chosen frame L' or S to the chosen frame S'.

Parameters
frameThe frame to rotate
quatThe desired alignment rotation setting of the device.
Returns
true if the alignment rotation has been set successfully
See also
alignmentRotationQuaternion, setAlignmentRotationMatrix, alignmentRotationMatrix

Reimplemented in MtiBaseDevice.

Definition at line 2094 of file xsdevice_def.cpp.

◆ setBlueToothEnabled()

bool XsDevice::setBlueToothEnabled ( bool  enabled)
virtual

Enable or disable the BlueTooth radio of the device.

Parameters
enabledSet to true to enable the BlueTooth radio
Returns
true if the device was successfully updated
See also
isBlueToothEnabled

Definition at line 2422 of file xsdevice_def.cpp.

◆ setBusPowerEnabled()

bool XsDevice::setBusPowerEnabled ( bool  enabled)
virtual

Tell the Xbus to provide power to its child devices or not.

This function can be used to tell the Xbus to stop and start powering its child devices. By default when the Xbus starts up it will provide power to its child devices. Switching the power off can save a lot of energy, but powering the system up again will take some time, depending on the number of connected devices.

Parameters
enabledtrue to enable bus power, false to disable the bus power
Returns
true If the Xbus' bus power state was successfully updated.

Definition at line 2444 of file xsdevice_def.cpp.

◆ setCanConfiguration()

bool XsDevice::setCanConfiguration ( uint32_t  config)
virtual

Set the CAN configuration for this device.

Parameters
configShould consist of 8 bytes baudcode and 1 bit to enable CAN
Returns
true if the CAN output configuration was successfully updated

Reimplemented in Mti6X0Device, and Mti8X0Device.

Definition at line 1198 of file xsdevice_def.cpp.

◆ setCanOutputConfiguration()

bool XsDevice::setCanOutputConfiguration ( XsCanOutputConfigurationArray config)
virtual

Set the CAN output configuration for this device.

When the function exits with a true value config will contain the actual configuration in the device after configuration. When it exits with false the contents of config are undefined.

Note
The config is updated to reflect frequency mismatches in desired configuration and actually possible configuration. As input, a frequency of 65535 (0xFFFF) may be supplied to indicate 'maximum output rate', but after configuration XDA will have put the actual maximum value in config. Similarly, some data types may not have a real update rate (ie. packet counter) and will return an update rate of 65535 (0xFFFF) when configured at any rate other than 0.
Parameters
configThe desired output configuration
Returns
true if the output configuration was successfully updated

Reimplemented in Mti6X0Device, and Mti8X0Device.

Definition at line 1188 of file xsdevice_def.cpp.

◆ setCommunicator()

void XsDevice::setCommunicator ( Communicator comm)
protected

◆ setDeviceAccepted()

bool XsDevice::setDeviceAccepted ( const XsDeviceId deviceId)
virtual

Accepts a device.

Parameters
[in]deviceIdThe device to accept
Returns
true when the device has been successfully accepted

Definition at line 3730 of file xsdevice_def.cpp.

◆ setDeviceBufferSize()

bool XsDevice::setDeviceBufferSize ( uint32_t  frames)
virtual

Request the device to set it's internal buffer to the specified size.

Parameters
framesbuffer size in frames
Returns
True if the setting was successfully updated

Definition at line 4328 of file xsdevice_def.cpp.

◆ setDeviceId()

void XsDevice::setDeviceId ( const XsDeviceId deviceId)
protected

◆ setDeviceOptionFlags()

bool XsDevice::setDeviceOptionFlags ( XsDeviceOptionFlag  setFlags,
XsDeviceOptionFlag  clearFlags 
)
virtual

Set the device option flags.

Parameters
setFlagsThe option flags that must be set. Set to XDOF_None if no flags need to be set
clearFlagsThe option flags that must be cleared. Set to XDOF_None if no flags need to be cleared
Returns
true if the device option flags were successfully altered

Definition at line 1112 of file xsdevice_def.cpp.

◆ setDeviceParameter()

XsResultValue XsDevice::setDeviceParameter ( XsDeviceParameter const &  parameter)
virtual

Sets the given parameter for the device.

Settings device parameters is only valid after initialization and before switching the device to be operational.

Parameters
parametera parameter object, corresponding to a row in the table below.
Returns
Result value indicating success (XRV_OK) or unsupported with current device or firmware version (XRV_UNSUPPORTED).

For Awinda stations this function needs to be called before enabling the radio (XsDevice::enableRadio).

XsDeviceParameterIdentifier Value type/range Description Supported devices
Awinda 2 (Station, Dongle) BodyPack MTmk4 MTw2 MTx2 SyncStation
XDPI_PacketErrorRate boolean Report packet error rate for each child device. Y - - - - -
XDPI_SyncLossTimeout uint16_t Network timeout in seconds used by connected child devices.
For Awinda2: this timeout is measured by connected MTw2 devices based on received data from the station.
Y - - - - -
XDPI_UplinkTimeout uint16_t Network timeout in seconds used by the master devices.
For Awinda2: this timeout is measured based on received data from each connected MTw2 individually.
Y - - - - -
XDPI_ExtendedBuffer bool If set, enables the extended buffer on connected MTw2 devices. Y - - - - -

Definition at line 4456 of file xsdevice_def.cpp.

◆ setDeviceRejected()

bool XsDevice::setDeviceRejected ( const XsDeviceId deviceId)
virtual

Rejects a device.

Parameters
[in]deviceIdThe device to reject
Returns
true when the device has been successfully rejected

Definition at line 3739 of file xsdevice_def.cpp.

◆ setDeviceState()

virtual void XsDevice::setDeviceState ( XsDeviceState  state)
protectedvirtual

◆ setErrorMode()

bool XsDevice::setErrorMode ( XsErrorMode  errormode)
virtual

Sets the error mode of the device.

The error mode tells the device what to do if a problem occurs.

Parameters
errormodeThe desired error mode of the device
Returns
true if the device was successfully updated
See also
errorMode

Reimplemented in MtiBaseDevice, and MtDevice.

Definition at line 2473 of file xsdevice_def.cpp.

◆ setFirmwareVersion()

void XsDevice::setFirmwareVersion ( const XsVersion version)
private

◆ setFixedGravityEnabled()

bool XsDevice::setFixedGravityEnabled ( bool  enable)
virtual

Sets whether the fixed gravity value should be used or if it should be computed from the initialPositionLLA value.

Parameters
enabletrue to use fixed gravity, false to compute from initialPositionLLA
Returns
true if the device was successfully update
See also
isFixedGravityEnabled
setGravityMagnitude
setInitialPositionLLA

Definition at line 2934 of file xsdevice_def.cpp.

◆ setGnssLeverArm()

bool XsDevice::setGnssLeverArm ( const XsVector arm)
virtual

Sets the GNSS Lever Arm vector.

GNSS Lever arm is the length/pos of the antenna w.r.t. the center of the sensor It is a 3-vector: x,y,z

Parameters
armThe lever arm vector
Returns
True if successful

Reimplemented in Mti6X0Device, and MTi7_MTi8Device.

Definition at line 2946 of file xsdevice_def.cpp.

◆ setGnssPlatform()

XSNOEXPORT virtual XSDEPRECATED bool XsDevice::setGnssPlatform ( XsGnssPlatform  gnssPlatform)
virtual

◆ setGnssReceiverSettings()

bool XsDevice::setGnssReceiverSettings ( const XsIntArray gnssReceiverSettings)
virtual

Sets some GNSS receiver settings.

Parameters
gnssReceiverSettingsXsIntArray containing the receiver settings, that are to be set
Returns
true if the settings were successfully set; false otherwise

Reimplemented in MtDevice.

Definition at line 4529 of file xsdevice_def.cpp.

◆ setGotoConfigOnClose()

void XsDevice::setGotoConfigOnClose ( bool  gotoConfigOnClose)

On closePort the device will go to config by default, with this function it is possible to prevent that.

Parameters
gotoConfigOnCloseboolean

Definition at line 519 of file xsdevice_def.cpp.

◆ setGravityMagnitude()

bool XsDevice::setGravityMagnitude ( double  mag)
virtual

Sets the 'Gravity Magnitude' of the device to the given value mag.

The Gravity Magnitude is the strength of the gravity where the measurements are done. Setting this value precisely allows for more accurate measurements.

Parameters
magThe desired 'Gravity Magnitude' setting of the device.
Returns
true if the Gravity Magnitude was successfully written
Note
The default value is usually computed from the last known Lat Lon Alt value
See also
gravityMagnitude
setInitialPositionLLA
initialPositionLLA

Reimplemented in BroadcastDevice.

Definition at line 2579 of file xsdevice_def.cpp.

◆ setHeadingOffset()

bool XsDevice::setHeadingOffset ( double  offset)
virtual

Set the 'heading offset' setting of the device.

Parameters
offsetThe desired heading offset of the device in degrees
Returns
true if the device was successfully updated
See also
headingOffset

Reimplemented in BroadcastDevice, and MtiBaseDevice.

Definition at line 2486 of file xsdevice_def.cpp.

◆ setInitialBiasUpdateEnabled()

bool XsDevice::setInitialBiasUpdateEnabled ( bool  enable)
virtual

Set if the device does gyroscope bias estimation when switching to measurement mode.

When this option is enabled, the device will automatically run the 'no rotation' algorithm every time it switches to measurement mode.

Parameters
enabletrue to enable the option, false to disable it
Returns
true if the device was successfully update
See also
setNoRotation
isInitialBiasUpdateEnabled

Definition at line 2912 of file xsdevice_def.cpp.

◆ setInitialized()

void XsDevice::setInitialized ( bool  initialized)
inlineprotected

Set the initialized state to initialized.

Definition at line 611 of file xsdevice_def.h.

◆ setInitialPositionLLA()

bool XsDevice::setInitialPositionLLA ( const XsVector lla)
virtual

Sets the 'Latitude Longitude Altitude' setting of the device to the given vector.

The Latitude Longitude Altitude contains the location on earth where the measurements are done. Setting this value allows for more accurate measurements. The default gravity magnitude and earth magnetic field are computed form this value.

Parameters
llaThe desired 'Latitude Longitude Altitude' setting for the device. This should be a 3-element vector.
Returns
true if the Latitude Longitude Altitude was successfully written
Note
When GNSS is available, this value is automatically updated with the last known position when the device is put in config mode after measurement.
See also
initialPositionLLA
labMagneticField
gravityMagnitude

Reimplemented in MtDevice, BroadcastDevice, and MtiBaseDevice.

Definition at line 2809 of file xsdevice_def.cpp.

◆ setLocationId()

bool XsDevice::setLocationId ( int  id)
virtual

Set the location ID of the device.

The location ID is a custom 16-bit ID that can be assigned to a device.

Parameters
idThe desired location ID for the device
Returns
true if the Location ID was successfully updated
See also
locationId

Reimplemented in BroadcastDevice, and MtDevice.

Definition at line 2506 of file xsdevice_def.cpp.

◆ setNoRotation()

bool XsDevice::setNoRotation ( uint16_t  duration)
virtual

Set the no rotation period to duration.

This function can be called in both config and measurement modes. In config mode it specifies the duration that the device is considered to be stationary as soon as it enters measurement mode. In measurement mode, it specifies the duration that the device is considered to be stationary, starting immediately.

During the stationary period, the gyroscope biases are measured, giving better performance.

Parameters
durationThe desired stationary duration in seconds
Returns
true if the no rotation command was accepted by the device
See also
isInitialBiasUpdateEnabled
setInitialBiasUpdateEnabled

Reimplemented in BroadcastDevice, MtDevice, and MtiBaseDevice.

Definition at line 2743 of file xsdevice_def.cpp.

◆ setObjectAlignment()

bool XsDevice::setObjectAlignment ( const XsMatrix matrix)
virtual

Sets the object alignment of the device to the given matrix.

Parameters
matrixThe desired 'object alignment matrix' setting of the device. This should be an orthonormal 3x3 matrix.
Returns
true if the object alignment matrix was successfully written
Note
This is legacy functionality to support backwards compatibility with older devices. For MT Mk4 devices it is suggested to use setAlignmentRotationQuaternion or setAlignmentRotationMatrix instead.
See also
objectAlignmentMatrix
headingOffset
setHeadingOffset
setAlignmentRotationQuaternion
setAlignmentRotationMatrix

Reimplemented in BroadcastDevice.

Definition at line 2554 of file xsdevice_def.cpp.

◆ setOnboardFilterProfile() [1/2]

bool XsDevice::setOnboardFilterProfile ( int  profileType)
virtual

Sets the filter profile to use for computing orientations on the device.

When computing orientation data, there is a choice of filter profiles. This function can be used to select the appropriate one.

Parameters
profileTypeThe filter profile type to use. This can be chosen from the list returned by availableOnboardFilterProfiles()
Returns
true if the filter profile was successfully changed
See also
availableOnboardFilterProfiles
onboardFilterProfile
setXdaFilterProfile

Reimplemented in MtDevice, and BroadcastDevice.

Definition at line 2659 of file xsdevice_def.cpp.

◆ setOnboardFilterProfile() [2/2]

bool XsDevice::setOnboardFilterProfile ( XsString const &  profileType)
virtual

Sets the filter profile to use for computing orientations on the device.

When computing orientation data, there is a choice of filter profiles. This function can be used to select the appropriate one.

Parameters
profileTypeThe filter profile type to use. This can be chosen from the list returned by availableOnboardFilterProfiles()
Returns
true if the filter profile was successfully changed
See also
availableOnboardFilterProfiles
onboardFilterProfile
setXdaFilterProfile

Reimplemented in MtDevice, and BroadcastDevice.

Definition at line 2673 of file xsdevice_def.cpp.

◆ setOperationalMode()

bool XsDevice::setOperationalMode ( XsOperationalMode  mode)
virtual

Set the device in the given operational mode.

Parameters
modeDesired operional mode.
Returns
True when successful, false otherwise.

Definition at line 3371 of file xsdevice_def.cpp.

◆ setOptions()

void XsDevice::setOptions ( XsOption  enable,
XsOption  disable 
)
virtual

Enable and disable processing options.

These options are used to specify whether XDA should compute certain kinds of data from available other data and what data-retention policy to use. On a system with limited resources it may be useful to limit the processing and data retention done by XDA. By default XDA will do all processing it can do, but retain as little data as possible. In case of conflict, enable supersedes disable.

Parameters
enableA logically OR'ed combination of XsOptions to enable
disableA logically OR'ed combination of XsOptions to disable
See also
areOptionsEnabled

Reimplemented in BroadcastDevice.

Definition at line 3411 of file xsdevice_def.cpp.

◆ setOutputConfiguration()

bool XsDevice::setOutputConfiguration ( XsOutputConfigurationArray config)

Set the output configuration for this device.

When the function exits with a true value config will contain the actual configuration in the device after configuration. When it exits with false the contents of config are undefined.

Note
The config is updated to reflect frequency mismatches in desired configuration and actually possible configuration. As input, a frequency of 65535 (0xFFFF) may be supplied to indicate 'maximum output rate', but after configuration XDA will have put the actual maximum value in config. Similarly, some data types may not have a real update rate (ie. packet counter) and will return an update rate of 65535 (0xFFFF) when configured at any rate other than 0.
Parameters
configThe desired output configuration
Returns
true if the output configuration was successfully updated

Definition at line 1138 of file xsdevice_def.cpp.

◆ setOutputConfigurationInternal()

virtual XsResultValue XsDevice::setOutputConfigurationInternal ( XsOutputConfigurationArray config)
protectedvirtual

Reimplemented in MtiBaseDevice.

◆ setPacketErrorRate()

virtual XSNOEXPORT void XsDevice::setPacketErrorRate ( int  per)
virtual

◆ setPortConfiguration()

bool XsDevice::setPortConfiguration ( XsIntArray config)
virtual

Change the port configuration of a device.

Configures the 2 ports of the 6x0 device The integers consist of:

  • bits 0:7 XsBaudcode
  • bit 8 Enable flow control
  • bit 9 Use 2nd stop bit
  • bit 10 Use Parity bit
  • bit 11 Even/odd parity
  • bit 12:15 reserved
  • bits 16:19 bits XsProtocol
    Parameters
    configAn array of elements containing a configuration for each port (UART and RS232)
    Remarks
    Only Mti6x0 devices supported
    Returns
    true if the port configuration was successfully updated
    See also
    portConfiguration, XsBaudCode

Reimplemented in Mti6X0Device, and Mti8X0Device.

Definition at line 930 of file xsdevice_def.cpp.

◆ setRecordingStartFrame()

virtual void XsDevice::setRecordingStartFrame ( uint16_t  startFrame)
protectedvirtual

◆ setRecordingStopFrame()

virtual void XsDevice::setRecordingStopFrame ( uint16_t  stopFrame)
protectedvirtual

◆ setRs485TransmissionDelay()

bool XsDevice::setRs485TransmissionDelay ( uint16_t  delay)
virtual

Set the transmission delay used for RS485 transmissions.

See the low level documentation for more information on this function.

Parameters
delayThe desired delay
Returns
true if the device was successfully updated

Reimplemented in MtDevice, and MtiBaseDevice.

Definition at line 2851 of file xsdevice_def.cpp.

◆ setSerialBaudRate()

bool XsDevice::setSerialBaudRate ( XsBaudRate  baudrate)
virtual

Change the serial baudrate to baudrate.

This function is only useful when using a serial communication channel, such as a serial-USB converter or a direct COM port. It is advised to make the baud rate as high as your platform allows, to minimize latency and problems with bandwidth.

After setting the baudrate and communicating over the same communication channel, it is required to reset the device.

Parameters
baudrateThe desired serial baudrate
Returns
true if the baud rate was successfully updated

Reimplemented in BroadcastDevice.

Definition at line 875 of file xsdevice_def.cpp.

◆ setSkipEmtsReadOnInit()

XSNOEXPORT void XsDevice::setSkipEmtsReadOnInit ( bool  skip)

◆ setStartRecordingPacketId()

virtual void XsDevice::setStartRecordingPacketId ( int64_t  startFrame)
protectedvirtual

◆ setStealthMode()

bool XsDevice::setStealthMode ( bool  enabled)
virtual

Enable or disable stealth mode.

In stealth mode, the MVN hardware will be silent and all LEDs will be dimmed or disabled. Some minimal user feedback will remain enabled. The change will be applied immediately to all detected systems, resetting the mocap data stream.

Parameters
enabledSet to true if you wish to enable stealth mode, false to disable it.
Returns
true if the setting was successfully updated

Definition at line 4025 of file xsdevice_def.cpp.

◆ setStopRecordingPacketId()

virtual void XsDevice::setStopRecordingPacketId ( int64_t  stopFrame)
protectedvirtual

◆ setStringOutputMode()

bool XsDevice::setStringOutputMode ( uint16_t  type,
uint16_t  period,
uint16_t  skipFactor 
)
virtual

Sets the string output mode for this device.

Parameters
typeThe type to set
periodThe period to set
skipFactorThe skipFactor to set
Returns
True if the device was successfully updated

Reimplemented in MTi7_MTi8Device.

Definition at line 1220 of file xsdevice_def.cpp.

◆ setSyncSettings()

bool XsDevice::setSyncSettings ( const XsSyncSettingArray settingList)
virtual

Set the synchronization settings of the device.

This function can be used to set all the synchronization options of the device at once. It is translated into device-specific commands by XDA, since not all devices support the same synchronization functionality.

Parameters
settingListThe list of synchronization settings to set. An empty list will clear all synchronization settings.
Returns
true if the device was successfully updated
See also
syncSettings

Reimplemented in MtiBaseDevice, and BroadcastDevice.

Definition at line 3158 of file xsdevice_def.cpp.

◆ setSyncStationMode()

bool XsDevice::setSyncStationMode ( bool  enabled)
virtual

Set the Sync Station mode of the Awinda Station device.

Parameters
enabledtrue to enable Sync Station mode, false to disable it
Returns
true if successful

Definition at line 3801 of file xsdevice_def.cpp.

◆ setTerminationPrepared()

void XsDevice::setTerminationPrepared ( bool  prepared)
inlineprotected

Set the "termination prepared" state to prepared.

Definition at line 616 of file xsdevice_def.h.

◆ setTransportMode()

bool XsDevice::setTransportMode ( bool  transportModeEnabled)
virtual

Enable or disable the transport mode for the device.

The MTw has a "wake up by motion" feature that requires some power and can cause unnecessary wakeups when transporting the device. This function can be used to put the device in "transport mode", which effectively disables the motion wake up feature until the device is plugged into something or the transport mode is explicitly disabled by this function again.

Parameters
transportModeEnabledtrue to enable transport mode (which disables the motion wakeup)
Returns
true if the device was successfully put in transport mode (or taken out of it)
Note
MTw only

Reimplemented in BroadcastDevice.

Definition at line 2995 of file xsdevice_def.cpp.

◆ setUbloxGnssPlatform()

bool XsDevice::setUbloxGnssPlatform ( XsUbloxGnssPlatform  ubloxGnssPlatform)
virtual

Set the device GNSS platform for u-blox GNSS receivers.

Warning
This function produces undefined behaviour when used on non u-blox GNSS receivers.
Parameters
ubloxGnssPlatformThe GNSS platform that must be set
Returns
true if the device GNSS platform was successfully set

Reimplemented in Mti6X0Device, and MtDevice.

Definition at line 4511 of file xsdevice_def.cpp.

◆ setUpdateRate()

bool XsDevice::setUpdateRate ( int  rate)
virtual

Set the legacy update rate of the device.

Parameters
[in]rateThe desired legacy update rate for the device
Returns
true if the update rate was successfully set
See also
deviceMode
setDeviceMode

Definition at line 554 of file xsdevice_def.cpp.

◆ setUtcTime()

bool XsDevice::setUtcTime ( const XsTimeInfo time)
virtual

Sets the 'UTC Time' setting of the device to the given time.

Sets the UTC time in the device. Setting this value allows for more accurate measurements.

Parameters
timeThe current time in UTC format
Returns
true if the UTC Time was successfully written
Note
When GNSS is available, this value is automatically updated with the last known UTC time when the device is put in config mode after measurement.

Reimplemented in MtiBaseDevice.

Definition at line 2831 of file xsdevice_def.cpp.

◆ setWirelessPriority()

bool XsDevice::setWirelessPriority ( int  priority)
virtual

Sets the wireless priority of the device.

Parameters
priorityThe desired wireless priority of the device in the range 0-255.
Returns
true if the wireless priority has been successfully updated
Note
MTw connected to Awinda Station only

Definition at line 3581 of file xsdevice_def.cpp.

◆ setXdaFilterProfile() [1/2]

bool XsDevice::setXdaFilterProfile ( int  profileType)
virtual

Sets the filter profile to use for computing orientations on the host PC.

When computing orientation data, there is a choice of filter profiles. This function can be used to select the appropriate one. By default XDA will attempt to match the software filter profile to the configured hardware filter profile when detecting a new device.

Parameters
profileTypeThe filter profile type to use. This can be chosen from the list returned by availableXdaFilterProfiles()
Returns
true if the filter profile was successfully changed
Note
When reading from a file, make sure to call resetLogFileReadPosition() and possibly loadLogFile() after changing the filter profile to make sure all cached data is recomputed.
See also
availableXdaFilterProfiles
xdaFilterProfile
setOnboardFilterProfile

Reimplemented in BroadcastDevice.

Definition at line 2619 of file xsdevice_def.cpp.

◆ setXdaFilterProfile() [2/2]

bool XsDevice::setXdaFilterProfile ( XsString const &  profileType)
virtual

Sets the filter profile to use for computing orientations on the host PC.

When computing orientation data, there is a choice of filter profiles. This function can be used to select the appropriate one. By default XDA will attempt to match the software filter profile to the configured hardware filter profile when detecting a new device.

Parameters
profileTypeThe filter profile type to use. This can be chosen from the list returned by availableXdaFilterProfiles()
Returns
true if the filter profile was successfully changed
Note
When reading from a file, make sure to call resetLogFileReadPosition() and possibly loadLogFile() after changing the filter profile to make sure all cached data is recomputed.
See also
availableXdaFilterProfiles
xdaFilterProfile
setOnboardFilterProfile

Reimplemented in BroadcastDevice.

Definition at line 2636 of file xsdevice_def.cpp.

◆ shortProductCode()

XsString XsDevice::shortProductCode ( ) const
virtual

Return the shortened product code of the device suitable for display.

Returns
The short product code of the device

Reimplemented in Mti3X0Device, MtiXDevice, Mti6X0Device, Mti8X0Device, and MTi7_MTi8Device.

Definition at line 3459 of file xsdevice_def.cpp.

◆ shouldDataMsgBeRecorded()

virtual bool XsDevice::shouldDataMsgBeRecorded ( const XsMessage msg) const
protectedvirtual

◆ shouldDoRecordedCallback()

virtual bool XsDevice::shouldDoRecordedCallback ( XsDataPacket const &  packet) const
protectedvirtual

◆ shouldWriteMessageToLogFile() [1/2]

virtual bool XsDevice::shouldWriteMessageToLogFile ( const XsDevice dev,
const XsMessage message 
) const
protectedvirtual

◆ shouldWriteMessageToLogFile() [2/2]

virtual bool XsDevice::shouldWriteMessageToLogFile ( const XsMessage msg) const
protectedvirtual

◆ skipEmtsReadOnInit()

bool XsDevice::skipEmtsReadOnInit ( ) const
inlineprotected
Returns
True if skip EMTS read on initialization is set to true

Definition at line 681 of file xsdevice_def.h.

◆ startRecording()

bool XsDevice::startRecording ( )
virtual

Start recording incoming data.

To record successfully, a log file should be created by calling createLogFile() before this function is called. startRecording(XsString, XsDeviceId) can be used to achieve the same result.

Returns
true if recording was successfully started
Note
Starting recording for a single non-main device will start a recording for the entire system.
See also
createLogFile()
stopRecording()

Reimplemented in BroadcastDevice.

Definition at line 2171 of file xsdevice_def.cpp.

◆ startRepresentativeMotion()

bool XsDevice::startRepresentativeMotion ( )
virtual

Let the user indicate that he is starting the representative motion for the In-Run Compass Calibration.

Returns
true if the start indication was successfully sent to the device

Reimplemented in MtiBaseDevice.

Definition at line 2753 of file xsdevice_def.cpp.

◆ stealthMode()

bool XsDevice::stealthMode ( ) const
virtual

Return the state of the stealth mode setting.

Returns
the state of the stealth mode setting.
See also
setStealthMode

Definition at line 4034 of file xsdevice_def.cpp.

◆ stopRecording()

bool XsDevice::stopRecording ( )
virtual

Stop recording incoming data.

Returns
true if recording was successfully stopped
Note
Stopping recording for a single non-main device will stop a recording for the entire system.
See also
createLogFile()
startRecording()

Reimplemented in BroadcastDevice.

Definition at line 2201 of file xsdevice_def.cpp.

◆ stopRepresentativeMotion()

XsIccRepMotionResult XsDevice::stopRepresentativeMotion ( )
virtual

Let the user indicate that he stopped the representative motion.

for the In-Run Compass Calibration
\returns A struct containing the results of the last In-Run Compass Calibration

Reimplemented in MtiBaseDevice.

Definition at line 2772 of file xsdevice_def.cpp.

◆ storeFilterState()

bool XsDevice::storeFilterState ( )
virtual

Store orientation filter state in the device.

Use this function when the filters for the device have stabilized to store the current biases in the device. The benefit is that on the next startup the filter will stabilize quicker. However, the stored biases depend on temperature and other external parameters, so the stored values will remain correct for only a short time.

Returns
true if the filter state was saved, false otherwise

Reimplemented in MtDevice, and BroadcastDevice.

Definition at line 2888 of file xsdevice_def.cpp.

◆ storeIccResults()

bool XsDevice::storeIccResults ( )
virtual

Store the onboard ICC results for use by the device.

Returns
true if the store was successful

Reimplemented in MtiBaseDevice.

Definition at line 2780 of file xsdevice_def.cpp.

◆ stringOutputType()

uint16_t XsDevice::stringOutputType ( ) const
virtual

Returns the string output type.

Returns
The 'string output type' setting of the device
See also
setStringOutputType

Reimplemented in MtDevice.

Definition at line 3354 of file xsdevice_def.cpp.

◆ stringSamplePeriod()

uint16_t XsDevice::stringSamplePeriod ( ) const
virtual

Returns the sample period for string output.

Returns
The 'sample period' setting of the device for string output

Reimplemented in MtDevice.

Definition at line 3337 of file xsdevice_def.cpp.

◆ stringSkipFactor()

uint16_t XsDevice::stringSkipFactor ( ) const
virtual

Returns the skipfactor for string output.

Returns
The 'output skip factor' setting of the device for string output

Reimplemented in MtDevice.

Definition at line 3345 of file xsdevice_def.cpp.

◆ subDevice()

XsDevice * XsDevice::subDevice ( int  subDeviceId) const
virtual

Returns the sub-device at index index.

This function returns a software-only sub device of a larger device. It could for example return an XsDevice representing a single finger segment of an Xsens Glove. These devices have only limited functionality and are typically only used for data extraction as all communication goes through the main device.

Parameters
subDeviceIdThe sub device id of the device to return. Which ids are valid depends on the type of device, 0 always indicates the main device.
Returns
A pointer to the found XsDevice or 0 if the device could not be found or the device does not have sub-devices.

Definition at line 4632 of file xsdevice_def.cpp.

◆ subDeviceCount()

int XsDevice::subDeviceCount ( ) const
virtual

Returns the number of sub-devices of this device.

This function returns the number of software-only sub devices of a larger device.

Returns
The number of available sub-devices or 0 if none are available
See also
subDevice

Definition at line 4644 of file xsdevice_def.cpp.

◆ supportedStatusFlags()

uint32_t XsDevice::supportedStatusFlags ( ) const
virtual

Returns a bitmask with all the status flags supported by this device.

Not all devices support all status flags. When receiving an XsDataPacket with a status in it, this can affect how to interpret the flags. Especially with a flag like the self-test it's important not to conclude that a device is defective because it is not set when the device doesn't actually support this feature.

Returns
The bitmask with all the status flags that this device supports

Reimplemented in MtDevice, Mti3X0Device, MtiXDevice, Mti6X0Device, Mti8X0Device, MTi7_MTi8Device, MtiX00Device, MtiX0Device, and MtigDevice.

Definition at line 4610 of file xsdevice_def.cpp.

◆ supportedStringOutputTypes()

XsStringOutputTypeArray XsDevice::supportedStringOutputTypes ( ) const
virtual

Ask the device for its supported string output types.

Returns
A list with the supported string output types.

Reimplemented in Mti6X0Device, Mti8X0Device, MtiX00Device, MtiX0Device, and MtigDevice.

Definition at line 1259 of file xsdevice_def.cpp.

◆ supportedSyncSettings() [1/2]

XsSyncSettingArray XsDevice::supportedSyncSettings ( ) const
virtual

Get all supported synchronization settings available on the device.

This function provides a list of the available synchronization settings of the device, since not all devices support the same synchronization functionality. Every XsSyncSetting element in the list defines one function and line setting, with supported parameters. If the same function support multiple settings (i.e. multiple lines), then the list will contains multiple items with the same function name, but with different line settings. For easier use, same functions must be listed next to eachother, so each function settings in the list will be grouped. Properties, others then m_function and m_line are set to 0 if not supported or 1 if supported by the device.

Returns
The list of synchronization settings supported by the device. Each settings grouped by functions.

Definition at line 3175 of file xsdevice_def.cpp.

◆ supportedSyncSettings() [2/2]

XsSyncSettingArray XsDevice::supportedSyncSettings ( XsDeviceId const &  deviceId)
static

Return the supported synchronization settings for a specified deviceId or deviceId mask.

Parameters
[in]deviceIdThe device id to request the supported synchronization settings for
Returns
the supported synchronization settings for the specified deviceId

Definition at line 4043 of file xsdevice_def.cpp.

◆ supportedUpdateRates()

std::vector< int > XsDevice::supportedUpdateRates ( XsDataIdentifier  dataType = XDI_None) const
virtual

Ask the device for its supported update rates for the given dataType.

Parameters
dataTypeThe type of data to get the supported update rates for
Returns
A list with the supported update rates or an empty list in case of an error

Reimplemented in MtiBaseDevice, and BroadcastDevice.

Definition at line 2403 of file xsdevice_def.cpp.

◆ supportsSyncSettings()

bool XsDevice::supportsSyncSettings ( XsDeviceId const &  deviceId)
static

Determines whether the device specified by deviceId supports sync settings.

Parameters
[in]deviceIdThe device id to check
Returns
true when the device specified by deviceId supports sync settings

Definition at line 4057 of file xsdevice_def.cpp.

◆ syncRole()

XsSyncRole XsDevice::syncRole ( ) const
virtual

Returns the synchronization role of the device.

For synchronization purposes a device can be a master, a slave, both or neither. This function returns the way the device is currently configured.

Returns
The synchronization role of the device

Definition at line 1821 of file xsdevice_def.cpp.

◆ syncSettings()

XsSyncSettingArray XsDevice::syncSettings ( ) const
virtual

Get all the current synchronization settings of the device.

This function is a generic way of requesting the synchonization options of a device, since not all devices support the same synchronization functionality.

Returns
The list of synchronization settings configured for the device
See also
setSyncSettings

Reimplemented in MtiBaseDevice.

Definition at line 3144 of file xsdevice_def.cpp.

◆ syncSettingsTimeResolutionInMicroSeconds()

unsigned int XsDevice::syncSettingsTimeResolutionInMicroSeconds ( XsDeviceId const &  deviceId)
static
Returns
the time resolution in microseconds for a device with device id deviceId For example if the precision is 1 millisecond, 1000 is returned
Parameters
[in]deviceIdThe deviceId

Definition at line 4077 of file xsdevice_def.cpp.

◆ takeFirstDataPacketInQueue()

XsDataPacket XsDevice::takeFirstDataPacketInQueue ( )

Return the first packet in the packet queue or an empty packet if the queue is empty.

This function will only return a packet when XSO_RetainLiveData or XSO_RetainBufferedData is specified for the device. It will return the first packet in the queue and remove the packet from the queue.

Returns
The first packet in the queue or an empty packet if the queue is empty
See also
setOptions

Definition at line 4230 of file xsdevice_def.cpp.

◆ toType()

template<typename T >
XSNOEXPORT T* XsDevice::toType ( )
inline

Definition at line 251 of file xsdevice_def.h.

◆ transportMode()

bool XsDevice::transportMode ( )
virtual

Returns the current state of the transport mode feature.

Returns
true if tranport mode is currently enabled
See also
setTransportMode

Definition at line 3005 of file xsdevice_def.cpp.

◆ triggerStartRecording()

bool XsDevice::triggerStartRecording ( )
virtual

Start recording incoming data through generating a virtual input trigger.

Note
On devices without support for a start recording input trigger this function will default to XsDevice::startRecording
Returns
true if recording was successfully started
See also
createLogFile()
stopRecording()
startRecording

Definition at line 2191 of file xsdevice_def.cpp.

◆ ubloxGnssPlatform()

XsUbloxGnssPlatform XsDevice::ubloxGnssPlatform ( ) const
virtual

Returns the device GNSS platform for u-blox GNSS receivers.

Warning
This function has an undefined meaning when used on non u-blox GNSS receivers.
Returns
The current device GNSS platform

Reimplemented in Mti6X0Device, and MtDevice.

Definition at line 4501 of file xsdevice_def.cpp.

◆ updateCachedDeviceInformation()

bool XsDevice::updateCachedDeviceInformation ( )
virtual

Updates the cached device information for all devices connected to this port.

This function can only be called in config mode. XDA caches all device information to prevent unnecessary communication with the device. When some configuration has changed without XDA knowing about it (through sendCustomMessage() for example), it may be necessary to tell XDA to refresh its cached information by calling this function.

Returns
true if the cached information was updated successfully

Reimplemented in BroadcastDevice.

Definition at line 3254 of file xsdevice_def.cpp.

◆ updateConnectivityState()

void XsDevice::updateConnectivityState ( XsConnectivityState  newState)
protected

◆ updateDeviceState()

virtual void XsDevice::updateDeviceState ( XsDeviceState  state)
protectedvirtual

◆ updateLastAvailableLiveDataCache()

void XsDevice::updateLastAvailableLiveDataCache ( XsDataPacket const &  pack)
protected

◆ updatePortInfo()

XsResultValue XsDevice::updatePortInfo ( XsPortInfo const &  newInfo)
virtual

Update the connection information, this is only useful for devices communicating over a dynamic link such as a TCP/IP connection.

Parameters
newInfoThe new port information to use in the next (re)connect attempts
Returns
Whether the operation succeeded or not

Definition at line 4620 of file xsdevice_def.cpp.

◆ updateRate()

int XsDevice::updateRate ( ) const
virtual

Get the legacy update rate of the device.

This function is only valid for devices in legacy mode.

Returns
The legacy update rate of the device

Definition at line 544 of file xsdevice_def.cpp.

◆ updateRateForDataIdentifier()

int XsDevice::updateRateForDataIdentifier ( XsDataIdentifier  dataType) const
virtual

Returns the currently configured update rate for the supplied dataType.

This function checks if the configured output contains dataType and returns the associated update rate. In some cases 65535 (0xFFFF) will be returned, which means 'as fast as possible'. This applies to things like a packet counter, which is sent with every packet and can therefore have an unpredictable update rate. This function only checks the output configured in the device, not possible computed data

Parameters
dataTypeThe type of data to get the update rate for.
Returns
The requested update rate or 0 if the type is not configured for output

Reimplemented in MtDevice.

Definition at line 601 of file xsdevice_def.cpp.

◆ updateRateForProcessedDataIdentifier()

int XsDevice::updateRateForProcessedDataIdentifier ( XsDataIdentifier  dataType) const
virtual

Returns the currently configured update rate for the supplied dataType.

This function checks if the configured output contains dataType and returns the associated update rate. In some cases 65535 (0xFFFF) will be returned, which means 'as fast as possible'. This applies to things like a packet counter, which is sent with every packet and can therefore have an unpredictable update rate. Where updateRateForDataIdentifier only checks the outputs configured in the device, this function also checks what can and will be computed from the data.

See also
updateRateForDataIdentifier
Parameters
dataTypeThe type of data to get the update rate for.
Returns
The requested update rate or 0 if the type is not configured for output

Definition at line 622 of file xsdevice_def.cpp.

◆ useLogInterface()

void XsDevice::useLogInterface ( DataLogger logger)
protected

Uses log interface for a given data logger.

Parameters
loggerThe data logger

For testing purposes

◆ usesLegacyDeviceMode()

bool XsDevice::usesLegacyDeviceMode ( ) const
virtual

Returns whether the device uses legacy device mode.

Returns
True if the legacy period, outputmode, outputsettings or string reports are used

Definition at line 3022 of file xsdevice_def.cpp.

◆ utcTime()

XsTimeInfo XsDevice::utcTime ( ) const
virtual

Gets the 'UTC Time' setting of the device.

Gets the UTC time in the device.

Returns
The current UTC time of the sensor

Reimplemented in MtiBaseDevice.

Definition at line 2819 of file xsdevice_def.cpp.

◆ waitForAllDevicesInitialized()

void XsDevice::waitForAllDevicesInitialized ( )
virtual

Wait until are known devices are initialized.

Container devices such as Awinda Master and Bodypack can have (slightly) delayed initialization of child devices after they have been detected. This function can be used to wait for all currently detected trackers to have been properly initialized.

Definition at line 4339 of file xsdevice_def.cpp.

◆ waitForCustomMessage() [1/2]

virtual XSNOEXPORT bool XsDevice::waitForCustomMessage ( std::shared_ptr< ReplyObject reply,
XsMessage messageReceive,
int  timeout 
)
virtual

◆ waitForCustomMessage() [2/2]

virtual XSNOEXPORT bool XsDevice::waitForCustomMessage ( XsXbusMessageId  messageId,
XsMessage messageReceive,
int  timeout = 0 
)
virtual

◆ waitForLoadLogFileDone()

void XsDevice::waitForLoadLogFileDone ( ) const

Wait for the file operation started by loadLogFile to complete.

See also
loadLogFile
isLoadLogFileInProgress

Definition at line 4364 of file xsdevice_def.cpp.

◆ wirelessPriority()

int XsDevice::wirelessPriority ( ) const
virtual

Returns the wireless priority of the device.

Returns
The wireless priority of the device or 0 if it has none.
Note
MTw connected to Awinda Station only

Definition at line 3571 of file xsdevice_def.cpp.

◆ writeDeviceSettingsToFile()

void XsDevice::writeDeviceSettingsToFile ( )
virtual

Write the emts/wms/xms of the device and all its children to the open logfile.

Reimplemented in MtDevice.

Definition at line 2030 of file xsdevice_def.cpp.

◆ writeEmtsPage()

virtual XSNOEXPORT bool XsDevice::writeEmtsPage ( uint8_t const *  data,
int  pageNr,
int  bankNr 
)
virtual

◆ writeFilterStateToFile()

virtual void XsDevice::writeFilterStateToFile ( )
protectedvirtual

◆ writeMessageToLogFile()

virtual void XsDevice::writeMessageToLogFile ( const XsMessage message)
protectedvirtual

◆ xdaFilterProfile()

XsFilterProfile XsDevice::xdaFilterProfile ( ) const
virtual

Gets the filter profile in use for computing orientations on the host PC.

Returns
The filter profile in use when computing orientations is done on the PC
See also
setXdaFilterProfile
onboardFilterProfile

Definition at line 2603 of file xsdevice_def.cpp.

◆ XSENS_DISABLE_COPY()

XsDevice::XSENS_DISABLE_COPY ( XsDevice  )
protected

Friends And Related Function Documentation

◆ MtContainer

friend class MtContainer
friend

Definition at line 543 of file xsdevice_def.h.

◆ XsDeviceEx

friend struct XsDeviceEx
friend

Definition at line 538 of file xsdevice_def.h.

Member Data Documentation

◆ m_communicator

Communicator* XsDevice::m_communicator
protected

A communicator.

Definition at line 721 of file xsdevice_def.h.

◆ m_config

XsDeviceConfiguration XsDevice::m_config
protected

A device configuration.

Definition at line 712 of file xsdevice_def.h.

◆ m_connectivity

XsConnectivityState XsDevice::m_connectivity
protected

A current device connectivity state.

Definition at line 706 of file xsdevice_def.h.

◆ m_dataCache

DataPacketCache XsDevice::m_dataCache
protected

A data cache.

Definition at line 691 of file xsdevice_def.h.

◆ m_deviceId

XsDeviceId XsDevice::m_deviceId
protected

An ID of the device.

Definition at line 697 of file xsdevice_def.h.

◆ m_deviceMutex

xsens::GuardedMutex XsDevice::m_deviceMutex
mutableprotected

The mutex for guarding state changes of the device.

Definition at line 667 of file xsdevice_def.h.

◆ m_emtsBlob

XsMessage XsDevice::m_emtsBlob
protected

An EMTS blob from device.

Note
Used in public source for storing EMTS for log file header.

Definition at line 761 of file xsdevice_def.h.

◆ m_firmwareVersion

XsVersion XsDevice::m_firmwareVersion
protected

A firmware version.

Definition at line 718 of file xsdevice_def.h.

◆ m_gotoConfigOnClose

bool XsDevice::m_gotoConfigOnClose
protected

Go to confing on close boolean variable.

Definition at line 742 of file xsdevice_def.h.

◆ m_isInitialized

bool XsDevice::m_isInitialized
protected

Is intialized boolean variable.

Definition at line 736 of file xsdevice_def.h.

◆ m_justWriteSetting

bool XsDevice::m_justWriteSetting
protected

Just write setting boolean variable.

Definition at line 745 of file xsdevice_def.h.

◆ m_lastAvailableLiveDataCache

XsDataPacket* XsDevice::m_lastAvailableLiveDataCache
protected

A last available live data cache.

Definition at line 783 of file xsdevice_def.h.

◆ m_lastDataOkStamp

XsTimeStamp XsDevice::m_lastDataOkStamp
protected

A time stamp for an OK last data.

Definition at line 709 of file xsdevice_def.h.

◆ m_lastResult

LastResultManager XsDevice::m_lastResult
mutableprotected

The last result of an operation.

Definition at line 700 of file xsdevice_def.h.

◆ m_latestBufferedPacket

XsDataPacket* XsDevice::m_latestBufferedPacket
protected

A copy of the latest ready recording packet. This is the last packet that was popped off the front of m_dataCache. Use latestBufferedPacket() to access.

Definition at line 676 of file xsdevice_def.h.

◆ m_latestLivePacket

XsDataPacket* XsDevice::m_latestLivePacket
protected

A copy of the latest ready live packet. This is the packet with the highest 64-bit sample counter so far. Use latestLivePacket() to access.

Definition at line 673 of file xsdevice_def.h.

◆ m_linearPacketCache

std::deque<XsDataPacket*> XsDevice::m_linearPacketCache
protected

A linear data packet cache.

Definition at line 780 of file xsdevice_def.h.

◆ m_logFileInterface

DataLogger* XsDevice::m_logFileInterface
protected

A data logger for a file interface.

Definition at line 724 of file xsdevice_def.h.

◆ m_logFileMutex

xsens::Mutex XsDevice::m_logFileMutex
mutableprotected

The mutex for guarding access to the log file.

Definition at line 670 of file xsdevice_def.h.

◆ m_master

XsDevice* XsDevice::m_master
protected

A device object.

Definition at line 727 of file xsdevice_def.h.

◆ m_options

XsOption XsDevice::m_options
protected

The options.

Definition at line 756 of file xsdevice_def.h.

◆ m_outputConfiguration

XsOutputConfigurationArray XsDevice::m_outputConfiguration
protected

A devices output configuration.

Definition at line 715 of file xsdevice_def.h.

◆ m_packetStamper

PacketStamper XsDevice::m_packetStamper
protected

A packet stamper.

Definition at line 753 of file xsdevice_def.h.

◆ m_refCounter

volatile std::atomic_int XsDevice::m_refCounter
protected

A reference counter.

Definition at line 730 of file xsdevice_def.h.

◆ m_skipEmtsReadOnInit

bool XsDevice::m_skipEmtsReadOnInit
protected

Skip EMTS read on init boolean variable.

Required for the firmware updater to retain EMTS while rebooting devices

Definition at line 750 of file xsdevice_def.h.

◆ m_startRecordingPacketId

int64_t XsDevice::m_startRecordingPacketId
protected

The ID of the first packet that should be / was recorded.

Definition at line 766 of file xsdevice_def.h.

◆ m_state

XsDeviceState XsDevice::m_state
protected

A current device state.

Definition at line 703 of file xsdevice_def.h.

◆ m_stoppedRecordingPacketId

int64_t XsDevice::m_stoppedRecordingPacketId
protected

The ID of the last packet that was recorded. Remains valid after Flushing has ended, until a new recording is started.

Definition at line 772 of file xsdevice_def.h.

◆ m_stopRecordingPacketId

int64_t XsDevice::m_stopRecordingPacketId
protected

The ID of the last packet that should be / was recorded. Only valid in Recording/Flushing states.

Definition at line 769 of file xsdevice_def.h.

◆ m_terminationPrepared

bool XsDevice::m_terminationPrepared
protected

Termination prepared boolean variable.

Definition at line 739 of file xsdevice_def.h.

◆ m_toaDumpFile

DebugFileType* XsDevice::m_toaDumpFile
protected

To a dump file.

For debugging purposes only, but doesn't do any harm to always be there.

Definition at line 788 of file xsdevice_def.h.

◆ m_unavailableDataBoundary

int64_t XsDevice::m_unavailableDataBoundary
protected

A packet ID of the last sample we know to be unavailable.

Definition at line 694 of file xsdevice_def.h.

◆ m_writeToFile

bool XsDevice::m_writeToFile
protected

Write to file boolean variable.

Definition at line 733 of file xsdevice_def.h.


The documentation for this struct was generated from the following files:


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