|
| DotDevice (Communicator *comm) |
| Constructs a device. More...
|
|
| DotDevice (XsDevice *master) |
| An empty constructor for a master device. More...
|
|
virtual | ~DotDevice () |
| Destroys a device. More...
|
|
| MtiBaseDeviceEx (Communicator *comm) |
| Constructs a device. More...
|
|
| MtiBaseDeviceEx (XsDevice *master) |
| Constructs a device. More...
|
|
XsMatrix | alignmentRotationMatrix (XsAlignmentFrame frame) const override |
| Retrieve the alignment rotation matrix to rotate S to the chosen frame S'. More...
|
|
XsQuaternion | alignmentRotationQuaternion (XsAlignmentFrame frame) const override |
| Retrieve the alignment rotation quaternion. More...
|
|
XsErrorMode | errorMode () const override |
| Returns the error mode of the device. More...
|
|
int | getBaseFrequency (XsDataIdentifier dataType=XDI_None) const override |
|
| MtiBaseDevice (Communicator *comm) |
| Constructs a device. More...
|
|
| MtiBaseDevice (XsDevice *master) |
| Constructs a child device for a master device. More...
|
|
XsOutputConfigurationArray | outputConfiguration () const |
| Returns the currently configured output of the device. More...
|
|
bool | representativeMotionState () override |
|
uint16_t | rs485TransmissionDelay () const |
| Returns the transmission delay used for RS485 transmissions. More...
|
|
bool | setAlignmentRotationMatrix (XsAlignmentFrame frame, const XsMatrix &matrix) override |
| Set an arbitrary alignment rotation matrix Use to rotate either L to the chosen frame L' or S to the chosen frame S'. More...
|
|
bool | setAlignmentRotationQuaternion (XsAlignmentFrame frame, const XsQuaternion &quat) override |
| Set an arbitrary alignment rotation matrix Use to rotate either L to the chosen frame L' or S to the chosen frame S'. More...
|
|
bool | setErrorMode (XsErrorMode errorMode) override |
| Sets the error mode of the device. More...
|
|
bool | setHeadingOffset (double offset) |
| Set the 'heading offset' setting of the device. More...
|
|
bool | setInitialPositionLLA (const XsVector &lla) |
| Sets the 'Latitude Longitude Altitude' setting of the device to the given vector. More...
|
|
bool | setNoRotation (uint16_t duration) |
| Set the no rotation period to duration. More...
|
|
XsResultValue | setOutputConfigurationInternal (XsOutputConfigurationArray &o) override |
| Set the output configuration for this device. More...
|
|
bool | setRs485TransmissionDelay (uint16_t delay) |
| Set the transmission delay used for RS485 transmissions. More...
|
|
bool | setSyncSettings (const XsSyncSettingArray &s) override |
| Set the synchronization settings of the device. More...
|
|
bool | setUtcTime (const XsTimeInfo &time) |
| Sets the 'UTC Time' setting of the device to the given time. More...
|
|
bool | startRepresentativeMotion () override |
| Starts the representative motion. More...
|
|
XsIccRepMotionResult | stopRepresentativeMotion () override |
| Stops the representative motion. More...
|
|
bool | storeIccResults () override |
| Stores the ICC results. More...
|
|
std::vector< int > | supportedUpdateRates (XsDataIdentifier dataType=XDI_None) const override |
| Ask the device for its supported update rates for the given dataType. More...
|
|
XsSyncSettingArray | syncSettings () const override |
| Get all the current synchronization settings of the device. More...
|
|
XsTimeInfo | utcTime () const |
| Gets the 'UTC Time' setting of the device. More...
|
|
virtual | ~MtiBaseDevice () |
|
double | accelerometerRange () const |
|
XsFilterProfileArray | availableOnboardFilterProfiles () const override |
| Return the list of filter profiles available on the device. More...
|
|
virtual bool | canDoOrientationResetInFirmware (XsResetMethod method) |
| Checks if this device can do orientation reset in firmware. More...
|
|
XsDeviceOptionFlag | deviceOptionFlags () const override |
| Returns the device option flags. More...
|
|
XsIntArray | gnssReceiverSettings () const override |
| Gets some GNSS receiver settings. More...
|
|
double | gyroscopeRange () const |
|
XsVersion | hardwareVersion () const |
| Return the hardware version of the device. More...
|
|
double | headingOffset () const |
| The heading offset set for this device. More...
|
|
bool | initialize () override |
| Initialize the Mt device using the supplied filter profiles. More...
|
|
XsVector | initialPositionLLA () const override |
|
bool | isMotionTracker () const override |
|
int | locationId () const |
| Get the location ID of the device. More...
|
|
bool | messageLooksSane (const XsMessage &msg) const override |
| Checks for the sanity of a message. More...
|
|
XsFilterProfile | onboardFilterProfile () const override |
| Gets the filter profile in use by the device for computing orientations. More...
|
|
XsString | productCode () const |
| Return the product code of the device. More...
|
|
bool | reinitialize () |
| Reinitialize the XsDevice. More...
|
|
bool | requestData () |
| Request data from the motion tracker. More...
|
|
bool | restoreFactoryDefaults () |
| Restore to factory default settings. More...
|
|
XsSelfTestResult | runSelfTest () |
| Run a self test. More...
|
|
virtual bool | scheduleOrientationReset (XsResetMethod method) |
|
XsBaudRate | serialBaudRate () const override |
| The baud rate configured for cabled connection. More...
|
|
bool | setGnssReceiverSettings (const XsIntArray &gnssReceiverSettings) override |
| Sets some GNSS receiver settings. More...
|
|
virtual bool | setLocationId (int id) |
| Set the location ID of the device. More...
|
|
bool | setOnboardFilterProfile (int profileType) override |
| Sets the filter profile to use for computing orientations on the device. More...
|
|
bool | setOnboardFilterProfile (XsString const &profileType) override |
| Sets the filter profile to use for computing orientations on the device. More...
|
|
bool | setUbloxGnssPlatform (XsUbloxGnssPlatform ubloxGnssPlatform) override |
| Set the device GNSS platform for u-blox GNSS receivers. More...
|
|
virtual bool | storeAlignmentMatrix () |
| Store the current alignment matrix in the device. More...
|
|
bool | storeFilterState () override |
| Store orientation filter state in the device. More...
|
|
uint16_t | stringOutputType () const override |
| Returns the string output type. More...
|
|
uint16_t | stringSamplePeriod () const override |
| Returns the sample period for string output. More...
|
|
uint16_t | stringSkipFactor () const override |
| Returns the skipfactor for string output. More...
|
|
uint32_t | supportedStatusFlags () const override |
| Returns a bitmask with all the status flags supported by this device. More...
|
|
XsUbloxGnssPlatform | ubloxGnssPlatform () const override |
| Returns the device GNSS platform for u-blox GNSS receivers. More...
|
|
int | updateRateForDataIdentifier (XsDataIdentifier dataType) const override |
| Returns the currently configured update rate for the supplied dataType. More...
|
|
void | writeDeviceSettingsToFile () override |
| Write the emts of the device to the open logfile. More...
|
|
virtual | ~MtDevice () |
| Destroys the MtDevice. More...
|
|
bool | resetLogFileReadPosition () override |
| Set the read position of the open log file to the start of the file. More...
|
|
virtual bool | abortFlushing () |
| Abort the wireless flushing operation and finalize the recording. More...
|
|
virtual bool | abortLoadLogFile () |
| Aborts loading a logfile. 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 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 | 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 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 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 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 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 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 bool XSNOEXPORT | initializeSoftwareCalibration () |
|
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 | 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 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...
|
|
xsens::GuardedMutex * | mutex () const |
|
virtual XsMatrix | objectAlignment () const |
| Returns the object alignment matrix of the device. 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 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 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 | 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 | requestBatteryLevel () |
| Request the battery level from the device. More...
|
|
virtual XSNOEXPORT bool | requestUtcTime () |
|
virtual bool | reset () |
| Reset the device. More...
|
|
virtual XSNOEXPORT bool | reset (bool skipDeviceIdCheck) |
|
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 | 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 bool | setAccessControlMode (XsAccessControlMode mode, const XsDeviceIdArray &initialList) |
| Set the access control mode of the master device. 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 | 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) |
|
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 | setInitialBiasUpdateEnabled (bool enable) |
| Set if the device does gyroscope bias estimation when switching to measurement mode. More...
|
|
virtual bool | setObjectAlignment (const XsMatrix &matrix) |
| Sets the object alignment of the device to the given matrix. 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 | 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 | 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 | setUpdateRate (int rate) |
| Set the legacy update rate of the device. 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 | stealthMode () const |
| Return the state of the stealth mode setting. More...
|
|
virtual bool | stopRecording () |
| Stop recording incoming data. 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 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 XsSyncRole | syncRole () const |
| Returns the synchronization role 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 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 | 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 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 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...
|
|
virtual XSNOEXPORT void | onMessageSent (const XsMessage &message) |
|
virtual XSNOEXPORT void | onMessageReceived (const XsMessage &message) |
|
virtual XSNOEXPORT void | onMessageDetected2 (XsProtocolType type, const XsByteArray &rawMessage) |
|
virtual XSNOEXPORT void | onSessionRestarted () |
|
virtual XSNOEXPORT void | onConnectionLost () |
|
virtual XSNOEXPORT void | onEofReached () |
|
virtual XSNOEXPORT void | onWirelessConnectionLost () |
|
virtual XSNOEXPORT int64_t | deviceRecordingBufferItemCount (int64_t &lastCompletePacketId) const |
|
void | 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...
|
|