#include <xsdevice_def.h>
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< ReplyObject > | addReplyObject (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 XSNOEXPORT * | communicator () 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 XsDevice * | deviceAtBusId (int busid) |
Return the device with bus ID busid. More... | |
const XsDevice * | deviceAtBusIdConst (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 ¶meter) 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 XsDevice * | findDevice (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 XsDevice * | getDeviceFromLocationId (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 XSNOEXPORT * | logFileInterface (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 XsDevice * | master () 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::GuardedMutex * | mutex () 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 ¶meter) |
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 XsDevice * | subDevice (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... | |
![]() | |
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 | |
Communicator * | m_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... | |
XsDataPacket * | m_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... | |
XsDataPacket * | m_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... | |
XsDataPacket * | m_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... | |
DataLogger * | m_logFileInterface |
A data logger for a file interface. More... | |
xsens::Mutex | m_logFileMutex |
The mutex for guarding access to the log file. More... | |
XsDevice * | m_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... | |
DebugFileType * | m_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... | |
Definition at line 164 of file xsdevice_def.h.
|
virtual |
Destroy the device.
Definition at line 274 of file xsdevice_def.cpp.
|
explicitprotected |
Construct an empty device with device id id.
id | The device ID to construct with |
Definition at line 165 of file xsdevice_def.cpp.
|
explicitprotected |
Construct a device using inf for communication.
Using this constructor implies that this device is a master device (master() returns this).
comm | The Communicator to use for this device |
Definition at line 197 of file xsdevice_def.cpp.
|
explicitprotected |
Construct a device with device id childDeviceId for master masterDevice.
masterDevice | The master device ID to construct for |
childDeviceId | The child device ID to construct with |
Communication uses masterDevice's channel
Definition at line 245 of file xsdevice_def.cpp.
|
virtual |
Abort the wireless flushing operation and finalize the recording.
Reimplemented in BroadcastDevice.
Definition at line 3537 of file xsdevice_def.cpp.
|
virtual |
Aborts loading a logfile.
Definition at line 3062 of file xsdevice_def.cpp.
|
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.
Reimplemented in MtDevice.
Definition at line 2716 of file xsdevice_def.cpp.
|
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.
Definition at line 3548 of file xsdevice_def.cpp.
|
virtual |
Request the access control mode of the master device.
Definition at line 3760 of file xsdevice_def.cpp.
|
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.
|
virtual |
|
virtual |
Retrieve the alignment rotation matrix to rotate S to the chosen frame S'.
frame | The frame of which to return the alignment rotation |
Reimplemented in MtiBaseDevice.
Definition at line 2132 of file xsdevice_def.cpp.
|
virtual |
Retrieve the alignment rotation quaternion.
frame | The frame of which to return the alignment rotation |
Reimplemented in MtiBaseDevice.
Definition at line 2106 of file xsdevice_def.cpp.
|
virtual |
Loads a config file(.xsa) and configures the device accordingly.
[in] | filename | The desired path and filename of the config file |
Definition at line 2142 of file xsdevice_def.cpp.
|
virtual |
Returns true when all the specified processing options are enabled.
options | The options to check |
Definition at line 3434 of file xsdevice_def.cpp.
|
virtual |
Return the list of filter profiles available on the device.
Reimplemented in MtDevice.
Definition at line 2696 of file xsdevice_def.cpp.
|
virtual |
Return the list of filter profiles available on the host PC.
Definition at line 2705 of file xsdevice_def.cpp.
|
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
Definition at line 535 of file xsdevice_def.cpp.
|
virtual |
Requests the time the battery level was last updated.
Reimplemented in BroadcastDevice.
Definition at line 2981 of file xsdevice_def.cpp.
|
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).
Definition at line 849 of file xsdevice_def.cpp.
|
virtual |
The bus ID for this device.
Definition at line 860 of file xsdevice_def.cpp.
int XsDevice::cacheSize | ( | ) | const |
Get the number of items currently in the slow data cache for the device.
Definition at line 3131 of file xsdevice_def.cpp.
|
virtual |
Returns the currently configured CAN configuration of the device.
Reimplemented in Mti6X0Device, and Mti8X0Device.
Definition at line 3396 of file xsdevice_def.cpp.
|
virtual |
Returns the currently configured CAN output of the device.
Reimplemented in Mti6X0Device, and Mti8X0Device.
Definition at line 3388 of file xsdevice_def.cpp.
|
virtual |
|
staticprotected |
|
virtual |
Return the number of child-devices this device has. For standalone devices this is always 0.
Definition at line 4085 of file xsdevice_def.cpp.
|
virtual |
Return a managed array containing the child-devices this device has. For standalone devices this is always an empty array.
Reimplemented in BroadcastDevice.
Definition at line 4093 of file xsdevice_def.cpp.
|
protectedvirtual |
|
protectedvirtual |
|
protectedvirtual |
|
protectedvirtual |
|
virtual |
Close the log file.
Reimplemented in BroadcastDevice.
Definition at line 2150 of file xsdevice_def.cpp.
Communicator XSNOEXPORT* XsDevice::communicator | ( | ) | const |
|
virtual |
Returns the connectivity state of the device.
The connectivity describes how and if the device is connected to XDA.
Definition at line 3663 of file xsdevice_def.cpp.
|
virtual |
Stores the current device configuration in a config file(.xsa)
[in] | filename | The desired path and filename of the config file |
Definition at line 2082 of file xsdevice_def.cpp.
XsResultValue XsDevice::createLogFile | ( | const XsString & | filename | ) |
Create a log file for logging.
filename | The desired path and filename of the log file |
Definition at line 2038 of file xsdevice_def.cpp.
|
virtual |
Request the access control list of the master device.
Definition at line 3769 of file xsdevice_def.cpp.
|
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.
Definition at line 825 of file xsdevice_def.cpp.
|
protectedvirtual |
|
virtual |
|
virtual |
Return the device with bus ID busid.
busid | The busid to serach for |
Definition at line 767 of file xsdevice_def.cpp.
const XsDevice * XsDevice::deviceAtBusIdConst | ( | int | busid | ) | const |
Return the device with bus ID busid.
busid | The busid to serach for |
Definition at line 778 of file xsdevice_def.cpp.
|
virtual |
Request the size of the interal buffer.
Definition at line 4319 of file xsdevice_def.cpp.
|
inlineprotected |
Definition at line 556 of file xsdevice_def.h.
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.
Definition at line 1945 of file xsdevice_def.cpp.
|
virtual |
XsDeviceConfiguration& XSNOEXPORT XsDevice::deviceConfigurationRef | ( | ) |
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.
Definition at line 742 of file xsdevice_def.cpp.
|
virtual |
Check if the device is docked.
Checks if device dev is docked in this device
dev | The device to check |
Definition at line 3673 of file xsdevice_def.cpp.
|
virtual |
Returns the device option flags.
Reimplemented in MtDevice.
Definition at line 562 of file xsdevice_def.cpp.
|
virtual |
Retrieves the requested parameter's current value.
Retrieving device parameters is only valid after initialization
parameter | a parameter object, corresponding to a row in the table listed under XsDevice::setParameter |
Definition at line 4468 of file xsdevice_def.cpp.
|
virtual |
|
virtual |
Return the state of this device.
The device state indiciates whether the device is in config mode, measuring, recording, etc
Definition at line 1064 of file xsdevice_def.cpp.
|
virtual |
Disable a communication protocol previously added by XsDevice::enableProtocol.
protocol | The type of protocol-support to remove. |
Definition at line 3304 of file xsdevice_def.cpp.
|
virtual |
Disables the radio for this station, resetting all children to disconnected state.
Definition at line 3488 of file xsdevice_def.cpp.
|
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.
firstNewPacketId | The first packet that (if missing) should be retransmitted. |
Definition at line 4598 of file xsdevice_def.cpp.
|
protected |
|
protected |
|
virtual |
Enable an additional communication protocol when reading messages.
protocol | The type of protocol-support to add. |
Definition at line 3280 of file xsdevice_def.cpp.
|
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.
channel | A valid channel number in the range [11..25] or -1 to disable the radio |
Definition at line 3478 of file xsdevice_def.cpp.
|
protectedvirtual |
|
virtual |
Returns the error mode of the device.
The error mode tells the device what to do if a problem occurs.
Reimplemented in MtiBaseDevice, and MtDevice.
Definition at line 2463 of file xsdevice_def.cpp.
|
protectedvirtual |
|
protected |
|
protected |
|
virtual |
Find the child device with deviceid.
This function returns the child device of the current device that matches the given ID.
deviceid | The device ID to search for |
Definition at line 500 of file xsdevice_def.cpp.
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.
deviceid | The device ID to search for |
Definition at line 512 of file xsdevice_def.cpp.
|
virtual |
Return the firmware version.
Definition at line 675 of file xsdevice_def.cpp.
|
protectedvirtual |
|
virtual |
Clear the inbound data buffers of the device.
Reimplemented in BroadcastDevice.
Definition at line 1807 of file xsdevice_def.cpp.
|
virtual |
Return the cached data packet with index.
index | The requested index, this does not have to be the same as the packet counter |
Definition at line 4193 of file xsdevice_def.cpp.
XsSize XsDevice::getDataPacketCount | ( | ) | const |
Return the current size of the retained data packet cache.
Definition at line 4206 of file xsdevice_def.cpp.
|
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.
XsOption XsDevice::getOptions | ( | ) | const |
Return the currently enabled options.
Definition at line 3443 of file xsdevice_def.cpp.
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
Definition at line 4374 of file xsdevice_def.cpp.
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
Definition at line 4383 of file xsdevice_def.cpp.
|
virtual |
Reimplemented in Mti6X0Device, and MTi7_MTi8Device.
Definition at line 2953 of file xsdevice_def.cpp.
XSNOEXPORT XSDEPRECATED XsGnssPlatform XsDevice::gnssPlatform | ( | ) | const |
|
virtual |
Gets some GNSS receiver settings.
Reimplemented in MtDevice.
Definition at line 4520 of file xsdevice_def.cpp.
|
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.
Reimplemented in BroadcastDevice.
Definition at line 1014 of file xsdevice_def.cpp.
|
virtual |
Put this device in measurement mode.
Measurement mode is where the device is sampling data and producing inertial and orientation output.
Reimplemented in BroadcastDevice.
Definition at line 960 of file xsdevice_def.cpp.
|
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.
Definition at line 2566 of file xsdevice_def.cpp.
|
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.
Reimplemented in MtDevice.
Definition at line 2727 of file xsdevice_def.cpp.
|
virtual |
|
virtual |
|
virtual |
|
virtual |
|
virtual |
|
virtual |
|
virtual |
|
virtual |
|
virtual |
Return the hardware version of the device.
Reimplemented in BroadcastDevice, and MtDevice.
Definition at line 3467 of file xsdevice_def.cpp.
|
virtual |
Returns if the currently configured output contains dataType.
dataType | The type of data to check the output for. |
Definition at line 632 of file xsdevice_def.cpp.
|
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.
dataType | The type of data to check the output for. |
Definition at line 665 of file xsdevice_def.cpp.
|
virtual |
Return the 'heading offset' setting of the device.
Reimplemented in MtDevice.
Definition at line 2495 of file xsdevice_def.cpp.
|
virtual |
Reimplemented in MtDevice, and BroadcastDevice.
|
virtual |
|
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.
Reimplemented in MtDevice.
Definition at line 2793 of file xsdevice_def.cpp.
|
protectedvirtual |
|
protectedvirtual |
|
virtual |
Returns true if the device has its BlueTooth radio enabled.
Definition at line 2413 of file xsdevice_def.cpp.
|
virtual |
Returns if the Xbus is powering its child devices or not.
When the bus power is off, the child devices are disabled
Definition at line 2432 of file xsdevice_def.cpp.
|
static |
Determines whether setting1 is compatible with setting2 for deviceId deviceId.
[in] | deviceId | The device id |
[in] | setting1 | Setting 1 |
[in] | setting2 | Setting 2 |
Definition at line 4068 of file xsdevice_def.cpp.
|
virtual |
Returns true if this device can have child devices.
Definition at line 1094 of file xsdevice_def.cpp.
|
virtual |
Returns if the fixed gravity value should be used or if it should be computed from the initialPositionLLA value.
Definition at line 2923 of file xsdevice_def.cpp.
|
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.
Definition at line 2900 of file xsdevice_def.cpp.
bool XsDevice::isInitialized | ( | ) | const |
Returns true when the device is initialized.
Definition at line 3721 of file xsdevice_def.cpp.
|
virtual |
Returns if the device is outputting data in string mode.
In string mode only NMEA packets are transmitted at the legacy update rate
Definition at line 3014 of file xsdevice_def.cpp.
|
virtual |
Definition at line 3792 of file xsdevice_def.cpp.
bool XsDevice::isLoadLogFileInProgress | ( | ) | const |
Returns true if the file operation started by loadLogFile is still in progress.
Definition at line 4349 of file xsdevice_def.cpp.
bool XsDevice::isMasterDevice | ( | ) | const |
Returns true if this is the master device (not a child of another device)
Definition at line 1086 of file xsdevice_def.cpp.
|
virtual |
Returns true if the device is currently in a measuring state.
Reimplemented in BroadcastDevice.
Definition at line 1741 of file xsdevice_def.cpp.
|
virtual |
Returns true if this is a motion tracker.
Reimplemented in MtDevice.
Definition at line 813 of file xsdevice_def.cpp.
|
virtual |
Definition at line 3786 of file xsdevice_def.cpp.
|
virtual |
[in] | protocol | The protocol type to check |
Definition at line 3326 of file xsdevice_def.cpp.
|
virtual |
Returns if the radio is enabled.
Definition at line 3497 of file xsdevice_def.cpp.
|
virtual |
Returns true if the device is reading from a file.
Reimplemented in BroadcastDevice.
Definition at line 1783 of file xsdevice_def.cpp.
|
virtual |
Returns true if the device is currently in a recording state.
Reimplemented in BroadcastDevice.
Definition at line 1762 of file xsdevice_def.cpp.
|
protectedvirtual |
|
protectedvirtual |
bool XsDevice::isStandaloneDevice | ( | ) | const |
Returns true if this is a standalone device (not a child of another device and not a container device)
Definition at line 1102 of file xsdevice_def.cpp.
|
virtual |
returns whether this device is in a master role regarding the device synchronization
Definition at line 750 of file xsdevice_def.cpp.
|
virtual |
returns whether this device is in a slave role regarding the device synchronization
Definition at line 758 of file xsdevice_def.cpp.
|
inlineprotected |
Definition at line 642 of file xsdevice_def.h.
XsDataPacket XsDevice::lastAvailableLiveData | ( | ) | const |
Return the last available live data.
Definition at line 4218 of file xsdevice_def.cpp.
|
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.
Definition at line 3624 of file xsdevice_def.cpp.
XsResultValue XsDevice::lastResult | ( | ) | const |
Get the result value of the last operation.
The result values are codes that describe a failure in more detail.
Definition at line 794 of file xsdevice_def.cpp.
XsString XsDevice::lastResultText | ( | ) | const |
Get the accompanying error text for the value returned by lastResult() It may provide situation-specific information instead.
Definition at line 804 of file xsdevice_def.cpp.
|
inlineprotected |
Definition at line 582 of file xsdevice_def.h.
|
inlineprotected |
Definition at line 596 of file xsdevice_def.h.
|
protectedvirtual |
|
inlineprotected |
Definition at line 575 of file xsdevice_def.h.
|
inlineprotected |
Definition at line 589 of file xsdevice_def.h.
|
protectedvirtual |
|
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.
Reimplemented in BroadcastDevice.
Definition at line 3045 of file xsdevice_def.cpp.
|
virtual |
Get the location ID of the device.
The location ID is a custom 16-bit ID that can be assigned to a device.
Reimplemented in MtDevice.
Definition at line 2517 of file xsdevice_def.cpp.
|
virtual |
|
virtual |
Get the name of the log file the device is reading from.
Returns an empty string when not in file mode.
Definition at line 3078 of file xsdevice_def.cpp.
XsFilePos XsDevice::logFileReadPosition | ( | ) | const |
Get the current read position of the open log file.
If the function encounters an error the function returns -1.
Definition at line 3236 of file xsdevice_def.cpp.
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.
Definition at line 3219 of file xsdevice_def.cpp.
|
virtual |
Sets the Awinda station to operational state.
Definition at line 3778 of file xsdevice_def.cpp.
|
virtual |
Return the master device of this device.
This function returns the master device of the current device. This may be the device itself
Definition at line 332 of file xsdevice_def.cpp.
|
virtual |
Get the maximum update rate for the device.
Definition at line 3102 of file xsdevice_def.cpp.
|
virtual |
Reimplemented in MtDevice.
|
inline |
Definition at line 498 of file xsdevice_def.h.
|
virtual |
Returns the object alignment matrix of the device.
Definition at line 2541 of file xsdevice_def.cpp.
|
virtual |
Gets the filter profile in use by the device for computing orientations.
Reimplemented in MtDevice.
Definition at line 2646 of file xsdevice_def.cpp.
|
virtual |
|
virtual |
|
virtual |
|
virtual |
|
virtual |
|
virtual |
|
virtual |
|
virtual |
Returns the operational mode.
Definition at line 3362 of file xsdevice_def.cpp.
|
inline |
Compare device ID with that of dev.
dev | Device to compare against |
Definition at line 226 of file xsdevice_def.h.
|
inline |
Compare device ID with devId.
devId | DeviceId to compare against |
Definition at line 236 of file xsdevice_def.h.
|
inline |
Compare device ID with that of dev.
dev | Device to compare against |
Definition at line 231 of file xsdevice_def.h.
|
inline |
Compare device ID with devId.
devId | DeviceId to compare against |
Definition at line 241 of file xsdevice_def.h.
|
virtual |
Returns the currently configured output of the device.
Reimplemented in MtDevice, and MtiBaseDevice.
Definition at line 3380 of file xsdevice_def.cpp.
|
staticprotected |
|
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.
Definition at line 3653 of file xsdevice_def.cpp.
|
virtual |
Get the current port configuration of a device.
Reimplemented in Mti6X0Device, and Mti8X0Device.
Definition at line 910 of file xsdevice_def.cpp.
|
virtual |
The port information of the connection.
Definition at line 3696 of file xsdevice_def.cpp.
|
virtual |
The port name of the connection.
Definition at line 3683 of file xsdevice_def.cpp.
|
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.
Definition at line 2454 of file xsdevice_def.cpp.
|
virtual |
|
protectedvirtual |
|
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.
Definition at line 1209 of file xsdevice_def.cpp.
|
protectedvirtual |
|
virtual |
Return the product code of the device.
Reimplemented in BroadcastDevice, and MtDevice.
Definition at line 3451 of file xsdevice_def.cpp.
|
virtual |
Returns the radio channel used for wireless communication.
Definition at line 3506 of file xsdevice_def.cpp.
|
protectedvirtual |
|
virtual |
|
virtual |
Returns internal meta-data about the recording that some devices store in the mtb logfile.
Definition at line 4652 of file xsdevice_def.cpp.
int XsDevice::recordingQueueLength | ( | ) | const |
Get the number of packets currently waiting in the slow data cache for the device based.
Definition at line 3118 of file xsdevice_def.cpp.
XsSize XsDevice::refCounter | ( | ) | const |
The current reference counter.
Definition at line 3819 of file xsdevice_def.cpp.
|
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.
Reimplemented in MtDevice.
Definition at line 2594 of file xsdevice_def.cpp.
|
protectedvirtual |
|
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.
Definition at line 3562 of file xsdevice_def.cpp.
|
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.
Definition at line 3614 of file xsdevice_def.cpp.
|
protected |
|
virtual |
Decrease this XsDevices reference counter with 1.
Also decreases the reference count of each child with 1
Definition at line 3831 of file xsdevice_def.cpp.
|
virtual |
Reopens a port Uses rescan method to redetect a device. Also if USB descriptor has changed.
gotoConfig | Set to true if the device should be put to config before port closure |
skipDeviceIdCheck | Set to true if the rescan should not verify the device id (not recommended) |
Definition at line 2017 of file xsdevice_def.cpp.
|
virtual |
Replaces profileCurrent by profileNew in the device.
profileCurrent | The profile that should be replaced |
profileNew | The new profile |
Definition at line 2685 of file xsdevice_def.cpp.
|
virtual |
Retrieves the active representative motion state for the In-Run Compass Calibration.
Reimplemented in MtiBaseDevice.
Definition at line 2762 of file xsdevice_def.cpp.
|
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
Reimplemented in BroadcastDevice.
Definition at line 2973 of file xsdevice_def.cpp.
|
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.
Reimplemented in MtDevice.
Definition at line 2875 of file xsdevice_def.cpp.
|
virtual |
|
virtual |
Reset the device.
This function tells the device to reboot itself.
Definition at line 1971 of file xsdevice_def.cpp.
|
virtual |
Reimplemented in BroadcastDevice.
|
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.
Reimplemented in MtDevice, and BroadcastDevice.
Definition at line 3198 of file xsdevice_def.cpp.
|
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.
resetmethod | The requested orientation reset method. |
Reimplemented in BroadcastDevice.
Definition at line 3187 of file xsdevice_def.cpp.
|
protectedvirtual |
|
protectedvirtual |
Reimplemented in MtiBaseDevice.
|
virtual |
Restart the software filter used by this device.
Definition at line 785 of file xsdevice_def.cpp.
|
virtual |
Restore the device to its factory default settings.
Reimplemented in BroadcastDevice, and MtDevice.
Definition at line 1953 of file xsdevice_def.cpp.
|
protected |
|
virtual |
Returns the transmission delay used for RS485 transmissions.
See the low level documentation for more information on this function.
Reimplemented in MtDevice, and MtiBaseDevice.
Definition at line 2841 of file xsdevice_def.cpp.
|
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.
Reimplemented in MtDevice.
Definition at line 2864 of file xsdevice_def.cpp.
|
protectedvirtual |
Reimplemented in MtDevice.
|
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.
messageSend | The message to send to the device |
waitForResult | true 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. |
messageReceive | When waitForResult is true, the reply will be put in this object. |
timeout | Optional timeout in ms. When 0 is supplied (the default), the default timeout is used. |
Definition at line 1302 of file xsdevice_def.cpp.
|
virtual |
|
virtual |
Send a message directly to the communicator.
[in] | message | The message that will be sent |
Definition at line 1311 of file xsdevice_def.cpp.
|
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.
Reimplemented in MtDevice.
Definition at line 837 of file xsdevice_def.cpp.
|
virtual |
Set the access control mode of the master device.
The access control mode determines which connections are allowed.
mode | The access control mode to use, the choice is between blacklist or whitelist |
initialList | The initial list to use for the selected access control mode |
Definition at line 3751 of file xsdevice_def.cpp.
|
virtual |
Set an arbitrary alignment rotation matrix Use to rotate either L to the chosen frame L' or S to the chosen frame S'.
frame | The frame to rotate |
matrix | The desired alignment rotation setting of the device. This should be an orthonormal 3x3 matrix. |
Reimplemented in MtiBaseDevice.
Definition at line 2120 of file xsdevice_def.cpp.
|
virtual |
Set an arbitrary alignment rotation quaternion. Use to rotate either L to the chosen frame L' or S to the chosen frame S'.
frame | The frame to rotate |
quat | The desired alignment rotation setting of the device. |
Reimplemented in MtiBaseDevice.
Definition at line 2094 of file xsdevice_def.cpp.
|
virtual |
Enable or disable the BlueTooth radio of the device.
enabled | Set to true to enable the BlueTooth radio |
Definition at line 2422 of file xsdevice_def.cpp.
|
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.
enabled | true to enable bus power, false to disable the bus power |
Definition at line 2444 of file xsdevice_def.cpp.
|
virtual |
Set the CAN configuration for this device.
config | Should consist of 8 bytes baudcode and 1 bit to enable CAN |
Reimplemented in Mti6X0Device, and Mti8X0Device.
Definition at line 1198 of file xsdevice_def.cpp.
|
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.
config | The desired output configuration |
Reimplemented in Mti6X0Device, and Mti8X0Device.
Definition at line 1188 of file xsdevice_def.cpp.
|
protected |
|
virtual |
Accepts a device.
[in] | deviceId | The device to accept |
Definition at line 3730 of file xsdevice_def.cpp.
|
virtual |
Request the device to set it's internal buffer to the specified size.
frames | buffer size in frames |
Definition at line 4328 of file xsdevice_def.cpp.
|
protected |
|
virtual |
Set the device option flags.
setFlags | The option flags that must be set. Set to XDOF_None if no flags need to be set |
clearFlags | The option flags that must be cleared. Set to XDOF_None if no flags need to be cleared |
Definition at line 1112 of file xsdevice_def.cpp.
|
virtual |
Sets the given parameter for the device.
Settings device parameters is only valid after initialization and before switching the device to be operational.
parameter | a parameter object, corresponding to a row in the table below. |
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.
|
virtual |
Rejects a device.
[in] | deviceId | The device to reject |
Definition at line 3739 of file xsdevice_def.cpp.
|
protectedvirtual |
|
virtual |
Sets the error mode of the device.
The error mode tells the device what to do if a problem occurs.
errormode | The desired error mode of the device |
Reimplemented in MtiBaseDevice, and MtDevice.
Definition at line 2473 of file xsdevice_def.cpp.
|
private |
|
virtual |
Sets whether the fixed gravity value should be used or if it should be computed from the initialPositionLLA value.
enable | true to use fixed gravity, false to compute from initialPositionLLA |
Definition at line 2934 of file xsdevice_def.cpp.
|
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
arm | The lever arm vector |
Reimplemented in Mti6X0Device, and MTi7_MTi8Device.
Definition at line 2946 of file xsdevice_def.cpp.
|
virtual |
|
virtual |
Sets some GNSS receiver settings.
gnssReceiverSettings | XsIntArray containing the receiver settings, that are to be set |
Reimplemented in MtDevice.
Definition at line 4529 of file xsdevice_def.cpp.
void XsDevice::setGotoConfigOnClose | ( | bool | gotoConfigOnClose | ) |
On closePort the device will go to config by default, with this function it is possible to prevent that.
gotoConfigOnClose | boolean |
Definition at line 519 of file xsdevice_def.cpp.
|
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.
mag | The desired 'Gravity Magnitude' setting of the device. |
Reimplemented in BroadcastDevice.
Definition at line 2579 of file xsdevice_def.cpp.
|
virtual |
Set the 'heading offset' setting of the device.
offset | The desired heading offset of the device in degrees |
Reimplemented in BroadcastDevice, and MtiBaseDevice.
Definition at line 2486 of file xsdevice_def.cpp.
|
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.
enable | true to enable the option, false to disable it |
Definition at line 2912 of file xsdevice_def.cpp.
|
inlineprotected |
Set the initialized state to initialized.
Definition at line 611 of file xsdevice_def.h.
|
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.
lla | The desired 'Latitude Longitude Altitude' setting for the device. This should be a 3-element vector. |
Reimplemented in MtDevice, BroadcastDevice, and MtiBaseDevice.
Definition at line 2809 of file xsdevice_def.cpp.
|
virtual |
Set the location ID of the device.
The location ID is a custom 16-bit ID that can be assigned to a device.
id | The desired location ID for the device |
Reimplemented in BroadcastDevice, and MtDevice.
Definition at line 2506 of file xsdevice_def.cpp.
|
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.
duration | The desired stationary duration in seconds |
Reimplemented in BroadcastDevice, MtDevice, and MtiBaseDevice.
Definition at line 2743 of file xsdevice_def.cpp.
|
virtual |
Sets the object alignment of the device to the given matrix.
matrix | The desired 'object alignment matrix' setting of the device. This should be an orthonormal 3x3 matrix. |
Reimplemented in BroadcastDevice.
Definition at line 2554 of file xsdevice_def.cpp.
|
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.
profileType | The filter profile type to use. This can be chosen from the list returned by availableOnboardFilterProfiles() |
Reimplemented in MtDevice, and BroadcastDevice.
Definition at line 2659 of file xsdevice_def.cpp.
|
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.
profileType | The filter profile type to use. This can be chosen from the list returned by availableOnboardFilterProfiles() |
Reimplemented in MtDevice, and BroadcastDevice.
Definition at line 2673 of file xsdevice_def.cpp.
|
virtual |
Set the device in the given operational mode.
mode | Desired operional mode. |
Definition at line 3371 of file xsdevice_def.cpp.
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.
enable | A logically OR'ed combination of XsOptions to enable |
disable | A logically OR'ed combination of XsOptions to disable |
Reimplemented in BroadcastDevice.
Definition at line 3411 of file xsdevice_def.cpp.
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.
config | The desired output configuration |
Definition at line 1138 of file xsdevice_def.cpp.
|
protectedvirtual |
Reimplemented in MtiBaseDevice.
|
virtual |
|
virtual |
Change the port configuration of a device.
Configures the 2 ports of the 6x0 device The integers consist of:
config | An array of elements containing a configuration for each port (UART and RS232) |
Reimplemented in Mti6X0Device, and Mti8X0Device.
Definition at line 930 of file xsdevice_def.cpp.
|
protectedvirtual |
|
protectedvirtual |
|
virtual |
Set the transmission delay used for RS485 transmissions.
See the low level documentation for more information on this function.
delay | The desired delay |
Reimplemented in MtDevice, and MtiBaseDevice.
Definition at line 2851 of file xsdevice_def.cpp.
|
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.
baudrate | The desired serial baudrate |
Reimplemented in BroadcastDevice.
Definition at line 875 of file xsdevice_def.cpp.
XSNOEXPORT void XsDevice::setSkipEmtsReadOnInit | ( | bool | skip | ) |
|
protectedvirtual |
|
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.
enabled | Set to true if you wish to enable stealth mode, false to disable it. |
Definition at line 4025 of file xsdevice_def.cpp.
|
protectedvirtual |
|
virtual |
Sets the string output mode for this device.
type | The type to set |
period | The period to set |
skipFactor | The skipFactor to set |
Reimplemented in MTi7_MTi8Device.
Definition at line 1220 of file xsdevice_def.cpp.
|
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.
settingList | The list of synchronization settings to set. An empty list will clear all synchronization settings. |
Reimplemented in MtiBaseDevice, and BroadcastDevice.
Definition at line 3158 of file xsdevice_def.cpp.
|
virtual |
Set the Sync Station mode of the Awinda Station device.
enabled | true to enable Sync Station mode, false to disable it |
Definition at line 3801 of file xsdevice_def.cpp.
|
inlineprotected |
Set the "termination prepared" state to prepared.
Definition at line 616 of file xsdevice_def.h.
|
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.
transportModeEnabled | true to enable transport mode (which disables the motion wakeup) |
Reimplemented in BroadcastDevice.
Definition at line 2995 of file xsdevice_def.cpp.
|
virtual |
Set the device GNSS platform for u-blox GNSS receivers.
ubloxGnssPlatform | The GNSS platform that must be set |
Reimplemented in Mti6X0Device, and MtDevice.
Definition at line 4511 of file xsdevice_def.cpp.
|
virtual |
Set the legacy update rate of the device.
[in] | rate | The desired legacy update rate for the device |
Definition at line 554 of file xsdevice_def.cpp.
|
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.
time | The current time in UTC format |
Reimplemented in MtiBaseDevice.
Definition at line 2831 of file xsdevice_def.cpp.
|
virtual |
Sets the wireless priority of the device.
priority | The desired wireless priority of the device in the range 0-255. |
Definition at line 3581 of file xsdevice_def.cpp.
|
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.
profileType | The filter profile type to use. This can be chosen from the list returned by availableXdaFilterProfiles() |
Reimplemented in BroadcastDevice.
Definition at line 2619 of file xsdevice_def.cpp.
|
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.
profileType | The filter profile type to use. This can be chosen from the list returned by availableXdaFilterProfiles() |
Reimplemented in BroadcastDevice.
Definition at line 2636 of file xsdevice_def.cpp.
|
virtual |
Return the shortened product code of the device suitable for display.
Reimplemented in Mti3X0Device, MtiXDevice, Mti6X0Device, Mti8X0Device, and MTi7_MTi8Device.
Definition at line 3459 of file xsdevice_def.cpp.
|
protectedvirtual |
|
protectedvirtual |
|
protectedvirtual |
|
protectedvirtual |
|
inlineprotected |
Definition at line 681 of file xsdevice_def.h.
|
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.
Reimplemented in BroadcastDevice.
Definition at line 2171 of file xsdevice_def.cpp.
|
virtual |
Let the user indicate that he is starting the representative motion for the In-Run Compass Calibration.
Reimplemented in MtiBaseDevice.
Definition at line 2753 of file xsdevice_def.cpp.
|
virtual |
Return the state of the stealth mode setting.
Definition at line 4034 of file xsdevice_def.cpp.
|
virtual |
Stop recording incoming data.
Reimplemented in BroadcastDevice.
Definition at line 2201 of file xsdevice_def.cpp.
|
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.
|
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.
Reimplemented in MtDevice, and BroadcastDevice.
Definition at line 2888 of file xsdevice_def.cpp.
|
virtual |
Store the onboard ICC results for use by the device.
Reimplemented in MtiBaseDevice.
Definition at line 2780 of file xsdevice_def.cpp.
|
virtual |
Returns the string output type.
Reimplemented in MtDevice.
Definition at line 3354 of file xsdevice_def.cpp.
|
virtual |
Returns the sample period for string output.
Reimplemented in MtDevice.
Definition at line 3337 of file xsdevice_def.cpp.
|
virtual |
Returns the skipfactor for string output.
Reimplemented in MtDevice.
Definition at line 3345 of file xsdevice_def.cpp.
|
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.
subDeviceId | The sub device id of the device to return. Which ids are valid depends on the type of device, 0 always indicates the main device. |
Definition at line 4632 of file xsdevice_def.cpp.
|
virtual |
Returns the number of sub-devices of this device.
This function returns the number of software-only sub devices of a larger device.
Definition at line 4644 of file xsdevice_def.cpp.
|
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.
Reimplemented in MtDevice, Mti3X0Device, MtiXDevice, Mti6X0Device, Mti8X0Device, MTi7_MTi8Device, MtiX00Device, MtiX0Device, and MtigDevice.
Definition at line 4610 of file xsdevice_def.cpp.
|
virtual |
Ask the device for its supported string output types.
Reimplemented in Mti6X0Device, Mti8X0Device, MtiX00Device, MtiX0Device, and MtigDevice.
Definition at line 1259 of file xsdevice_def.cpp.
|
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.
Definition at line 3175 of file xsdevice_def.cpp.
|
static |
Return the supported synchronization settings for a specified deviceId or deviceId mask.
[in] | deviceId | The device id to request the supported synchronization settings for |
Definition at line 4043 of file xsdevice_def.cpp.
|
virtual |
Ask the device for its supported update rates for the given dataType.
dataType | The type of data to get the supported update rates for |
Reimplemented in MtiBaseDevice, and BroadcastDevice.
Definition at line 2403 of file xsdevice_def.cpp.
|
static |
Determines whether the device specified by deviceId supports sync settings.
[in] | deviceId | The device id to check |
Definition at line 4057 of file xsdevice_def.cpp.
|
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.
Definition at line 1821 of file xsdevice_def.cpp.
|
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.
Reimplemented in MtiBaseDevice.
Definition at line 3144 of file xsdevice_def.cpp.
|
static |
[in] | deviceId | The deviceId |
Definition at line 4077 of file xsdevice_def.cpp.
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.
Definition at line 4230 of file xsdevice_def.cpp.
|
inline |
Definition at line 251 of file xsdevice_def.h.
|
virtual |
Returns the current state of the transport mode feature.
Definition at line 3005 of file xsdevice_def.cpp.
|
virtual |
Start recording incoming data through generating a virtual input trigger.
Definition at line 2191 of file xsdevice_def.cpp.
|
virtual |
Returns the device GNSS platform for u-blox GNSS receivers.
Reimplemented in Mti6X0Device, and MtDevice.
Definition at line 4501 of file xsdevice_def.cpp.
|
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.
Reimplemented in BroadcastDevice.
Definition at line 3254 of file xsdevice_def.cpp.
|
protected |
|
protectedvirtual |
|
protected |
|
virtual |
Update the connection information, this is only useful for devices communicating over a dynamic link such as a TCP/IP connection.
newInfo | The new port information to use in the next (re)connect attempts |
Definition at line 4620 of file xsdevice_def.cpp.
|
virtual |
Get the legacy update rate of the device.
This function is only valid for devices in legacy mode.
Definition at line 544 of file xsdevice_def.cpp.
|
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
dataType | The type of data to get the update rate for. |
Reimplemented in MtDevice.
Definition at line 601 of file xsdevice_def.cpp.
|
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.
dataType | The type of data to get the update rate for. |
Definition at line 622 of file xsdevice_def.cpp.
|
protected |
Uses log interface for a given data logger.
logger | The data logger |
For testing purposes
|
virtual |
Returns whether the device uses legacy device mode.
Definition at line 3022 of file xsdevice_def.cpp.
|
virtual |
Gets the 'UTC Time' setting of the device.
Gets the UTC time in the device.
Reimplemented in MtiBaseDevice.
Definition at line 2819 of file xsdevice_def.cpp.
|
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.
|
virtual |
|
virtual |
void XsDevice::waitForLoadLogFileDone | ( | ) | const |
Wait for the file operation started by loadLogFile to complete.
Definition at line 4364 of file xsdevice_def.cpp.
|
virtual |
Returns the wireless priority of the device.
Definition at line 3571 of file xsdevice_def.cpp.
|
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.
|
virtual |
|
protectedvirtual |
|
protectedvirtual |
|
virtual |
Gets the filter profile in use for computing orientations on the host PC.
Definition at line 2603 of file xsdevice_def.cpp.
|
protected |
|
friend |
Definition at line 543 of file xsdevice_def.h.
|
friend |
Definition at line 538 of file xsdevice_def.h.
|
protected |
A communicator.
Definition at line 721 of file xsdevice_def.h.
|
protected |
A device configuration.
Definition at line 712 of file xsdevice_def.h.
|
protected |
A current device connectivity state.
Definition at line 706 of file xsdevice_def.h.
|
protected |
A data cache.
Definition at line 691 of file xsdevice_def.h.
|
protected |
An ID of the device.
Definition at line 697 of file xsdevice_def.h.
|
mutableprotected |
The mutex for guarding state changes of the device.
Definition at line 667 of file xsdevice_def.h.
|
protected |
An EMTS blob from device.
Definition at line 761 of file xsdevice_def.h.
|
protected |
A firmware version.
Definition at line 718 of file xsdevice_def.h.
|
protected |
Go to confing on close boolean variable.
Definition at line 742 of file xsdevice_def.h.
|
protected |
Is intialized boolean variable.
Definition at line 736 of file xsdevice_def.h.
|
protected |
Just write setting boolean variable.
Definition at line 745 of file xsdevice_def.h.
|
protected |
A last available live data cache.
Definition at line 783 of file xsdevice_def.h.
|
protected |
A time stamp for an OK last data.
Definition at line 709 of file xsdevice_def.h.
|
mutableprotected |
The last result of an operation.
Definition at line 700 of file xsdevice_def.h.
|
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.
|
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.
|
protected |
A linear data packet cache.
Definition at line 780 of file xsdevice_def.h.
|
protected |
A data logger for a file interface.
Definition at line 724 of file xsdevice_def.h.
|
mutableprotected |
The mutex for guarding access to the log file.
Definition at line 670 of file xsdevice_def.h.
|
protected |
A device object.
Definition at line 727 of file xsdevice_def.h.
|
protected |
The options.
Definition at line 756 of file xsdevice_def.h.
|
protected |
A devices output configuration.
Definition at line 715 of file xsdevice_def.h.
|
protected |
A packet stamper.
Definition at line 753 of file xsdevice_def.h.
|
protected |
A reference counter.
Definition at line 730 of file xsdevice_def.h.
|
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.
|
protected |
The ID of the first packet that should be / was recorded.
Definition at line 766 of file xsdevice_def.h.
|
protected |
A current device state.
Definition at line 703 of file xsdevice_def.h.
|
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.
|
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.
|
protected |
Termination prepared boolean variable.
Definition at line 739 of file xsdevice_def.h.
|
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.
|
protected |
A packet ID of the last sample we know to be unavailable.
Definition at line 694 of file xsdevice_def.h.
|
protected |
Write to file boolean variable.
Definition at line 733 of file xsdevice_def.h.