Go to the documentation of this file.
65 #ifndef XSDEVICE_DEF_H
66 #define XSDEVICE_DEF_H
127 #define DebugFileType FILE // required for autogenerate to correctly parse this
128 #define NOEXCEPT noexcept // required for autogenerate to correctly parse this
179 virtual int busId()
const;
253 return dynamic_cast<T*
>(
this);
274 #ifndef XSENS_NO_PORT_NUMBERS
350 virtual bool reset();
379 virtual std::vector<XsDevice*>
children()
const;
793 #ifndef XDA_PRIVATE_BUILD
796 #include "xsdeviceex.h"
virtual bool setPortConfiguration(XsIntArray &config)
Change the port configuration of a device.
XsOutputConfiguration findConfiguration(XsDataIdentifier dataType) const
virtual bool powerDown()
Tell the device to power down completely.
int64_t getStartRecordingPacketId() const
Return the ID of the first packet that should be recorded.
virtual std::vector< int > supportedUpdateRates(XsDataIdentifier dataType=XDI_None) const
Ask the device for its supported update rates for the given dataType.
virtual DataLogger XSNOEXPORT * logFileInterface(std::unique_ptr< xsens::Lock > &myLock) const
virtual bool expectingRetransmissionForPacket(int64_t packetId) const
bool isInitialized() const
Returns true when the device is initialized.
virtual bool setCanOutputConfiguration(XsCanOutputConfigurationArray &config)
Set the CAN output configuration for this device.
virtual XSNOEXPORT void handleUnavailableData(int64_t frameNumber)
bool operator==(const XsDevice &dev) const
Compare device ID with that of dev.
XsDataPacket lastAvailableLiveData() const
Return the last available live data.
virtual XsTimeInfo utcTime() const
Gets the 'UTC Time' setting of the device.
A class that represents a matrix of real numbers.
virtual XsVector gnssLeverArm() const
XsDevice const * findDeviceConst(XsDeviceId const &deviceid) const
Find the child device with deviceid.
virtual bool setRs485TransmissionDelay(uint16_t delay)
Set the transmission delay used for RS485 transmissions.
virtual XsSelfTestResult runSelfTest()
Run the self test for the device.
virtual bool enableProtocol(XsProtocolType protocol)
Enable an additional communication protocol when reading messages.
XsDeviceId const & deviceId() const
Return the device ID of the device.
bool isStandaloneDevice() const
Returns true if this is a standalone device (not a child of another device and not a container device...
void setTerminationPrepared(bool prepared) NOEXCEPT
Set the "termination prepared" state to prepared.
A class that represents a vector of real numbers.
void useLogInterface(DataLogger *logger)
Uses log interface for a given data logger.
virtual bool abortLoadLogFile()
Aborts loading a logfile.
virtual XSNOEXPORT void handleMessage(const XsMessage &msg)
virtual bool startRepresentativeMotion()
Let the user indicate that he is starting the representative motion for the In-Run Compass Calibratio...
virtual bool setErrorMode(XsErrorMode errormode)
Sets the error mode of the device.
virtual bool storeFilterState()
Store orientation filter state in the device.
virtual XSNOEXPORT void onMessageDetected2(XsProtocolType type, const XsByteArray &rawMessage)
virtual XsFilterProfileArray availableXdaFilterProfiles() const
Return the list of filter profiles available on the host PC.
virtual XsUbloxGnssPlatform ubloxGnssPlatform() const
Returns the device GNSS platform for u-blox GNSS receivers.
DataPacketCache m_dataCache
A data cache.
static bool supportsSyncSettings(XsDeviceId const &deviceId)
Determines whether the device specified by deviceId supports sync settings.
virtual bool isReadingFromFile() const
Returns true if the device is reading from a file.
A list of uint8_t values.
virtual uint16_t stringOutputType() const
Returns the string output type.
virtual int packetErrorRate() const
Returns the packet error rate for the for the device.
Structure that contains callback functions for the Xsens Device API.
virtual uint16_t stringSamplePeriod() const
Returns the sample period for string output.
virtual XsOperationalMode operationalMode() const
Returns the operational mode.
virtual XsDataPacket getDataPacketByIndex(XsSize index) const
Return the cached data packet with index.
DebugFileType * m_toaDumpFile
To a dump file.
virtual XsDevice const * firstChild() const
virtual bool setInitialPositionLLA(const XsVector &lla)
Sets the 'Latitude Longitude Altitude' setting of the device to the given vector.
virtual XSNOEXPORT ~XsDevice()
Destroy the device.
virtual XSNOEXPORT void handleErrorMessage(const XsMessage &msg)
virtual bool setSerialBaudRate(XsBaudRate baudrate)
Change the serial baudrate to baudrate.
class XSNOEXPORT PacketProcessor
void retainPacket(XsDataPacket const &pack)
Contains the result of the representative motion processed by ICC.
virtual XsDeviceState deviceState() const
Return the state of this device.
virtual XsDevice * master() const
Return the master device of this device.
virtual void removeRef()
Decrease this XsDevices reference counter with 1.
virtual XSNOEXPORT void onEofReached()
virtual XsFilterProfile xdaFilterProfile() const
Gets the filter profile in use for computing orientations on the host PC.
xsens::Mutex m_logFileMutex
The mutex for guarding access to the log file.
A list of XsFilterProfile values.
XsDevice(XsDeviceId const &id)
Construct an empty device with device id id.
@ XDI_None
Empty datatype.
bool m_skipEmtsReadOnInit
Skip EMTS read on init boolean variable.
virtual bool isInitialBiasUpdateEnabled() const
Returns if the device does gyroscope bias estimation when switching to measurement mode.
virtual XsByteArray readMetaDataFromLogFile()
Returns internal meta-data about the recording that some devices store in the mtb logfile.
Structure containing a full device configuration as returned by the ReqConfig message.
virtual void reinitializeProcessors()
XsDataPacket & latestBufferedPacket()
XsOutputConfigurationArray m_outputConfiguration
A devices output configuration.
virtual bool XSNOEXPORT initialize()
XSENS_DISABLE_COPY(XsDevice)
virtual bool isInSyncStationMode()
static bool packetContainsRetransmission(XsDataPacket const &pack)
virtual int16_t lastKnownRssi() const
Returns the last known RSSI value of the device.
bool m_terminationPrepared
Termination prepared boolean variable.
XSNOEXPORT XSDEPRECATED XsGnssPlatform gnssPlatform() const
virtual int locationId() const
Get the location ID of the device.
virtual bool setXdaFilterProfile(int profileType)
Sets the filter profile to use for computing orientations on the host PC.
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.
XsRejectReason
Identifiers for why a device's connection was rejected.
An abstract internal struct of a device.
const XsDevice * deviceAtBusIdConst(int busid) const
Return the device with bus ID busid.
virtual XsBaudRate serialBaudRate() const
The baud rate configured for cabled connection.
void setCommunicator(Communicator *comm)
virtual bool deviceIsDocked(XsDevice *dev) const
Check if the device is docked.
int64_t m_stoppedRecordingPacketId
The ID of the last packet that was recorded. Remains valid after Flushing has ended,...
virtual bool setSyncSettings(const XsSyncSettingArray &settingList)
Set the synchronization settings of the device.
virtual bool isBusPowerEnabled() const
Returns if the Xbus is powering its child devices or not.
A list of XsDeviceId values.
virtual bool isContainerDevice() const
Returns true if this device can have child devices.
virtual bool setStringOutputMode(uint16_t type, uint16_t period, uint16_t skipFactor)
Sets the string output mode for this device.
bool isMasterDevice() const
Returns true if this is the master device (not a child of another device)
XsConnectivityState m_connectivity
A current device connectivity state.
virtual XsVersion hardwareVersion() const
Return the hardware version of the device.
virtual XSNOEXPORT void handleWarningMessage(const XsMessage &msg)
virtual XsFilterProfileArray availableOnboardFilterProfiles() const
Return the list of filter profiles available on the device.
virtual bool disableProtocol(XsProtocolType protocol)
Disable a communication protocol previously added by XsDevice::enableProtocol.
Contains an interpreted data message. The class provides easy access to the contained data through it...
virtual bool sendRawMessage(const XsMessage &message)
Send a message directly to the communicator.
static bool checkDataEnabled(XsDataIdentifier dataType, XsOutputConfigurationArray const &configurations)
virtual void endRecordingStream()
virtual int updateRate() const
Get the legacy update rate of the device.
XsDataPacket * m_latestBufferedPacket
A copy of the latest ready recording packet. This is the last packet that was popped off the front of...
virtual XsFilterProfile onboardFilterProfile() const
Gets the filter profile in use by the device for computing orientations.
bool m_justWriteSetting
Just write setting boolean variable.
Contains the results of a self-test performed by an Xsens device.
virtual int subDeviceCount() const
Returns the number of sub-devices of this device.
virtual void writeDeviceSettingsToFile()
Write the emts/wms/xms of the device and all its children to the open logfile.
void setFirmwareVersion(const XsVersion &version)
virtual std::vector< XsDevice * > children() const
Return a managed array containing the child-devices this device has. For standalone devices this is a...
XsResultValue createLogFile(const XsString &filename)
Create a log file for logging.
virtual XsVector initialPositionLLA() const
Gets the 'Latitude Longitude Altitude' setting of the device.
virtual XSNOEXPORT bool requestUtcTime()
virtual XsResultValue setOutputConfigurationInternal(XsOutputConfigurationArray &config)
virtual XsPortInfo portInfo() const
The port information of the connection.
A list of XsString values.
virtual bool shouldDoRecordedCallback(XsDataPacket const &packet) const
XsOption m_options
The options.
virtual bool stealthMode() const
Return the state of the stealth mode setting.
A class that implements a quaternion.
virtual uint32_t supportedStatusFlags() const
Returns a bitmask with all the status flags supported by this device.
virtual bool reinitialize()
Reinitialize the XsDevice.
virtual XsString productCode() const
Return the product code of the device.
virtual bool transportMode()
Returns the current state of the transport mode feature.
virtual bool isRadioEnabled() const
Returns if the radio is enabled.
virtual XsOutputConfigurationArray outputConfiguration() const
Returns the currently configured output of the device.
XsDataPacket & latestLivePacket()
virtual int childCount() const
Return the number of child-devices this device has. For standalone devices this is always 0.
virtual XSNOEXPORT void onMessageReceived(const XsMessage &message)
void removeCallbackHandler(XsCallbackPlainC *cb, bool chain=true)
Remove a handler from the list.
XsSize getDataPacketCount() const
Return the current size of the retained data packet cache.
virtual void setRecordingStartFrame(uint16_t startFrame)
virtual int updateRateForDataIdentifier(XsDataIdentifier dataType) const
Returns the currently configured update rate for the supplied dataType.
virtual void flushInputBuffers()
Clear the inbound data buffers of the device.
virtual void clearProcessors()
int64_t m_unavailableDataBoundary
A packet ID of the last sample we know to be unavailable.
static bool isCompatibleSyncSetting(XsDeviceId const &deviceId, XsSyncSetting const &setting1, XsSyncSetting const &setting2)
Determines whether setting1 is compatible with setting2 for deviceId deviceId.
virtual void processBufferedPacket(XsDataPacket &pack)
void setDeviceId(const XsDeviceId &deviceId)
virtual XsString shortProductCode() const
Return the shortened product code of the device suitable for display.
Communicator * m_communicator
A communicator.
Communicator XSNOEXPORT * communicator() const
virtual bool setFixedGravityEnabled(bool enable)
Sets whether the fixed gravity value should be used or if it should be computed from the initialPosit...
virtual XsStringOutputTypeArray supportedStringOutputTypes() const
Ask the device for its supported string output types.
virtual bool stopRecording()
Stop recording incoming data.
virtual bool setNoRotation(uint16_t duration)
Set the no rotation period to duration.
XsOption
Xda options, used to control the kind of data processing done by XDA.
virtual XSNOEXPORT void handleWakeupMessage(const XsMessage &msg)
virtual bool setSyncStationMode(bool enabled)
Set the Sync Station mode of the Awinda Station device.
XsResultValue
Xsens result values.
virtual int64_t latestBufferedPacketId() const
void waitForLoadLogFileDone() const
Wait for the file operation started by loadLogFile to complete.
virtual int busId() const
The bus ID for this device.
virtual bool interpolateMissingData(XsDataPacket const &pack, XsDataPacket const &prev, std::function< void(XsDataPacket *)> packetHandler)
virtual XSNOEXPORT void onSessionRestarted()
bool operator<(const XsDevice &dev) const
Compare device ID with that of dev.
A list of XsOutputConfiguration values.
void updateLastAvailableLiveDataCache(XsDataPacket const &pack)
virtual bool resetRemovesPort() const
An abstract class for data logging.
virtual uint16_t rs485TransmissionDelay() const
Returns the transmission delay used for RS485 transmissions.
A structure for storing all xsens sync settings.
XsDataIdentifier
Defines the data identifiers.
virtual XsDevice * getDeviceFromLocationId(uint16_t locId)
Get the device given locId.
virtual bool isMotionTracker() const
Returns true if this is a motion tracker.
Contains information about an available filter profile.
virtual bool loadLogFile()
Load a complete logfile.
A base struct for a communication interface.
virtual bool isOperational() const
XsDeviceId m_deviceId
An ID of the device.
virtual XsDevice * findDevice(XsDeviceId const &deviceid) const
Find the child device with deviceid.
enum XsBaudRate XsBaudRate
Communication speed.
virtual void addRef()
Increase reference count of XsDevice pointer XsDevice pointers stay alive while reference counter is ...
virtual XSNOEXPORT void prepareForTermination()
virtual XsDeviceConfiguration const &XSNOEXPORT deviceConfigurationConst() const
XsDeviceState m_state
A current device state.
virtual bool setDeviceBufferSize(uint32_t frames)
Request the device to set it's internal buffer to the specified size.
virtual XsAccessControlMode accessControlMode() const
Request the access control mode of the master device.
virtual bool replaceFilterProfile(XsFilterProfile const &profileCurrent, XsFilterProfile const &profileNew)
Replaces profileCurrent by profileNew in the device.
bool setOutputConfiguration(XsOutputConfigurationArray &config)
Set the output configuration for this device.
Class to set and retrieve parameters from a XsDevice object.
Contains a descriptor for opening a communication port to an Xsens device.
XsDataPacket * m_latestLivePacket
A copy of the latest ready live packet. This is the packet with the highest 64-bit sample counter so ...
virtual XsVersion firmwareVersion() const
Return the firmware version.
virtual void setRecordingStopFrame(uint16_t stopFrame)
virtual XsSyncSettingArray syncSettings() const
Get all the current synchronization settings of the device.
virtual XsConnectivityState connectivityState() const
Returns the connectivity state of the device.
virtual XsBaudRate baudRate() const
Get the baud rate (communication speed) of the serial port on which the given deviceId is connected.
virtual bool setHeadingOffset(double offset)
Set the 'heading offset' setting of the device.
virtual bool restoreFactoryDefaults()
Restore the device to its factory default settings.
virtual bool representativeMotionState()
Retrieves the active representative motion state for the In-Run Compass Calibration.
int64_t m_stopRecordingPacketId
The ID of the last packet that should be / was recorded. Only valid in Recording/Flushing states.
PacketStamper m_packetStamper
A packet stamper.
virtual XSNOEXPORT bool messageLooksSane(const XsMessage &msg) const
virtual double headingOffset() const
Return the 'heading offset' setting of the device.
virtual void updateDeviceState(XsDeviceState state)
LastResultManager m_lastResult
The last result of an operation.
XsFilePos logFileReadPosition() const
Get the current read position of the open log file.
XsDeviceConfiguration m_config
A device configuration.
XsVersion m_firmwareVersion
A firmware version.
virtual void waitForAllDevicesInitialized()
Wait until are known devices are initialized.
virtual bool isSoftwareFilteringEnabled() const
XsTimeStamp m_lastDataOkStamp
A time stamp for an OK last data.
virtual void discardRetransmissions(int64_t firstNewPacketId)
Tell XDA and the device that any data from before firstNewPacketId may be lossy.
virtual void XSNOEXPORT checkDataCache()
virtual XsDevice * deviceAtBusId(int busid)
Return the device with bus ID busid.
virtual bool storeIccResults()
Store the onboard ICC results for use by the device.
virtual int updateRateForProcessedDataIdentifier(XsDataIdentifier dataType) const
Returns the currently configured update rate for the supplied dataType.
virtual XSNOEXPORT bool waitForCustomMessage(XsXbusMessageId messageId, XsMessage &messageReceive, int timeout=0)
XsSize refCounter() const
The current reference counter.
virtual bool setUpdateRate(int rate)
Set the legacy update rate of the device.
virtual XsCanOutputConfigurationArray canOutputConfiguration() const
Returns the currently configured CAN output of the device.
virtual XsResultValue deviceParameter(XsDeviceParameter ¶meter) const
Retrieves the requested parameter's current value.
virtual XSNOEXPORT void setPacketErrorRate(int per)
virtual int maximumUpdateRate() const
Get the maximum update rate for the device.
bool skipEmtsReadOnInit() const
bool m_gotoConfigOnClose
Go to confing on close boolean variable.
XsSyncRole
Synchronization roles.
virtual bool setOnboardFilterProfile(int profileType)
Sets the filter profile to use for computing orientations on the device.
XsResetMethod
Orientation reset type.
virtual bool isSyncMaster() const
returns whether this device is in a master role regarding the device synchronization
size_t XsSize
XsSize must be unsigned number!
void setGotoConfigOnClose(bool gotoConfigOnClose)
On closePort the device will go to config by default, with this function it is possible to prevent th...
XsDataPacket takeFirstDataPacketInQueue()
Return the first packet in the packet queue or an empty packet if the queue is empty.
A class that represents a fixed size (3x3) matrix.
virtual void resetPacketStamping()
A class to store version information.
DataLogger * m_logFileInterface
A data logger for a file interface.
virtual uint32_t deviceBufferSize()
Request the size of the interal buffer.
XsAccessControlMode
Device access control modes (XsDevice::setAccessControlMode())
virtual bool enableRadio(int channel)
Set the radio channel to use for wireless communication.
virtual double gyroscopeRange() const
Returns the maximum official value of the gyroscopes in the device.
XsXbusMessageId
Xsens Xbus Message Identifiers.
virtual uint16_t stringSkipFactor() const
Returns the skipfactor for string output.
virtual void setDeviceState(XsDeviceState state)
virtual XsIntArray gnssReceiverSettings() const
Gets some GNSS receiver settings.
virtual bool startRecording()
Start recording incoming data.
virtual bool setWirelessPriority(int priority)
Sets the wireless priority of the device.
bool m_writeToFile
Write to file boolean variable.
virtual void insertIntoDataCache(int64_t pid, XsDataPacket *pack)
virtual XsString portName() const
The port name of the connection.
bool justWriteSetting() const
virtual bool reopenPort(bool gotoConfig, bool skipDeviceIdCheck=false)
Reopens a port Uses rescan method to redetect a device. Also if USB descriptor has changed.
Structure for storing a single message.
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 ...
virtual bool isRecording() const
Returns true if the device is currently in a recording state.
virtual bool reset()
Reset the device.
virtual bool isProtocolEnabled(XsProtocolType protocol) const
virtual XsIccRepMotionResult stopRepresentativeMotion()
Let the user indicate that he stopped the representative motion.
virtual void processLivePacket(XsDataPacket &pack)
virtual bool setStealthMode(bool enabled)
Enable or disable stealth mode.
virtual XsMatrix alignmentRotationMatrix(XsAlignmentFrame frame) const
Retrieve the alignment rotation matrix to rotate S to the chosen frame S'.
virtual bool setObjectAlignment(const XsMatrix &matrix)
Sets the object alignment of the device to the given matrix.
volatile std::atomic_int m_refCounter
A reference counter.
XsResultValue lastResult() const
Get the result value of the last operation.
Contains an Xsens device ID and provides operations for determining the type of device.
xsens::GuardedMutex m_deviceMutex
The mutex for guarding state changes of the device.
virtual XsResultValue applyConfigFile(const XsString &filename)
Loads a config file(.xsa) and configures the device accordingly.
virtual int radioChannel() const
Returns the radio channel used for wireless communication.
XsDataPacket * m_lastAvailableLiveDataCache
A last available live data cache.
virtual void setStartRecordingPacketId(int64_t startFrame)
virtual bool shouldDataMsgBeRecorded(const XsMessage &msg) const
virtual XsRejectReason rejectReason() const
Returns the reason why a device's connection was rejected.
virtual bool setOperationalMode(XsOperationalMode mode)
Set the device in the given operational mode.
Container for combined calibrated measurement data from accelerometers, gyroscopes and magnetometers.
virtual XSNOEXPORT bool readEmtsAndDeviceConfiguration()
virtual bool closeLogFile()
Close the log file.
static unsigned int syncSettingsTimeResolutionInMicroSeconds(XsDeviceId const &deviceId)
virtual XSNOEXPORT void onConnectionLost()
virtual bool setUbloxGnssPlatform(XsUbloxGnssPlatform ubloxGnssPlatform)
Set the device GNSS platform for u-blox GNSS receivers.
virtual bool updateCachedDeviceInformation()
Updates the cached device information for all devices connected to this port.
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...
void updateConnectivityState(XsConnectivityState newState)
virtual XSNOEXPORT void onMessageSent(const XsMessage &message)
virtual bool isSoftwareCalibrationEnabled() const
virtual bool readDeviceConfiguration()
XsDataPacket const & latestLivePacketConst() const
virtual XSNOEXPORT void handleMasterIndication(const XsMessage &message)
virtual bool isSyncSlave() const
returns whether this device is in a slave role regarding the device synchronization
virtual XsResultValue setDeviceParameter(XsDeviceParameter const ¶meter)
Sets the given parameter for the device.
virtual bool setGnssLeverArm(const XsVector &arm)
Sets the GNSS Lever Arm vector.
virtual XsString logFileName() const
Get the name of the log file the device is reading from.
virtual double accelerometerRange() const
Returns the maximum official value of the accelerometers in the device.
Container for raw sensor measurement data.
virtual bool resetLogFileReadPosition()
Set the read position of the open log file to the start of the file.
virtual bool requestBatteryLevel()
Request the battery level from the device.
virtual bool gotoConfig()
Put the device in config mode.
XsConnectivityState
XsDevice connectivity state identifiers.
virtual void clearDataCache()
Supplies functionality for timestamping data packets.
virtual bool areOptionsEnabled(XsOption options) const
Returns true when all the specified processing options are enabled.
XsOption getOptions() const
Return the currently enabled options.
virtual XsDeviceOptionFlag deviceOptionFlags() const
Returns the device option flags.
virtual bool abortFlushing()
Abort the wireless flushing operation and finalize the recording.
virtual bool usesLegacyDeviceMode() const
Returns whether the device uses legacy device mode.
virtual void setStopRecordingPacketId(int64_t stopFrame)
virtual bool setGnssReceiverSettings(const XsIntArray &gnssReceiverSettings)
Sets some GNSS receiver settings.
virtual bool isInStringOutputMode() const
Returns if the device is outputting data in string mode.
virtual uint32_t canConfiguration() const
Returns the currently configured CAN configuration of the device.
virtual bool acceptConnection()
Accept connections from the device on the parent/master device.
virtual XsIntArray portConfiguration() const
Get the current port configuration of a device.
XsDeviceConfiguration deviceConfiguration() const
Returns the device configuration.
virtual bool gotoMeasurement()
Put this device in measurement mode.
virtual bool disableRadio()
Disables the radio for this station, resetting all children to disconnected state.
virtual bool rejectConnection()
Reject connections from the device on the parent/master device.
XsErrorMode
Error modes for use in XsDevice::setErrorMode.
virtual bool setAccessControlMode(XsAccessControlMode mode, const XsDeviceIdArray &initialList)
Set the access control mode of the master device.
XsProtocolType
Protocol types (XsDevice::enableProtocol())
virtual bool setTransportMode(bool transportModeEnabled)
Enable or disable the transport mode for the device.
A list of XsSyncSetting values.
virtual bool shouldWriteMessageToLogFile(const XsMessage &msg) const
virtual bool resetOrientation(XsResetMethod resetmethod)
Perform an orientation reset on the device using the given resetMethod.
virtual void setOptions(XsOption enable, XsOption disable)
Enable and disable processing options.
virtual bool setGravityMagnitude(double mag)
Sets the 'Gravity Magnitude' of the device to the given value mag.
int64_t m_startRecordingPacketId
The ID of the first packet that should be / was recorded.
virtual bool setUtcTime(const XsTimeInfo &time)
Sets the 'UTC Time' setting of the device to the given time.
virtual XsResultValue createConfigFile(const XsString &filename)
Stores the current device configuration in a config file(.xsa)
virtual XSNOEXPORT int64_t deviceRecordingBufferItemCount(int64_t &lastCompletePacketId) const
virtual XsDeviceIdArray currentAccessControlList() const
Request the access control list of the master device.
virtual XsDevice * subDevice(int subDeviceId) const
Returns the sub-device at index index.
virtual void writeMessageToLogFile(const XsMessage &message)
virtual XSNOEXPORT void handleDataPacket(const XsDataPacket &packet)
virtual bool XSNOEXPORT initializeSoftwareCalibration()
virtual bool isMeasuring() const
Returns true if the device is currently in a measuring state.
virtual bool setDeviceAccepted(const XsDeviceId &deviceId)
Accepts a device.
int recordingQueueLength() const
Get the number of packets currently waiting in the slow data cache for the device based.
const XsDeviceConfiguration & deviceConfig() const
xsens::GuardedMutex * mutex() const
virtual bool isBlueToothEnabled() const
Returns true if the device has its BlueTooth radio enabled.
class XSNOEXPORT MtContainer
virtual bool requestData()
Request data when configured in legacy mode with infinite skip factor.
virtual XsQuaternion alignmentRotationQuaternion(XsAlignmentFrame frame) const
Retrieve the alignment rotation quaternion.
This class manages a result code with optional additional text.
A list of XsStringOutputType values.
XsMessage m_emtsBlob
An EMTS blob from device.
virtual int batteryLevel() const
Get the batterylevel of this device The battery level is a value between 0 and 100 that indicates the...
virtual int wirelessPriority() const
Returns the wireless priority of the device.
virtual double gravityMagnitude() const
Returns the 'Gravity Magnitude' of the device.
XsDeviceConfiguration &XSNOEXPORT deviceConfigurationRef()
void setInitialized(bool initialized)
Set the initialized state to initialized.
virtual XSNOEXPORT void onWirelessConnectionLost()
A list of XsCanOutputConfiguration values.
XsDeviceState
XsDevice state identifiers.
virtual XsMatrix objectAlignment() const
Returns the object alignment matrix of the device.
virtual bool setInitialBiasUpdateEnabled(bool enable)
Set if the device does gyroscope bias estimation when switching to measurement mode.
virtual void clearCacheToRecordingStart()
virtual std::shared_ptr< ReplyObject > addReplyObject(XsXbusMessageId messageId, uint8_t data)
virtual XSNOEXPORT bool writeEmtsPage(uint8_t const *data, int pageNr, int bankNr)
virtual bool makeOperational()
Sets the Awinda station to operational state.
bool doTransaction(const XsMessage &snd) const
A two-layer mutex, typically used for status+data protection.
Single data type output configuration.
virtual bool scheduleOrientationReset(XsResetMethod method)
Class that delegates callbacks to registered XsCallbackHandlerItems.
virtual bool setDeviceRejected(const XsDeviceId &deviceId)
Rejects a device.
XSNOEXPORT virtual XSDEPRECATED bool setGnssPlatform(XsGnssPlatform gnssPlatform)
XsFilePos logFileSize() const
Get the size of the log file the device is reading from.
virtual bool setBlueToothEnabled(bool enabled)
Enable or disable the BlueTooth radio of the device.
int64_t XsFilePos
The type that is used for positioning inside a file.
A 0-terminated managed string of characters.
virtual void clearExternalPacketCaches()
std::deque< XsDataPacket * > m_linearPacketCache
A linear data packet cache.
virtual void writeFilterStateToFile()
virtual XsSyncSettingArray supportedSyncSettings() const
Get all supported synchronization settings available on the device.
virtual void XSNOEXPORT deinitializeSoftwareCalibration()
void extractFirmwareVersion(XsMessage const &message)
XsDataPacket const & latestBufferedPacketConst() const
virtual bool setCanConfiguration(uint32_t config)
Set the CAN configuration for this device.
virtual bool hasDataEnabled(XsDataIdentifier dataType) const
Returns if the currently configured output contains dataType.
virtual int dataLength() const
Returns the length of the data in the legacy MTData packets that the device will send in measurement ...
virtual XsSyncRole syncRole() const
Returns the synchronization role of the device.
bool m_isInitialized
Is intialized boolean variable.
int cacheSize() const
Get the number of items currently in the slow data cache for the device.
virtual XsOutputConfigurationArray processedOutputConfiguration() const
Return the full output configuration including post processing outputs.
XSNOEXPORT void setSkipEmtsReadOnInit(bool skip)
virtual void restartFilter()
Restart the software filter used by this device.
virtual XsErrorMode errorMode() const
Returns the error mode of the device.
virtual XSNOEXPORT void handleNonDataMessage(const XsMessage &msg)
virtual bool setDeviceOptionFlags(XsDeviceOptionFlag setFlags, XsDeviceOptionFlag clearFlags)
Set the device option flags.
virtual XsConnectivityState defaultChildConnectivityState() const
bool isLoadLogFileInProgress() const
Returns true if the file operation started by loadLogFile is still in progress.
This class contains method to set, retrieve and compare timestamps.
virtual bool setBusPowerEnabled(bool enabled)
Tell the Xbus to provide power to its child devices or not.
void clearCallbackHandlers(bool chain=true)
Clear the callback list.
XsDevice * m_master
A device object.
virtual XsResultValue updatePortInfo(XsPortInfo const &newInfo)
Update the connection information, this is only useful for devices communicating over a dynamic link ...
virtual bool isFixedGravityEnabled() const
Returns if the fixed gravity value should be used or if it should be computed from the initialPositio...
XsDeviceOptionFlag
Used to enable or disable some device options.
int64_t getStopRecordingPacketId() const
Return the ID of the last packet that should be recorded.
virtual bool triggerStartRecording()
Start recording incoming data through generating a virtual input trigger.
XsString lastResultText() const
Get the accompanying error text for the value returned by lastResult() It may provide situation-speci...
XsAlignmentFrame
Alignment frame.
void addCallbackHandler(XsCallbackPlainC *cb, bool chain=true)
Add a handler to the list.
virtual int64_t latestLivePacketId() const
virtual XsTimeStamp batteryLevelTime()
Requests the time the battery level was last updated.
A structure for storing Time values.
virtual bool setLocationId(int id)
Set the location ID of the device.
virtual bool hasProcessedDataEnabled(XsDataIdentifier dataType) const
Returns if the currently configured output contains dataType after processing on the host.