xsdevice_def.h
Go to the documentation of this file.
1 
2 // Copyright (c) 2003-2021 Xsens Technologies B.V. or subsidiaries worldwide.
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without modification,
6 // are permitted provided that the following conditions are met:
7 //
8 // 1. Redistributions of source code must retain the above copyright notice,
9 // this list of conditions, and the following disclaimer.
10 //
11 // 2. Redistributions in binary form must reproduce the above copyright notice,
12 // this list of conditions, and the following disclaimer in the documentation
13 // and/or other materials provided with the distribution.
14 //
15 // 3. Neither the names of the copyright holders nor the names of their contributors
16 // may be used to endorse or promote products derived from this software without
17 // specific prior written permission.
18 //
19 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY
20 // EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
21 // MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL
22 // THE COPYRIGHT HOLDERS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
23 // SPECIAL, EXEMPLARY OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
24 // OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
25 // HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY OR
26 // TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
27 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.THE LAWS OF THE NETHERLANDS
28 // SHALL BE EXCLUSIVELY APPLICABLE AND ANY DISPUTES SHALL BE FINALLY SETTLED UNDER THE RULES
29 // OF ARBITRATION OF THE INTERNATIONAL CHAMBER OF COMMERCE IN THE HAGUE BY ONE OR MORE
30 // ARBITRATORS APPOINTED IN ACCORDANCE WITH SAID RULES.
31 //
32 
33 
34 // Copyright (c) 2003-2021 Xsens Technologies B.V. or subsidiaries worldwide.
35 // All rights reserved.
36 //
37 // Redistribution and use in source and binary forms, with or without modification,
38 // are permitted provided that the following conditions are met:
39 //
40 // 1. Redistributions of source code must retain the above copyright notice,
41 // this list of conditions, and the following disclaimer.
42 //
43 // 2. Redistributions in binary form must reproduce the above copyright notice,
44 // this list of conditions, and the following disclaimer in the documentation
45 // and/or other materials provided with the distribution.
46 //
47 // 3. Neither the names of the copyright holders nor the names of their contributors
48 // may be used to endorse or promote products derived from this software without
49 // specific prior written permission.
50 //
51 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY
52 // EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
53 // MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL
54 // THE COPYRIGHT HOLDERS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
55 // SPECIAL, EXEMPLARY OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
56 // OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
57 // HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY OR
58 // TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
59 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.THE LAWS OF THE NETHERLANDS
60 // SHALL BE EXCLUSIVELY APPLICABLE AND ANY DISPUTES SHALL BE FINALLY SETTLED UNDER THE RULES
61 // OF ARBITRATION OF THE INTERNATIONAL CHAMBER OF COMMERCE IN THE HAGUE BY ONE OR MORE
62 // ARBITRATORS APPOINTED IN ACCORDANCE WITH SAID RULES.
63 //
64 
65 #ifndef XSDEVICE_DEF_H
66 #define XSDEVICE_DEF_H
67 
68 #include <xstypes/xssyncrole.h>
69 #include <xstypes/xsversion.h>
70 #include "packetstamper.h"
71 #include "xsdeviceconfiguration.h"
72 #include "xserrormode.h"
73 #include <xstypes/xsresetmethod.h>
74 #include "callbackmanagerxda.h"
75 #include <xstypes/xsoption.h>
76 #include "xsrejectreason.h"
77 #include "communicator.h"
78 #include "xsalignmentframe.h"
79 #include "xsaccesscontrolmode.h"
80 #include "datapacketcache.h"
83 #include "lastresultmanager.h"
84 #include "xsgnssplatform.h"
85 #include <functional>
86 #include "xsoperationalmode.h"
87 
91 
92 //AUTO namespace xstypes {
93 struct XsString;
94 struct XsDeviceId;
95 struct XsPortInfo;
96 struct XsDataPacket;
97 struct XsSyncSetting;
98 struct XsVersion;
99 struct XsScrData;
100 struct XsCalibratedData;
101 struct XsTimeInfo;
104 struct XsIntArray;
105 struct XsMatrix3x3;
106 struct XsDeviceIdArray;
107 struct XsDataPacket;
108 struct XsMessage;
109 struct XsSyncSettingArray;
110 struct XsMatrix;
111 struct XsVector;
112 struct XsStringArray;
113 struct XsQuaternion;
114 struct XsFilterProfileArray;
115 struct XsOutputConfiguration;
117 //AUTO+chdr struct XsException;
118 //AUTO }
119 
120 //AUTO namespace xscontroller {
121 struct XsCallbackPlainC;
122 struct XsSelfTestResult;
123 struct XsDeviceParameter;
124 struct XsIccRepMotionResult;
125 //AUTO }
126 
127 #define DebugFileType FILE // required for autogenerate to correctly parse this
128 #define NOEXCEPT noexcept // required for autogenerate to correctly parse this
129 
130 //AUTO namespace xstypes {
131 struct XsFilterProfile;
132 //AUTO enum XsBaud;
133 //AUTO enum XsResultValue;
134 //AUTO enum XsSyncRole;
135 //AUTO struct XsIntArray;
136 //AUTO struct XsOutputConfigurationArray;
137 //AUTO struct XsCanOutputConfigurationArray;
138 //AUTO struct XsSyncSettingArray;
139 //AUTO enum XsXbusMessageId;
140 //AUTO enum XsFilePos;
141 //AUTO struct XsFilterProfileArray;
142 //AUTO enum XsDeviceOptionFlag;
143 //AUTO enum XsResetMethod;
144 //AUTO enum XsOption;
145 //AUTO }
146 
147 //AUTO namespace xscontroller {
148 //AUTO struct XsDevicePtrArray;
149 //AUTO enum XsDeviceState;
150 //AUTO enum XsErrorMode;
151 //AUTO struct XsDeviceConfiguration;
152 //AUTO enum XsProtocolType;
153 //AUTO enum XsRejectReason;
154 //AUTO enum XsAlignmentFrame;
155 //AUTO enum XsOperationalMode;
156 //AUTO enum XsAccessControlMode;
157 //AUTO struct XsDeviceParameter;
158 //AUTO enum XsUbloxGnssPlatform;
159 //AUTO struct XsIccRepMotionResult;
160 //AUTO }
161 
162 //AUTO struct XdaConfig;
163 
165 {
166 public:
167  XSNOEXPORT virtual ~XsDevice();
168 
169  virtual void addRef();
170  virtual void removeRef();
171  XsSize refCounter() const;
172 
173  virtual XsDevice* master() const;
174 
175  virtual XsDevice* findDevice(XsDeviceId const& deviceid) const;
176  XsDevice const* findDeviceConst(XsDeviceId const& deviceid) const;
177  virtual XsDevice* subDevice(int subDeviceId) const;
178  virtual int subDeviceCount() const;
179  virtual int busId() const;
180  XsDeviceId const& deviceId() const;
181  virtual XsVersion firmwareVersion() const;
182  bool isMasterDevice() const;
183  virtual bool isContainerDevice() const;
184  bool isInitialized() const;
185  bool isStandaloneDevice() const;
186 
187  const XsDevice* deviceAtBusIdConst(int busid) const;
188  virtual XsDevice* deviceAtBusId(int busid);
189 
191  virtual DataLogger XSNOEXPORT* logFileInterface(std::unique_ptr<xsens::Lock>& myLock) const;
192  virtual XsResultValue updatePortInfo(XsPortInfo const& newInfo);
193 
194  void setGotoConfigOnClose(bool gotoConfigOnClose);
195 
196  XsResultValue createLogFile(const XsString& filename);
197  virtual bool closeLogFile();
198 
199  virtual bool isMeasuring() const;
200  virtual bool isRecording() const;
201  virtual bool isReadingFromFile() const;
202 
203  virtual void XSNOEXPORT checkDataCache();
204  virtual void restartFilter();
205 
206  XsResultValue lastResult() const;
207  XsString lastResultText() const;
208 
209  int recordingQueueLength() const;
210  int cacheSize() const;
211 
212  virtual XsDeviceState deviceState() const;
213 
214  static bool supportsSyncSettings(XsDeviceId const& deviceId);
215  static bool isCompatibleSyncSetting(XsDeviceId const& deviceId, XsSyncSetting const& setting1, XsSyncSetting const& setting2);
217 
218 #ifdef DOXYGEN
219  // Explicit inheritance for generator
220  void XSNOCOMEXPORT clearCallbackHandlers(bool chain = true);
221  void XSNOCOMEXPORT addCallbackHandler(XsCallbackPlainC* cb, bool chain = true);
222  void XSNOCOMEXPORT removeCallbackHandler(XsCallbackPlainC* cb, bool chain = true);
223 #endif
224 
226  bool operator < (const XsDevice& dev) const
227  {
228  return m_deviceId.toInt() < dev.m_deviceId.toInt();
229  }
231  bool operator == (const XsDevice& dev) const
232  {
233  return m_deviceId.toInt() == dev.m_deviceId.toInt();
234  }
236  bool operator < (XsDeviceId const& devId) const
237  {
238  return m_deviceId.toInt() < devId.toInt();
239  }
241  bool operator == (XsDeviceId const& devId) const
242  {
243  return m_deviceId.toInt() == devId.toInt();
244  }
245 
249 
251  XSNOEXPORT template <typename T> T* toType()
252  {
253  return dynamic_cast<T*>(this);
254  }
255 
256  virtual bool XSNOEXPORT initialize();
259 
260  virtual int batteryLevel() const;
261  virtual int updateRateForDataIdentifier(XsDataIdentifier dataType) const;
262  virtual int updateRateForProcessedDataIdentifier(XsDataIdentifier dataType) const;
263  virtual std::vector<int> supportedUpdateRates(XsDataIdentifier dataType = XDI_None) const;
264  virtual int maximumUpdateRate() const;
265  virtual bool hasDataEnabled(XsDataIdentifier dataType) const;
266  virtual bool hasProcessedDataEnabled(XsDataIdentifier dataType) const;
267  virtual XsString productCode() const;
268  virtual XsString shortProductCode() const;
269  virtual XsString portName() const;
270  virtual XsPortInfo portInfo() const;
271  virtual XsBaudRate baudRate() const;
272  virtual XsBaudRate serialBaudRate() const;
273  virtual XsVersion hardwareVersion() const;
274 #ifndef XSENS_NO_PORT_NUMBERS
275  virtual int XSNOLINUXEXPORT portNumber() const;
276 #endif
277  virtual bool startRecording();
278  virtual bool triggerStartRecording();
279  virtual bool stopRecording();
280  int64_t getStartRecordingPacketId() const;
281  int64_t getStopRecordingPacketId() const;
282 
283  virtual void setOptions(XsOption enable, XsOption disable);
284  virtual bool areOptionsEnabled(XsOption options) const;
285  XsOption getOptions() const;
286 
287  virtual bool sendCustomMessage(const XsMessage& messageSend, bool waitForResult, XsMessage& messageReceive, int timeout = 0);
288  virtual bool sendRawMessage(const XsMessage& message);
289 
290  XSNOEXPORT virtual bool sendCustomMessage(const XsMessage& messageSend, bool waitForResult, XsXbusMessageId messageId, XsMessage& messageReceive, int timeout = 0);
291  XSNOEXPORT virtual bool waitForCustomMessage(XsXbusMessageId messageId, XsMessage& messageReceive, int timeout = 0);
292  XSNOEXPORT virtual bool waitForCustomMessage(std::shared_ptr<ReplyObject> reply, XsMessage& messageReceive, int timeout);
293  virtual std::shared_ptr<ReplyObject> addReplyObject(XsXbusMessageId messageId, uint8_t data);
294 
295  XSNOEXPORT virtual void handleMessage(const XsMessage& msg);
296  XSNOEXPORT virtual void handleDataPacket(const XsDataPacket& packet);
297  XSNOEXPORT virtual void handleNonDataMessage(const XsMessage& msg);
298  XSNOEXPORT virtual void handleErrorMessage(const XsMessage& msg);
299  XSNOEXPORT virtual void handleWarningMessage(const XsMessage& msg);
300  XSNOEXPORT virtual void handleWakeupMessage(const XsMessage& msg);
301 
302  virtual bool setSerialBaudRate(XsBaudRate baudrate);
303 
304  virtual XsIntArray portConfiguration() const;
305  virtual bool setPortConfiguration(XsIntArray& config);
306 
307  virtual bool isMotionTracker() const;
308 
309  virtual XsOperationalMode operationalMode() const;
310  virtual bool setOperationalMode(XsOperationalMode mode);
311 
312  virtual int updateRate() const;
313  virtual bool setUpdateRate(int rate);
314 
315  virtual XsDeviceOptionFlag deviceOptionFlags() const;
316  virtual bool setDeviceOptionFlags(XsDeviceOptionFlag setFlags, XsDeviceOptionFlag clearFlags);
317 
321  virtual bool isInStringOutputMode() const;
324  virtual uint32_t canConfiguration() const;
325  virtual bool setCanConfiguration(uint32_t config);
326 
327  virtual bool usesLegacyDeviceMode() const;
328 
329  virtual uint16_t stringOutputType() const;
330  virtual uint16_t stringSamplePeriod() const;
331  virtual uint16_t stringSkipFactor() const;
332 
333  virtual bool setStringOutputMode(uint16_t type, uint16_t period, uint16_t skipFactor);
335 
336  virtual int dataLength() const;
337 
338  virtual XsSyncSettingArray syncSettings() const;
339  virtual bool setSyncSettings(const XsSyncSettingArray& settingList);
340  virtual bool isSyncMaster() const;
341  virtual bool isSyncSlave() const;
344 
345  virtual bool gotoMeasurement();
346  virtual bool gotoConfig();
347 
348  virtual bool restoreFactoryDefaults();
349 
350  virtual bool reset();
351  XSNOEXPORT virtual bool reset(bool skipDeviceIdCheck);
352 
353  virtual bool reopenPort(bool gotoConfig, bool skipDeviceIdCheck = false);
354 
355  virtual void writeDeviceSettingsToFile();
356 
357  virtual void flushInputBuffers();
358 
359  virtual XsSyncRole syncRole() const;
360  virtual bool loadLogFile();
361  virtual bool abortLoadLogFile();
362  virtual XsString logFileName() const;
363  virtual bool resetOrientation(XsResetMethod resetmethod);
364  virtual bool resetLogFileReadPosition();
365  XsFilePos logFileSize() const;
367  virtual bool updateCachedDeviceInformation();
368  virtual bool enableProtocol(XsProtocolType protocol);
369  virtual bool disableProtocol(XsProtocolType protocol);
370  virtual bool isProtocolEnabled(XsProtocolType protocol) const;
371 
372  virtual uint32_t deviceBufferSize();
373  virtual bool setDeviceBufferSize(uint32_t frames);
374 
375  virtual XsConnectivityState connectivityState() const;
376  virtual void waitForAllDevicesInitialized();
377 
378  // MtContainer
379  virtual std::vector<XsDevice*> children() const;
380  virtual int childCount() const;
381 
382  // Awinda Station
383  virtual bool enableRadio(int channel);
384  virtual bool disableRadio();
385  virtual int radioChannel() const;
386  virtual bool isRadioEnabled() const;
387  virtual bool makeOperational();
388  virtual bool isOperational() const;
389  virtual bool isInSyncStationMode();
390  virtual bool setSyncStationMode(bool enabled);
391 
392  virtual bool stealthMode() const;
393  virtual bool setStealthMode(bool enabled);
394 
395  virtual void discardRetransmissions(int64_t firstNewPacketId);
396 
397  //virtual int radioQualityIndication() const;
398  XSNOEXPORT virtual void handleMasterIndication(const XsMessage& message);
399  virtual bool abortFlushing();
400  virtual bool setDeviceAccepted(const XsDeviceId& deviceId);
401  virtual bool setDeviceRejected(const XsDeviceId& deviceId);
402  virtual bool setAccessControlMode(XsAccessControlMode mode, const XsDeviceIdArray& initialList);
403  virtual XsAccessControlMode accessControlMode() const;
405 
406  virtual XsResultValue setDeviceParameter(XsDeviceParameter const& parameter);
407  virtual XsResultValue deviceParameter(XsDeviceParameter& parameter) const;
408 
411  virtual XsUbloxGnssPlatform ubloxGnssPlatform() const;
413  virtual XsIntArray gnssReceiverSettings() const;
415 
416  // MTw
417  virtual bool acceptConnection();
418  virtual bool rejectConnection();
419  virtual int wirelessPriority() const;
420  virtual bool setWirelessPriority(int priority);
421  virtual XsRejectReason rejectReason() const;
422 
423  virtual bool requestBatteryLevel();
424  virtual XsTimeStamp batteryLevelTime();
425  virtual bool setTransportMode(bool transportModeEnabled);
426  virtual bool transportMode();
427  virtual int16_t lastKnownRssi() const;
428  XSNOEXPORT virtual void setPacketErrorRate(int per);
429  virtual int packetErrorRate() const;
430 
431  virtual bool isBlueToothEnabled() const;
432  virtual bool setBlueToothEnabled(bool enabled);
433  virtual bool isBusPowerEnabled() const;
434  virtual bool setBusPowerEnabled(bool enabled);
435  virtual bool powerDown();
436  virtual XsErrorMode errorMode() const;
437  virtual bool setErrorMode(XsErrorMode errormode);
438 
439  // MT device
440  virtual bool setHeadingOffset(double offset);
441  virtual double headingOffset() const;
442  virtual bool setLocationId(int id);
443  virtual int locationId() const;
444  virtual XsDevice* getDeviceFromLocationId(uint16_t locId);
445  virtual XsMatrix objectAlignment() const;
446  virtual bool setObjectAlignment(const XsMatrix& matrix);
447  virtual double gravityMagnitude() const;
448  virtual bool setGravityMagnitude(double mag);
449  virtual XsVector initialPositionLLA() const;
450  virtual bool setInitialPositionLLA(const XsVector& lla);
451  virtual XsTimeInfo utcTime() const;
452  virtual bool setUtcTime(const XsTimeInfo& time);
453  virtual bool reinitialize();
454 
455  virtual XsFilterProfile xdaFilterProfile() const;
456  virtual bool setXdaFilterProfile(int profileType);
457  virtual bool setXdaFilterProfile(XsString const& profileType);
458  virtual XsFilterProfile onboardFilterProfile() const;
459  virtual bool setOnboardFilterProfile(int profileType);
460  virtual bool setOnboardFilterProfile(XsString const& profileType);
461  virtual bool replaceFilterProfile(XsFilterProfile const& profileCurrent, XsFilterProfile const& profileNew);
464  virtual double accelerometerRange() const;
465  virtual double gyroscopeRange() const;
466  virtual bool setNoRotation(uint16_t duration);
467  virtual bool startRepresentativeMotion();
468  virtual bool representativeMotionState();
470  virtual bool storeIccResults();
471  virtual uint16_t rs485TransmissionDelay() const;
472  virtual bool setRs485TransmissionDelay(uint16_t delay);
473  virtual XsSelfTestResult runSelfTest();
474  virtual bool requestData();
475  virtual bool storeFilterState();
476 
477  virtual XsDataPacket getDataPacketByIndex(XsSize index) const;
478  XsSize getDataPacketCount() const;
481 
482  // MTix device
483  virtual bool isInitialBiasUpdateEnabled() const;
484  virtual bool setInitialBiasUpdateEnabled(bool enable);
485  virtual bool isFixedGravityEnabled() const;
486  virtual bool setFixedGravityEnabled(bool enable);
487 
488  virtual XsResultValue createConfigFile(const XsString& filename);
489  virtual XsResultValue applyConfigFile(const XsString& filename);
490 
491  // MtMk4 device
492  virtual bool setAlignmentRotationMatrix(XsAlignmentFrame frame, const XsMatrix& matrix);
494  virtual bool setAlignmentRotationQuaternion(XsAlignmentFrame frame, const XsQuaternion& quat);
496 
499  {
500  return &m_deviceMutex;
501  }
502 
503  virtual bool deviceIsDocked(XsDevice* dev) const;
504 
505  bool isLoadLogFileInProgress() const;
506  void waitForLoadLogFileDone() const;
507 
508  XSNOEXPORT virtual bool messageLooksSane(const XsMessage& msg) const;
509  XSNOEXPORT virtual void prepareForTermination();
510 
511  // MTi with RTK support
512  virtual bool setGnssLeverArm(const XsVector& arm);
513  virtual XsVector gnssLeverArm() const;
514  XSNOEXPORT virtual bool requestUtcTime();
515 
516  // Snapshot related
517  XSNOEXPORT virtual void handleUnavailableData(int64_t frameNumber);
518 
519  XSNOEXPORT virtual bool writeEmtsPage(uint8_t const* data, int pageNr, int bankNr);
520  XSNOEXPORT void setSkipEmtsReadOnInit(bool skip);
521 
523 
524  virtual uint32_t supportedStatusFlags() const;
526 
527 protected:
528  virtual XsDevice const* firstChild() const;
529  virtual void setRecordingStartFrame(uint16_t startFrame);
530  virtual void setRecordingStopFrame(uint16_t stopFrame);
531 
536  void useLogInterface(DataLogger* logger);
537 
538  friend struct XsDeviceEx;
540  void setFirmwareVersion(const XsVersion& version);
541  void extractFirmwareVersion(XsMessage const& message);
542 
543  friend class MtContainer;
544  virtual void setDeviceState(XsDeviceState state);
545  virtual void updateDeviceState(XsDeviceState state);
546 
547  void removeIfNoRefs();
548 
549  virtual bool scheduleOrientationReset(XsResetMethod method);
550 
551  explicit XsDevice(XsDeviceId const& id);
552  explicit XsDevice(Communicator* comm);
553  explicit XsDevice(XsDevice* master, const XsDeviceId& childDeviceId);
554 
556  inline const XsDeviceConfiguration& deviceConfig() const
557  {
558  return m_config;
559  }
560 
561  void setDeviceId(const XsDeviceId& deviceId);
562 
564 
565  virtual void writeMessageToLogFile(const XsMessage& message);
566 
567  virtual void writeFilterStateToFile();
568 
569  virtual void processLivePacket(XsDataPacket& pack);
570  virtual void processBufferedPacket(XsDataPacket& pack);
571 
572  virtual bool readDeviceConfiguration();
573 
576  {
577  assert(m_latestLivePacket);
578  assert(m_deviceMutex.haveGuardedLock());
579  return *m_latestLivePacket;
580  }
583  {
584  assert(m_latestBufferedPacket);
585  assert(m_deviceMutex.haveGuardedLock());
586  return *m_latestBufferedPacket;
587  }
589  inline XsDataPacket const& latestLivePacketConst() const
590  {
591  assert(m_latestLivePacket);
592  assert(m_deviceMutex.haveGuardedLock());
593  return *m_latestLivePacket;
594  }
597  {
598  assert(m_latestBufferedPacket);
599  assert(m_deviceMutex.haveGuardedLock());
600  return *m_latestBufferedPacket;
601  }
602  virtual int64_t latestLivePacketId() const;
603  virtual int64_t latestBufferedPacketId() const;
604 
605  virtual void resetPacketStamping();
606 
609 
611  void setInitialized(bool initialized)
612  {
613  m_isInitialized = initialized;
614  }
616  void setTerminationPrepared(bool prepared)
617  NOEXCEPT { m_terminationPrepared = prepared; }
618 
619  virtual bool shouldWriteMessageToLogFile(const XsMessage& msg) const;
620  virtual bool shouldWriteMessageToLogFile(const XsDevice* dev, const XsMessage& message) const;
621 
623 
624 public:
625  XSNOEXPORT virtual void onMessageSent(const XsMessage& message);
626  XSNOEXPORT virtual void onMessageReceived(const XsMessage& message);
627  XSNOEXPORT virtual void onMessageDetected2(XsProtocolType type, const XsByteArray& rawMessage);
628 
629  XSNOEXPORT virtual void onSessionRestarted();
630  XSNOEXPORT virtual void onConnectionLost();
631  XSNOEXPORT virtual void onEofReached();
632  XSNOEXPORT virtual void onWirelessConnectionLost();
633  XSNOEXPORT virtual int64_t deviceRecordingBufferItemCount(int64_t& lastCompletePacketId) const;
634 
635 protected:
636  bool doTransaction(const XsMessage& snd) const;
637  bool doTransaction(const XsMessage& snd, XsMessage& rcv) const;
638  bool doTransaction(const XsMessage& snd, XsMessage& rcv, uint32_t timeout) const;
639  bool doTransaction(const XsMessage& snd, uint32_t timeout) const;
640 
642  bool justWriteSetting() const
643  {
644  return m_justWriteSetting;
645  }
646 
647  virtual void clearProcessors();
648  virtual void clearDataCache();
649  virtual void insertIntoDataCache(int64_t pid, XsDataPacket* pack);
650  virtual void reinitializeProcessors();
651  virtual bool expectingRetransmissionForPacket(int64_t packetId) const;
652 
653  virtual bool resetRemovesPort() const;
654 
655  virtual bool isSoftwareFilteringEnabled() const;
656  virtual bool isSoftwareCalibrationEnabled() const;
657 
658 
659  virtual void setStartRecordingPacketId(int64_t startFrame);
660  virtual void setStopRecordingPacketId(int64_t stopFrame);
661  virtual void endRecordingStream();
662  virtual void clearCacheToRecordingStart();
663 
668 
671 
674 
677 
678  void setCommunicator(Communicator* comm);
679 
681  bool skipEmtsReadOnInit() const
682  {
683  return m_skipEmtsReadOnInit;
684  }
685  static bool checkDataEnabled(XsDataIdentifier dataType, XsOutputConfigurationArray const& configurations);
686  virtual bool shouldDataMsgBeRecorded(const XsMessage& msg) const;
687  virtual bool shouldDoRecordedCallback(XsDataPacket const& packet) const;
688  virtual bool interpolateMissingData(XsDataPacket const& pack, XsDataPacket const& prev, std::function<void (XsDataPacket*)> packetHandler);
689 
692 
695 
698 
701 
704 
707 
710 
713 
716 
719 
722 
725 
728 
730  volatile std::atomic_int m_refCounter;
731 
734 
737 
740 
743 
746 
751 
754 
757 
762 
763  //These members are protected instead of private to give direct access to tests
764 
767 
770 
773 
774  virtual void clearExternalPacketCaches();
776  void retainPacket(XsDataPacket const& pack);
777  static bool packetContainsRetransmission(XsDataPacket const& pack);
778 
780  std::deque<XsDataPacket*> m_linearPacketCache;
781 
784 
789 
791 };
792 
793 #ifndef XDA_PRIVATE_BUILD
794  #include "xsdevice_public.h"
795 #else
796  #include "xsdeviceex.h"
797 #endif
798 
799 #endif
XsDevice::setPortConfiguration
virtual bool setPortConfiguration(XsIntArray &config)
Change the port configuration of a device.
Definition: xsdevice_def.cpp:930
XsDevice::findConfiguration
XsOutputConfiguration findConfiguration(XsDataIdentifier dataType) const
XsDevice::powerDown
virtual bool powerDown()
Tell the device to power down completely.
Definition: xsdevice_def.cpp:2454
XsDevice::getStartRecordingPacketId
int64_t getStartRecordingPacketId() const
Return the ID of the first packet that should be recorded.
Definition: xsdevice_def.cpp:4374
XsDevice::supportedUpdateRates
virtual std::vector< int > supportedUpdateRates(XsDataIdentifier dataType=XDI_None) const
Ask the device for its supported update rates for the given dataType.
Definition: xsdevice_def.cpp:2403
XsDevice::logFileInterface
virtual DataLogger XSNOEXPORT * logFileInterface(std::unique_ptr< xsens::Lock > &myLock) const
XsDevice::expectingRetransmissionForPacket
virtual bool expectingRetransmissionForPacket(int64_t packetId) const
XsDevice::isInitialized
bool isInitialized() const
Returns true when the device is initialized.
Definition: xsdevice_def.cpp:3721
XsDevice::setCanOutputConfiguration
virtual bool setCanOutputConfiguration(XsCanOutputConfigurationArray &config)
Set the CAN output configuration for this device.
Definition: xsdevice_def.cpp:1188
XsDevice::handleUnavailableData
virtual XSNOEXPORT void handleUnavailableData(int64_t frameNumber)
xsalignmentframe.h
XsDevice::operator==
bool operator==(const XsDevice &dev) const
Compare device ID with that of dev.
Definition: xsdevice_def.h:231
XsDevice::lastAvailableLiveData
XsDataPacket lastAvailableLiveData() const
Return the last available live data.
Definition: xsdevice_def.cpp:4218
XsDevice::utcTime
virtual XsTimeInfo utcTime() const
Gets the 'UTC Time' setting of the device.
Definition: xsdevice_def.cpp:2819
XsMatrix
A class that represents a matrix of real numbers.
Definition: xsmatrix.h:107
XsDevice::gnssLeverArm
virtual XsVector gnssLeverArm() const
Definition: xsdevice_def.cpp:2953
XsDevice::findDeviceConst
XsDevice const * findDeviceConst(XsDeviceId const &deviceid) const
Find the child device with deviceid.
Definition: xsdevice_def.cpp:512
XsDevice::setRs485TransmissionDelay
virtual bool setRs485TransmissionDelay(uint16_t delay)
Set the transmission delay used for RS485 transmissions.
Definition: xsdevice_def.cpp:2851
XsDevice::runSelfTest
virtual XsSelfTestResult runSelfTest()
Run the self test for the device.
Definition: xsdevice_def.cpp:2864
XsDevice::enableProtocol
virtual bool enableProtocol(XsProtocolType protocol)
Enable an additional communication protocol when reading messages.
Definition: xsdevice_def.cpp:3280
XsDevice::deviceId
XsDeviceId const & deviceId() const
Return the device ID of the device.
Definition: xsdevice_def.cpp:742
XsDevice::isStandaloneDevice
bool isStandaloneDevice() const
Returns true if this is a standalone device (not a child of another device and not a container device...
Definition: xsdevice_def.cpp:1102
XsDevice::setTerminationPrepared
void setTerminationPrepared(bool prepared) NOEXCEPT
Set the "termination prepared" state to prepared.
Definition: xsdevice_def.h:616
XsVector
A class that represents a vector of real numbers.
Definition: xsvector.h:113
XsDevice::useLogInterface
void useLogInterface(DataLogger *logger)
Uses log interface for a given data logger.
XsDevice::abortLoadLogFile
virtual bool abortLoadLogFile()
Aborts loading a logfile.
Definition: xsdevice_def.cpp:3062
XsDevice::handleMessage
virtual XSNOEXPORT void handleMessage(const XsMessage &msg)
XsDevice::startRepresentativeMotion
virtual bool startRepresentativeMotion()
Let the user indicate that he is starting the representative motion for the In-Run Compass Calibratio...
Definition: xsdevice_def.cpp:2753
XsDevice::setErrorMode
virtual bool setErrorMode(XsErrorMode errormode)
Sets the error mode of the device.
Definition: xsdevice_def.cpp:2473
XsDevice::storeFilterState
virtual bool storeFilterState()
Store orientation filter state in the device.
Definition: xsdevice_def.cpp:2888
XsDevice::onMessageDetected2
virtual XSNOEXPORT void onMessageDetected2(XsProtocolType type, const XsByteArray &rawMessage)
XsDevice::toType
XSNOEXPORT T * toType()
Definition: xsdevice_def.h:251
XsDevice::availableXdaFilterProfiles
virtual XsFilterProfileArray availableXdaFilterProfiles() const
Return the list of filter profiles available on the host PC.
Definition: xsdevice_def.cpp:2705
XsDevice::ubloxGnssPlatform
virtual XsUbloxGnssPlatform ubloxGnssPlatform() const
Returns the device GNSS platform for u-blox GNSS receivers.
Definition: xsdevice_def.cpp:4501
XsDevice::m_dataCache
DataPacketCache m_dataCache
A data cache.
Definition: xsdevice_def.h:691
XsDevice::supportsSyncSettings
static bool supportsSyncSettings(XsDeviceId const &deviceId)
Determines whether the device specified by deviceId supports sync settings.
Definition: xsdevice_def.cpp:4057
XsDevice::isReadingFromFile
virtual bool isReadingFromFile() const
Returns true if the device is reading from a file.
Definition: xsdevice_def.cpp:1783
XsByteArray
A list of uint8_t values.
XsDevice::stringOutputType
virtual uint16_t stringOutputType() const
Returns the string output type.
Definition: xsdevice_def.cpp:3354
XsDevice::packetErrorRate
virtual int packetErrorRate() const
Returns the packet error rate for the for the device.
Definition: xsdevice_def.cpp:3653
XsCallbackPlainC
Structure that contains callback functions for the Xsens Device API.
Definition: xscallbackplainc.h:99
XsDevice::stringSamplePeriod
virtual uint16_t stringSamplePeriod() const
Returns the sample period for string output.
Definition: xsdevice_def.cpp:3337
XsDevice::operationalMode
virtual XsOperationalMode operationalMode() const
Returns the operational mode.
Definition: xsdevice_def.cpp:3362
XsDevice::getDataPacketByIndex
virtual XsDataPacket getDataPacketByIndex(XsSize index) const
Return the cached data packet with index.
Definition: xsdevice_def.cpp:4193
XsDevice::m_toaDumpFile
DebugFileType * m_toaDumpFile
To a dump file.
Definition: xsdevice_def.h:788
XsDevice::firstChild
virtual XsDevice const * firstChild() const
XsDevice::setInitialPositionLLA
virtual bool setInitialPositionLLA(const XsVector &lla)
Sets the 'Latitude Longitude Altitude' setting of the device to the given vector.
Definition: xsdevice_def.cpp:2809
XsDevice::~XsDevice
virtual XSNOEXPORT ~XsDevice()
Destroy the device.
Definition: xsdevice_def.cpp:274
XsDevice::handleErrorMessage
virtual XSNOEXPORT void handleErrorMessage(const XsMessage &msg)
XsDevice::setSerialBaudRate
virtual bool setSerialBaudRate(XsBaudRate baudrate)
Change the serial baudrate to baudrate.
Definition: xsdevice_def.cpp:875
PacketProcessor
class XSNOEXPORT PacketProcessor
Definition: xsdevice_def.h:90
XsDevice::retainPacket
void retainPacket(XsDataPacket const &pack)
XsIccRepMotionResult
Contains the result of the representative motion processed by ICC.
Definition: xsiccrepmotionresult.h:72
XsDevice::deviceState
virtual XsDeviceState deviceState() const
Return the state of this device.
Definition: xsdevice_def.cpp:1064
XsDevice::master
virtual XsDevice * master() const
Return the master device of this device.
Definition: xsdevice_def.cpp:332
XsDevice::removeRef
virtual void removeRef()
Decrease this XsDevices reference counter with 1.
Definition: xsdevice_def.cpp:3831
XsDevice::onEofReached
virtual XSNOEXPORT void onEofReached()
XsDevice::xdaFilterProfile
virtual XsFilterProfile xdaFilterProfile() const
Gets the filter profile in use for computing orientations on the host PC.
Definition: xsdevice_def.cpp:2603
XsDevice::m_logFileMutex
xsens::Mutex m_logFileMutex
The mutex for guarding access to the log file.
Definition: xsdevice_def.h:670
XsFilterProfileArray
A list of XsFilterProfile values.
XsDevice::XsDevice
XsDevice(XsDeviceId const &id)
Construct an empty device with device id id.
Definition: xsdevice_def.cpp:165
XDI_None
@ XDI_None
Empty datatype.
Definition: xsdataidentifier.h:86
XsDevice::m_skipEmtsReadOnInit
bool m_skipEmtsReadOnInit
Skip EMTS read on init boolean variable.
Definition: xsdevice_def.h:750
XsDevice::isInitialBiasUpdateEnabled
virtual bool isInitialBiasUpdateEnabled() const
Returns if the device does gyroscope bias estimation when switching to measurement mode.
Definition: xsdevice_def.cpp:2900
XsDevice::readMetaDataFromLogFile
virtual XsByteArray readMetaDataFromLogFile()
Returns internal meta-data about the recording that some devices store in the mtb logfile.
Definition: xsdevice_def.cpp:4652
XsDeviceConfiguration
Structure containing a full device configuration as returned by the ReqConfig message.
Definition: xsdeviceconfiguration.h:143
XsDevice::reinitializeProcessors
virtual void reinitializeProcessors()
XsDevice::latestBufferedPacket
XsDataPacket & latestBufferedPacket()
Definition: xsdevice_def.h:582
XsDevice::m_outputConfiguration
XsOutputConfigurationArray m_outputConfiguration
A devices output configuration.
Definition: xsdevice_def.h:715
XsDevice::initialize
virtual bool XSNOEXPORT initialize()
XsDevice::XSENS_DISABLE_COPY
XSENS_DISABLE_COPY(XsDevice)
XsDevice::isInSyncStationMode
virtual bool isInSyncStationMode()
Definition: xsdevice_def.cpp:3792
XsDevice::packetContainsRetransmission
static bool packetContainsRetransmission(XsDataPacket const &pack)
XsDevice::lastKnownRssi
virtual int16_t lastKnownRssi() const
Returns the last known RSSI value of the device.
Definition: xsdevice_def.cpp:3624
XsDevice::m_terminationPrepared
bool m_terminationPrepared
Termination prepared boolean variable.
Definition: xsdevice_def.h:739
XsDevice::gnssPlatform
XSNOEXPORT XSDEPRECATED XsGnssPlatform gnssPlatform() const
XsDevice::locationId
virtual int locationId() const
Get the location ID of the device.
Definition: xsdevice_def.cpp:2517
XsDevice::setXdaFilterProfile
virtual bool setXdaFilterProfile(int profileType)
Sets the filter profile to use for computing orientations on the host PC.
Definition: xsdevice_def.cpp:2619
XsDevice::sendCustomMessage
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.
Definition: xsdevice_def.cpp:1302
XsRejectReason
XsRejectReason
Identifiers for why a device's connection was rejected.
Definition: xsrejectreason.h:74
XsDeviceEx
An abstract internal struct of a device.
Definition: xsdevice_public.h:78
XsDevice::deviceAtBusIdConst
const XsDevice * deviceAtBusIdConst(int busid) const
Return the device with bus ID busid.
Definition: xsdevice_def.cpp:778
XsDevice::serialBaudRate
virtual XsBaudRate serialBaudRate() const
The baud rate configured for cabled connection.
Definition: xsdevice_def.cpp:837
XsDevice::setCommunicator
void setCommunicator(Communicator *comm)
XsDevice::deviceIsDocked
virtual bool deviceIsDocked(XsDevice *dev) const
Check if the device is docked.
Definition: xsdevice_def.cpp:3673
packetstamper.h
XsDevice::m_stoppedRecordingPacketId
int64_t m_stoppedRecordingPacketId
The ID of the last packet that was recorded. Remains valid after Flushing has ended,...
Definition: xsdevice_def.h:772
XsIntArray
A list of XsInt values.
XsDevice::setSyncSettings
virtual bool setSyncSettings(const XsSyncSettingArray &settingList)
Set the synchronization settings of the device.
Definition: xsdevice_def.cpp:3158
XsDevice::isBusPowerEnabled
virtual bool isBusPowerEnabled() const
Returns if the Xbus is powering its child devices or not.
Definition: xsdevice_def.cpp:2432
XsDeviceIdArray
A list of XsDeviceId values.
XsDevice::isContainerDevice
virtual bool isContainerDevice() const
Returns true if this device can have child devices.
Definition: xsdevice_def.cpp:1094
XsDevice::setStringOutputMode
virtual bool setStringOutputMode(uint16_t type, uint16_t period, uint16_t skipFactor)
Sets the string output mode for this device.
Definition: xsdevice_def.cpp:1220
XsDevice::isMasterDevice
bool isMasterDevice() const
Returns true if this is the master device (not a child of another device)
Definition: xsdevice_def.cpp:1086
XsDevice::m_connectivity
XsConnectivityState m_connectivity
A current device connectivity state.
Definition: xsdevice_def.h:706
XsDevice::hardwareVersion
virtual XsVersion hardwareVersion() const
Return the hardware version of the device.
Definition: xsdevice_def.cpp:3467
XsDevice::handleWarningMessage
virtual XSNOEXPORT void handleWarningMessage(const XsMessage &msg)
XsDevice::availableOnboardFilterProfiles
virtual XsFilterProfileArray availableOnboardFilterProfiles() const
Return the list of filter profiles available on the device.
Definition: xsdevice_def.cpp:2696
XsDevice::disableProtocol
virtual bool disableProtocol(XsProtocolType protocol)
Disable a communication protocol previously added by XsDevice::enableProtocol.
Definition: xsdevice_def.cpp:3304
XsDataPacket
Contains an interpreted data message. The class provides easy access to the contained data through it...
Definition: xsdatapacket.h:301
XsDevice::sendRawMessage
virtual bool sendRawMessage(const XsMessage &message)
Send a message directly to the communicator.
Definition: xsdevice_def.cpp:1311
XsDevice::checkDataEnabled
static bool checkDataEnabled(XsDataIdentifier dataType, XsOutputConfigurationArray const &configurations)
XsDevice::endRecordingStream
virtual void endRecordingStream()
xsgnssplatform.h
XsDevice::updateRate
virtual int updateRate() const
Get the legacy update rate of the device.
Definition: xsdevice_def.cpp:544
XsDevice::m_latestBufferedPacket
XsDataPacket * m_latestBufferedPacket
A copy of the latest ready recording packet. This is the last packet that was popped off the front of...
Definition: xsdevice_def.h:676
XsDevice::onboardFilterProfile
virtual XsFilterProfile onboardFilterProfile() const
Gets the filter profile in use by the device for computing orientations.
Definition: xsdevice_def.cpp:2646
XsDevice::m_justWriteSetting
bool m_justWriteSetting
Just write setting boolean variable.
Definition: xsdevice_def.h:745
XsSelfTestResult
Contains the results of a self-test performed by an Xsens device.
Definition: xsselftestresult.h:105
XsDevice::subDeviceCount
virtual int subDeviceCount() const
Returns the number of sub-devices of this device.
Definition: xsdevice_def.cpp:4644
XsDevice::writeDeviceSettingsToFile
virtual void writeDeviceSettingsToFile()
Write the emts/wms/xms of the device and all its children to the open logfile.
Definition: xsdevice_def.cpp:2030
XsDevice::setFirmwareVersion
void setFirmwareVersion(const XsVersion &version)
XsDevice::children
virtual std::vector< XsDevice * > children() const
Return a managed array containing the child-devices this device has. For standalone devices this is a...
Definition: xsdevice_def.cpp:4093
XsDevice::createLogFile
XsResultValue createLogFile(const XsString &filename)
Create a log file for logging.
Definition: xsdevice_def.cpp:2038
XsDevice::initialPositionLLA
virtual XsVector initialPositionLLA() const
Gets the 'Latitude Longitude Altitude' setting of the device.
Definition: xsdevice_def.cpp:2793
XsDevice::requestUtcTime
virtual XSNOEXPORT bool requestUtcTime()
XsDevice::setOutputConfigurationInternal
virtual XsResultValue setOutputConfigurationInternal(XsOutputConfigurationArray &config)
XsDevice::portInfo
virtual XsPortInfo portInfo() const
The port information of the connection.
Definition: xsdevice_def.cpp:3696
XsStringArray
A list of XsString values.
XsDevice::shouldDoRecordedCallback
virtual bool shouldDoRecordedCallback(XsDataPacket const &packet) const
XsDevice::m_options
XsOption m_options
The options.
Definition: xsdevice_def.h:756
XsDevice::stealthMode
virtual bool stealthMode() const
Return the state of the stealth mode setting.
Definition: xsdevice_def.cpp:4034
XsQuaternion
A class that implements a quaternion.
Definition: xsquaternion.h:102
XsDevice::supportedStatusFlags
virtual uint32_t supportedStatusFlags() const
Returns a bitmask with all the status flags supported by this device.
Definition: xsdevice_def.cpp:4610
XsDevice::reinitialize
virtual bool reinitialize()
Reinitialize the XsDevice.
Definition: xsdevice_def.cpp:2594
XsDevice::productCode
virtual XsString productCode() const
Return the product code of the device.
Definition: xsdevice_def.cpp:3451
xsoption.h
XsDevice::transportMode
virtual bool transportMode()
Returns the current state of the transport mode feature.
Definition: xsdevice_def.cpp:3005
XsDevice::isRadioEnabled
virtual bool isRadioEnabled() const
Returns if the radio is enabled.
Definition: xsdevice_def.cpp:3497
XsDevice::outputConfiguration
virtual XsOutputConfigurationArray outputConfiguration() const
Returns the currently configured output of the device.
Definition: xsdevice_def.cpp:3380
XsDevice::latestLivePacket
XsDataPacket & latestLivePacket()
Definition: xsdevice_def.h:575
XsDevice::childCount
virtual int childCount() const
Return the number of child-devices this device has. For standalone devices this is always 0.
Definition: xsdevice_def.cpp:4085
xsdeviceoptionflag.h
XsDevice::onMessageReceived
virtual XSNOEXPORT void onMessageReceived(const XsMessage &message)
CallbackManagerXda::removeCallbackHandler
void removeCallbackHandler(XsCallbackPlainC *cb, bool chain=true)
Remove a handler from the list.
Definition: callbackmanagerxda.cpp:207
XsDevice::getDataPacketCount
XsSize getDataPacketCount() const
Return the current size of the retained data packet cache.
Definition: xsdevice_def.cpp:4206
XsDevice::setRecordingStartFrame
virtual void setRecordingStartFrame(uint16_t startFrame)
XsDevice::updateRateForDataIdentifier
virtual int updateRateForDataIdentifier(XsDataIdentifier dataType) const
Returns the currently configured update rate for the supplied dataType.
Definition: xsdevice_def.cpp:601
datapacketcache.h
XsDevice::flushInputBuffers
virtual void flushInputBuffers()
Clear the inbound data buffers of the device.
Definition: xsdevice_def.cpp:1807
XsDevice::clearProcessors
virtual void clearProcessors()
NOEXCEPT
#define NOEXCEPT
Definition: xsdevice_def.h:128
XsDevice::m_unavailableDataBoundary
int64_t m_unavailableDataBoundary
A packet ID of the last sample we know to be unavailable.
Definition: xsdevice_def.h:694
XsDevice::isCompatibleSyncSetting
static bool isCompatibleSyncSetting(XsDeviceId const &deviceId, XsSyncSetting const &setting1, XsSyncSetting const &setting2)
Determines whether setting1 is compatible with setting2 for deviceId deviceId.
Definition: xsdevice_def.cpp:4068
XsDevice::processBufferedPacket
virtual void processBufferedPacket(XsDataPacket &pack)
XsDevice::setDeviceId
void setDeviceId(const XsDeviceId &deviceId)
xsresetmethod.h
XsDevice::shortProductCode
virtual XsString shortProductCode() const
Return the shortened product code of the device suitable for display.
Definition: xsdevice_def.cpp:3459
xsaccesscontrolmode.h
XsDevice::m_communicator
Communicator * m_communicator
A communicator.
Definition: xsdevice_def.h:721
XsDevice::communicator
Communicator XSNOEXPORT * communicator() const
XsDevice::setFixedGravityEnabled
virtual bool setFixedGravityEnabled(bool enable)
Sets whether the fixed gravity value should be used or if it should be computed from the initialPosit...
Definition: xsdevice_def.cpp:2934
DebugFileType
#define DebugFileType
Definition: xsdevice_def.h:127
XsDevice::supportedStringOutputTypes
virtual XsStringOutputTypeArray supportedStringOutputTypes() const
Ask the device for its supported string output types.
Definition: xsdevice_def.cpp:1259
XsDevice::stopRecording
virtual bool stopRecording()
Stop recording incoming data.
Definition: xsdevice_def.cpp:2201
XsDevice::setNoRotation
virtual bool setNoRotation(uint16_t duration)
Set the no rotation period to duration.
Definition: xsdevice_def.cpp:2743
XsOption
XsOption
Xda options, used to control the kind of data processing done by XDA.
Definition: xsoption.h:76
XsDevice::handleWakeupMessage
virtual XSNOEXPORT void handleWakeupMessage(const XsMessage &msg)
XsDevice::setSyncStationMode
virtual bool setSyncStationMode(bool enabled)
Set the Sync Station mode of the Awinda Station device.
Definition: xsdevice_def.cpp:3801
XsResultValue
XsResultValue
Xsens result values.
Definition: xsresultvalue.h:82
XsDevice::latestBufferedPacketId
virtual int64_t latestBufferedPacketId() const
XsDevice::waitForLoadLogFileDone
void waitForLoadLogFileDone() const
Wait for the file operation started by loadLogFile to complete.
Definition: xsdevice_def.cpp:4364
XsDevice::busId
virtual int busId() const
The bus ID for this device.
Definition: xsdevice_def.cpp:860
XsDevice::interpolateMissingData
virtual bool interpolateMissingData(XsDataPacket const &pack, XsDataPacket const &prev, std::function< void(XsDataPacket *)> packetHandler)
XsDevice::onSessionRestarted
virtual XSNOEXPORT void onSessionRestarted()
XsDevice::operator<
bool operator<(const XsDevice &dev) const
Compare device ID with that of dev.
Definition: xsdevice_def.h:226
XsOutputConfigurationArray
A list of XsOutputConfiguration values.
XsDevice::updateLastAvailableLiveDataCache
void updateLastAvailableLiveDataCache(XsDataPacket const &pack)
XsDevice::resetRemovesPort
virtual bool resetRemovesPort() const
XsOperationalMode
XsOperationalMode
Definition: xsoperationalmode.h:68
XSNOEXPORT
#define XSNOEXPORT
Definition: xscommon_config.h:65
DataLogger
An abstract class for data logging.
Definition: datalogger.h:73
XsDevice::rs485TransmissionDelay
virtual uint16_t rs485TransmissionDelay() const
Returns the transmission delay used for RS485 transmissions.
Definition: xsdevice_def.cpp:2841
XsSyncSetting
A structure for storing all xsens sync settings.
Definition: xssyncsetting.h:95
XsDataIdentifier
XsDataIdentifier
Defines the data identifiers.
Definition: xsdataidentifier.h:84
XsDevice::getDeviceFromLocationId
virtual XsDevice * getDeviceFromLocationId(uint16_t locId)
Get the device given locId.
Definition: xsdevice_def.cpp:2527
XsDevice::isMotionTracker
virtual bool isMotionTracker() const
Returns true if this is a motion tracker.
Definition: xsdevice_def.cpp:813
XsGnssPlatform
enum XsUbloxGnssPlatform XsGnssPlatform
Definition: xsgnssplatform.h:71
XsFilterProfile
Contains information about an available filter profile.
Definition: xsfilterprofile.h:92
XsDevice::loadLogFile
virtual bool loadLogFile()
Load a complete logfile.
Definition: xsdevice_def.cpp:3045
Communicator
A base struct for a communication interface.
Definition: communicator.h:95
XsDevice::isOperational
virtual bool isOperational() const
Definition: xsdevice_def.cpp:3786
XsDevice::m_deviceId
XsDeviceId m_deviceId
An ID of the device.
Definition: xsdevice_def.h:697
XsDevice::findDevice
virtual XsDevice * findDevice(XsDeviceId const &deviceid) const
Find the child device with deviceid.
Definition: xsdevice_def.cpp:500
XsBaudRate
enum XsBaudRate XsBaudRate
Communication speed.
Definition: xsbaud.h:81
XsDevice::addRef
virtual void addRef()
Increase reference count of XsDevice pointer XsDevice pointers stay alive while reference counter is ...
Definition: xsdevice_def.cpp:3810
XsDevice::prepareForTermination
virtual XSNOEXPORT void prepareForTermination()
XsDevice::deviceConfigurationConst
virtual XsDeviceConfiguration const &XSNOEXPORT deviceConfigurationConst() const
uint32_t
unsigned int uint32_t
Definition: pstdint.h:485
XsDevice::m_state
XsDeviceState m_state
A current device state.
Definition: xsdevice_def.h:703
XsDevice::setDeviceBufferSize
virtual bool setDeviceBufferSize(uint32_t frames)
Request the device to set it's internal buffer to the specified size.
Definition: xsdevice_def.cpp:4328
XsDevice::accessControlMode
virtual XsAccessControlMode accessControlMode() const
Request the access control mode of the master device.
Definition: xsdevice_def.cpp:3760
XsDevice::replaceFilterProfile
virtual bool replaceFilterProfile(XsFilterProfile const &profileCurrent, XsFilterProfile const &profileNew)
Replaces profileCurrent by profileNew in the device.
Definition: xsdevice_def.cpp:2685
XSNOLINUXEXPORT
#define XSNOLINUXEXPORT
Definition: xscontrollerconfig.h:253
XsDevice::setOutputConfiguration
bool setOutputConfiguration(XsOutputConfigurationArray &config)
Set the output configuration for this device.
Definition: xsdevice_def.cpp:1138
XsDeviceParameter
Class to set and retrieve parameters from a XsDevice object.
Definition: xsdeviceparameter.h:81
XsPortInfo
Contains a descriptor for opening a communication port to an Xsens device.
Definition: xsportinfo.h:128
XsDevice::m_latestLivePacket
XsDataPacket * m_latestLivePacket
A copy of the latest ready live packet. This is the packet with the highest 64-bit sample counter so ...
Definition: xsdevice_def.h:673
XsDevice::firmwareVersion
virtual XsVersion firmwareVersion() const
Return the firmware version.
Definition: xsdevice_def.cpp:675
XsDevice::setRecordingStopFrame
virtual void setRecordingStopFrame(uint16_t stopFrame)
XsDevice::syncSettings
virtual XsSyncSettingArray syncSettings() const
Get all the current synchronization settings of the device.
Definition: xsdevice_def.cpp:3144
XsDevice::connectivityState
virtual XsConnectivityState connectivityState() const
Returns the connectivity state of the device.
Definition: xsdevice_def.cpp:3663
XsDevice::baudRate
virtual XsBaudRate baudRate() const
Get the baud rate (communication speed) of the serial port on which the given deviceId is connected.
Definition: xsdevice_def.cpp:849
XsDevice::setHeadingOffset
virtual bool setHeadingOffset(double offset)
Set the 'heading offset' setting of the device.
Definition: xsdevice_def.cpp:2486
xsdevice_public.h
XsDevice::restoreFactoryDefaults
virtual bool restoreFactoryDefaults()
Restore the device to its factory default settings.
Definition: xsdevice_def.cpp:1953
XsDevice::representativeMotionState
virtual bool representativeMotionState()
Retrieves the active representative motion state for the In-Run Compass Calibration.
Definition: xsdevice_def.cpp:2762
XsDevice::m_stopRecordingPacketId
int64_t m_stopRecordingPacketId
The ID of the last packet that should be / was recorded. Only valid in Recording/Flushing states.
Definition: xsdevice_def.h:769
XsDevice::m_packetStamper
PacketStamper m_packetStamper
A packet stamper.
Definition: xsdevice_def.h:753
XsDevice::messageLooksSane
virtual XSNOEXPORT bool messageLooksSane(const XsMessage &msg) const
XsDevice::headingOffset
virtual double headingOffset() const
Return the 'heading offset' setting of the device.
Definition: xsdevice_def.cpp:2495
XsDevice::updateDeviceState
virtual void updateDeviceState(XsDeviceState state)
XsDevice::m_lastResult
LastResultManager m_lastResult
The last result of an operation.
Definition: xsdevice_def.h:700
XsDevice::logFileReadPosition
XsFilePos logFileReadPosition() const
Get the current read position of the open log file.
Definition: xsdevice_def.cpp:3236
XsDevice::m_config
XsDeviceConfiguration m_config
A device configuration.
Definition: xsdevice_def.h:712
XsDevice::m_firmwareVersion
XsVersion m_firmwareVersion
A firmware version.
Definition: xsdevice_def.h:718
XsDevice::waitForAllDevicesInitialized
virtual void waitForAllDevicesInitialized()
Wait until are known devices are initialized.
Definition: xsdevice_def.cpp:4339
XsDevice::isSoftwareFilteringEnabled
virtual bool isSoftwareFilteringEnabled() const
XsDevice::m_lastDataOkStamp
XsTimeStamp m_lastDataOkStamp
A time stamp for an OK last data.
Definition: xsdevice_def.h:709
XsDevice::discardRetransmissions
virtual void discardRetransmissions(int64_t firstNewPacketId)
Tell XDA and the device that any data from before firstNewPacketId may be lossy.
Definition: xsdevice_def.cpp:4598
XsDevice::checkDataCache
virtual void XSNOEXPORT checkDataCache()
XsDevice::deviceAtBusId
virtual XsDevice * deviceAtBusId(int busid)
Return the device with bus ID busid.
Definition: xsdevice_def.cpp:767
xsoperationalmode.h
XsDevice::storeIccResults
virtual bool storeIccResults()
Store the onboard ICC results for use by the device.
Definition: xsdevice_def.cpp:2780
XsDevice::updateRateForProcessedDataIdentifier
virtual int updateRateForProcessedDataIdentifier(XsDataIdentifier dataType) const
Returns the currently configured update rate for the supplied dataType.
Definition: xsdevice_def.cpp:622
XsDevice::waitForCustomMessage
virtual XSNOEXPORT bool waitForCustomMessage(XsXbusMessageId messageId, XsMessage &messageReceive, int timeout=0)
xsens::Mutex
A base mutex class.
Definition: xsens_mutex.h:132
XsDevice::refCounter
XsSize refCounter() const
The current reference counter.
Definition: xsdevice_def.cpp:3819
XsDevice::setUpdateRate
virtual bool setUpdateRate(int rate)
Set the legacy update rate of the device.
Definition: xsdevice_def.cpp:554
XsDevice::canOutputConfiguration
virtual XsCanOutputConfigurationArray canOutputConfiguration() const
Returns the currently configured CAN output of the device.
Definition: xsdevice_def.cpp:3388
XsDevice::deviceParameter
virtual XsResultValue deviceParameter(XsDeviceParameter &parameter) const
Retrieves the requested parameter's current value.
Definition: xsdevice_def.cpp:4468
XsDevice::setPacketErrorRate
virtual XSNOEXPORT void setPacketErrorRate(int per)
XsDevice::maximumUpdateRate
virtual int maximumUpdateRate() const
Get the maximum update rate for the device.
Definition: xsdevice_def.cpp:3102
XsDevice::skipEmtsReadOnInit
bool skipEmtsReadOnInit() const
Definition: xsdevice_def.h:681
XsDevice::removeIfNoRefs
void removeIfNoRefs()
XsDevice::m_gotoConfigOnClose
bool m_gotoConfigOnClose
Go to confing on close boolean variable.
Definition: xsdevice_def.h:742
XsSyncRole
XsSyncRole
Synchronization roles.
Definition: xssyncrole.h:73
XsDevice::setOnboardFilterProfile
virtual bool setOnboardFilterProfile(int profileType)
Sets the filter profile to use for computing orientations on the device.
Definition: xsdevice_def.cpp:2659
XsResetMethod
XsResetMethod
Orientation reset type.
Definition: xsresetmethod.h:74
XsDevice::isSyncMaster
virtual bool isSyncMaster() const
returns whether this device is in a master role regarding the device synchronization
Definition: xsdevice_def.cpp:750
XsSize
size_t XsSize
XsSize must be unsigned number!
Definition: xstypedefs.h:74
XsDevice::setGotoConfigOnClose
void setGotoConfigOnClose(bool gotoConfigOnClose)
On closePort the device will go to config by default, with this function it is possible to prevent th...
Definition: xsdevice_def.cpp:519
XsDevice::takeFirstDataPacketInQueue
XsDataPacket takeFirstDataPacketInQueue()
Return the first packet in the packet queue or an empty packet if the queue is empty.
Definition: xsdevice_def.cpp:4230
XsMatrix3x3
A class that represents a fixed size (3x3) matrix.
Definition: xsmatrix3x3.h:95
XsDevice::resetPacketStamping
virtual void resetPacketStamping()
XsVersion
A class to store version information.
Definition: xsversion.h:95
XsDevice::m_logFileInterface
DataLogger * m_logFileInterface
A data logger for a file interface.
Definition: xsdevice_def.h:724
XsDevice::deviceBufferSize
virtual uint32_t deviceBufferSize()
Request the size of the interal buffer.
Definition: xsdevice_def.cpp:4319
XsAccessControlMode
XsAccessControlMode
Device access control modes (XsDevice::setAccessControlMode())
Definition: xsaccesscontrolmode.h:74
XsDevice::enableRadio
virtual bool enableRadio(int channel)
Set the radio channel to use for wireless communication.
Definition: xsdevice_def.cpp:3478
XsUbloxGnssPlatform
XsUbloxGnssPlatform
Used to select u-blox GNSS chip platform.
Definition: xsubloxgnssplatform.h:72
XsDevice::gyroscopeRange
virtual double gyroscopeRange() const
Returns the maximum official value of the gyroscopes in the device.
Definition: xsdevice_def.cpp:2727
XsXbusMessageId
XsXbusMessageId
Xsens Xbus Message Identifiers.
Definition: xsxbusmessageid.h:73
XsDevice::stringSkipFactor
virtual uint16_t stringSkipFactor() const
Returns the skipfactor for string output.
Definition: xsdevice_def.cpp:3345
xsversion.h
XsDevice::setDeviceState
virtual void setDeviceState(XsDeviceState state)
XsDevice::gnssReceiverSettings
virtual XsIntArray gnssReceiverSettings() const
Gets some GNSS receiver settings.
Definition: xsdevice_def.cpp:4520
XsDevice::startRecording
virtual bool startRecording()
Start recording incoming data.
Definition: xsdevice_def.cpp:2171
XsDevice::setWirelessPriority
virtual bool setWirelessPriority(int priority)
Sets the wireless priority of the device.
Definition: xsdevice_def.cpp:3581
xserrormode.h
XsDevice::m_writeToFile
bool m_writeToFile
Write to file boolean variable.
Definition: xsdevice_def.h:733
XsDevice::insertIntoDataCache
virtual void insertIntoDataCache(int64_t pid, XsDataPacket *pack)
XsDevice::portName
virtual XsString portName() const
The port name of the connection.
Definition: xsdevice_def.cpp:3683
XsDevice::justWriteSetting
bool justWriteSetting() const
Definition: xsdevice_def.h:642
XsDevice::reopenPort
virtual bool reopenPort(bool gotoConfig, bool skipDeviceIdCheck=false)
Reopens a port Uses rescan method to redetect a device. Also if USB descriptor has changed.
Definition: xsdevice_def.cpp:2017
XsMessage
Structure for storing a single message.
Definition: xsmessage.h:202
XsDevice::setAlignmentRotationMatrix
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 ...
Definition: xsdevice_def.cpp:2120
XsDevice::isRecording
virtual bool isRecording() const
Returns true if the device is currently in a recording state.
Definition: xsdevice_def.cpp:1762
XsDevice::reset
virtual bool reset()
Reset the device.
Definition: xsdevice_def.cpp:1971
XsDevice::isProtocolEnabled
virtual bool isProtocolEnabled(XsProtocolType protocol) const
Definition: xsdevice_def.cpp:3326
XsDevice::stopRepresentativeMotion
virtual XsIccRepMotionResult stopRepresentativeMotion()
Let the user indicate that he stopped the representative motion.
Definition: xsdevice_def.cpp:2772
XsDevice::processLivePacket
virtual void processLivePacket(XsDataPacket &pack)
XsDevice::setStealthMode
virtual bool setStealthMode(bool enabled)
Enable or disable stealth mode.
Definition: xsdevice_def.cpp:4025
XsDevice::alignmentRotationMatrix
virtual XsMatrix alignmentRotationMatrix(XsAlignmentFrame frame) const
Retrieve the alignment rotation matrix to rotate S to the chosen frame S'.
Definition: xsdevice_def.cpp:2132
xsoutputconfigurationarray.h
XsDevice::setObjectAlignment
virtual bool setObjectAlignment(const XsMatrix &matrix)
Sets the object alignment of the device to the given matrix.
Definition: xsdevice_def.cpp:2554
XsDevice::m_refCounter
volatile std::atomic_int m_refCounter
A reference counter.
Definition: xsdevice_def.h:730
XsDevice::lastResult
XsResultValue lastResult() const
Get the result value of the last operation.
Definition: xsdevice_def.cpp:794
XsDeviceId
Contains an Xsens device ID and provides operations for determining the type of device.
Definition: xsdeviceid.h:192
XsDevice::m_deviceMutex
xsens::GuardedMutex m_deviceMutex
The mutex for guarding state changes of the device.
Definition: xsdevice_def.h:667
XsDevice::applyConfigFile
virtual XsResultValue applyConfigFile(const XsString &filename)
Loads a config file(.xsa) and configures the device accordingly.
Definition: xsdevice_def.cpp:2142
XsDevice::radioChannel
virtual int radioChannel() const
Returns the radio channel used for wireless communication.
Definition: xsdevice_def.cpp:3506
XsDevice::m_lastAvailableLiveDataCache
XsDataPacket * m_lastAvailableLiveDataCache
A last available live data cache.
Definition: xsdevice_def.h:783
XsDevice::setStartRecordingPacketId
virtual void setStartRecordingPacketId(int64_t startFrame)
XsDevice::shouldDataMsgBeRecorded
virtual bool shouldDataMsgBeRecorded(const XsMessage &msg) const
XsDevice::rejectReason
virtual XsRejectReason rejectReason() const
Returns the reason why a device's connection was rejected.
Definition: xsdevice_def.cpp:3614
XsDevice::setOperationalMode
virtual bool setOperationalMode(XsOperationalMode mode)
Set the device in the given operational mode.
Definition: xsdevice_def.cpp:3371
XsCalibratedData
Container for combined calibrated measurement data from accelerometers, gyroscopes and magnetometers.
Definition: xscalibrateddata.h:87
XsDevice::readEmtsAndDeviceConfiguration
virtual XSNOEXPORT bool readEmtsAndDeviceConfiguration()
XsDevice::closeLogFile
virtual bool closeLogFile()
Close the log file.
Definition: xsdevice_def.cpp:2150
XsDevice::syncSettingsTimeResolutionInMicroSeconds
static unsigned int syncSettingsTimeResolutionInMicroSeconds(XsDeviceId const &deviceId)
Definition: xsdevice_def.cpp:4077
XsDevice::onConnectionLost
virtual XSNOEXPORT void onConnectionLost()
XsDevice::setUbloxGnssPlatform
virtual bool setUbloxGnssPlatform(XsUbloxGnssPlatform ubloxGnssPlatform)
Set the device GNSS platform for u-blox GNSS receivers.
Definition: xsdevice_def.cpp:4511
XsDevice::updateCachedDeviceInformation
virtual bool updateCachedDeviceInformation()
Updates the cached device information for all devices connected to this port.
Definition: xsdevice_def.cpp:3254
XsDevice::setAlignmentRotationQuaternion
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...
Definition: xsdevice_def.cpp:2094
XsDevice::updateConnectivityState
void updateConnectivityState(XsConnectivityState newState)
XsDevice::onMessageSent
virtual XSNOEXPORT void onMessageSent(const XsMessage &message)
XsDevice::isSoftwareCalibrationEnabled
virtual bool isSoftwareCalibrationEnabled() const
XsDevice::readDeviceConfiguration
virtual bool readDeviceConfiguration()
XsDevice::latestLivePacketConst
XsDataPacket const & latestLivePacketConst() const
Definition: xsdevice_def.h:589
XsDevice::handleMasterIndication
virtual XSNOEXPORT void handleMasterIndication(const XsMessage &message)
XsDevice::isSyncSlave
virtual bool isSyncSlave() const
returns whether this device is in a slave role regarding the device synchronization
Definition: xsdevice_def.cpp:758
XsDevice::setDeviceParameter
virtual XsResultValue setDeviceParameter(XsDeviceParameter const &parameter)
Sets the given parameter for the device.
Definition: xsdevice_def.cpp:4456
XsDevice::setGnssLeverArm
virtual bool setGnssLeverArm(const XsVector &arm)
Sets the GNSS Lever Arm vector.
Definition: xsdevice_def.cpp:2946
XsDevice::logFileName
virtual XsString logFileName() const
Get the name of the log file the device is reading from.
Definition: xsdevice_def.cpp:3078
XsDevice::accelerometerRange
virtual double accelerometerRange() const
Returns the maximum official value of the accelerometers in the device.
Definition: xsdevice_def.cpp:2716
XsScrData
Container for raw sensor measurement data.
Definition: xsscrdata.h:79
XsDevice::resetLogFileReadPosition
virtual bool resetLogFileReadPosition()
Set the read position of the open log file to the start of the file.
Definition: xsdevice_def.cpp:3198
xsrejectreason.h
XsDevice::requestBatteryLevel
virtual bool requestBatteryLevel()
Request the battery level from the device.
Definition: xsdevice_def.cpp:2973
XsDevice::gotoConfig
virtual bool gotoConfig()
Put the device in config mode.
Definition: xsdevice_def.cpp:1014
XsConnectivityState
XsConnectivityState
XsDevice connectivity state identifiers.
Definition: xsconnectivitystate.h:78
xssyncrole.h
XsDevice::clearDataCache
virtual void clearDataCache()
PacketStamper
Supplies functionality for timestamping data packets.
Definition: packetstamper.h:73
XsDevice::areOptionsEnabled
virtual bool areOptionsEnabled(XsOption options) const
Returns true when all the specified processing options are enabled.
Definition: xsdevice_def.cpp:3434
XsDevice::getOptions
XsOption getOptions() const
Return the currently enabled options.
Definition: xsdevice_def.cpp:3443
XsDevice::deviceOptionFlags
virtual XsDeviceOptionFlag deviceOptionFlags() const
Returns the device option flags.
Definition: xsdevice_def.cpp:562
XsDevice::abortFlushing
virtual bool abortFlushing()
Abort the wireless flushing operation and finalize the recording.
Definition: xsdevice_def.cpp:3537
XsDevice::usesLegacyDeviceMode
virtual bool usesLegacyDeviceMode() const
Returns whether the device uses legacy device mode.
Definition: xsdevice_def.cpp:3022
XsDevice::setStopRecordingPacketId
virtual void setStopRecordingPacketId(int64_t stopFrame)
XsDevice::setGnssReceiverSettings
virtual bool setGnssReceiverSettings(const XsIntArray &gnssReceiverSettings)
Sets some GNSS receiver settings.
Definition: xsdevice_def.cpp:4529
XsDevice::isInStringOutputMode
virtual bool isInStringOutputMode() const
Returns if the device is outputting data in string mode.
Definition: xsdevice_def.cpp:3014
XsDevice::canConfiguration
virtual uint32_t canConfiguration() const
Returns the currently configured CAN configuration of the device.
Definition: xsdevice_def.cpp:3396
XsDevice::acceptConnection
virtual bool acceptConnection()
Accept connections from the device on the parent/master device.
Definition: xsdevice_def.cpp:3548
XsDevice::portConfiguration
virtual XsIntArray portConfiguration() const
Get the current port configuration of a device.
Definition: xsdevice_def.cpp:910
XsDevice::deviceConfiguration
XsDeviceConfiguration deviceConfiguration() const
Returns the device configuration.
Definition: xsdevice_def.cpp:1945
XsDevice::gotoMeasurement
virtual bool gotoMeasurement()
Put this device in measurement mode.
Definition: xsdevice_def.cpp:960
XsDevice::disableRadio
virtual bool disableRadio()
Disables the radio for this station, resetting all children to disconnected state.
Definition: xsdevice_def.cpp:3488
XsDevice::rejectConnection
virtual bool rejectConnection()
Reject connections from the device on the parent/master device.
Definition: xsdevice_def.cpp:3562
XsErrorMode
XsErrorMode
Error modes for use in XsDevice::setErrorMode.
Definition: xserrormode.h:74
XSDEPRECATED
#define XSDEPRECATED
Definition: xstypedefs.h:153
XsDevice::setAccessControlMode
virtual bool setAccessControlMode(XsAccessControlMode mode, const XsDeviceIdArray &initialList)
Set the access control mode of the master device.
Definition: xsdevice_def.cpp:3751
XsProtocolType
XsProtocolType
Protocol types (XsDevice::enableProtocol())
Definition: xsprotocoltype.h:72
XsDevice::setTransportMode
virtual bool setTransportMode(bool transportModeEnabled)
Enable or disable the transport mode for the device.
Definition: xsdevice_def.cpp:2995
XsSyncSettingArray
A list of XsSyncSetting values.
XsDevice::shouldWriteMessageToLogFile
virtual bool shouldWriteMessageToLogFile(const XsMessage &msg) const
XsDevice::resetOrientation
virtual bool resetOrientation(XsResetMethod resetmethod)
Perform an orientation reset on the device using the given resetMethod.
Definition: xsdevice_def.cpp:3187
XsDevice::setOptions
virtual void setOptions(XsOption enable, XsOption disable)
Enable and disable processing options.
Definition: xsdevice_def.cpp:3411
XsDevice::setGravityMagnitude
virtual bool setGravityMagnitude(double mag)
Sets the 'Gravity Magnitude' of the device to the given value mag.
Definition: xsdevice_def.cpp:2579
XsDevice::m_startRecordingPacketId
int64_t m_startRecordingPacketId
The ID of the first packet that should be / was recorded.
Definition: xsdevice_def.h:766
XsDevice::setUtcTime
virtual bool setUtcTime(const XsTimeInfo &time)
Sets the 'UTC Time' setting of the device to the given time.
Definition: xsdevice_def.cpp:2831
XsDevice::createConfigFile
virtual XsResultValue createConfigFile(const XsString &filename)
Stores the current device configuration in a config file(.xsa)
Definition: xsdevice_def.cpp:2082
callbackmanagerxda.h
XsDevice::deviceRecordingBufferItemCount
virtual XSNOEXPORT int64_t deviceRecordingBufferItemCount(int64_t &lastCompletePacketId) const
XsDevice::currentAccessControlList
virtual XsDeviceIdArray currentAccessControlList() const
Request the access control list of the master device.
Definition: xsdevice_def.cpp:3769
XsDevice::subDevice
virtual XsDevice * subDevice(int subDeviceId) const
Returns the sub-device at index index.
Definition: xsdevice_def.cpp:4632
XsDevice::writeMessageToLogFile
virtual void writeMessageToLogFile(const XsMessage &message)
XsDevice::handleDataPacket
virtual XSNOEXPORT void handleDataPacket(const XsDataPacket &packet)
XsDevice::initializeSoftwareCalibration
virtual bool XSNOEXPORT initializeSoftwareCalibration()
XsDevice::isMeasuring
virtual bool isMeasuring() const
Returns true if the device is currently in a measuring state.
Definition: xsdevice_def.cpp:1741
XsDevice::setDeviceAccepted
virtual bool setDeviceAccepted(const XsDeviceId &deviceId)
Accepts a device.
Definition: xsdevice_def.cpp:3730
XsDevice::recordingQueueLength
int recordingQueueLength() const
Get the number of packets currently waiting in the slow data cache for the device based.
Definition: xsdevice_def.cpp:3118
XsDevice::deviceConfig
const XsDeviceConfiguration & deviceConfig() const
Definition: xsdevice_def.h:556
XsDevice::mutex
xsens::GuardedMutex * mutex() const
Definition: xsdevice_def.h:498
XsDevice::isBlueToothEnabled
virtual bool isBlueToothEnabled() const
Returns true if the device has its BlueTooth radio enabled.
Definition: xsdevice_def.cpp:2413
MtContainer
class XSNOEXPORT MtContainer
Definition: xsdevice_def.h:88
XsDevice::requestData
virtual bool requestData()
Request data when configured in legacy mode with infinite skip factor.
Definition: xsdevice_def.cpp:2875
XsDevice::alignmentRotationQuaternion
virtual XsQuaternion alignmentRotationQuaternion(XsAlignmentFrame frame) const
Retrieve the alignment rotation quaternion.
Definition: xsdevice_def.cpp:2106
LastResultManager
This class manages a result code with optional additional text.
Definition: lastresultmanager.h:75
XsStringOutputTypeArray
A list of XsStringOutputType values.
XsDevice::m_emtsBlob
XsMessage m_emtsBlob
An EMTS blob from device.
Definition: xsdevice_def.h:761
XsDevice::batteryLevel
virtual int batteryLevel() const
Get the batterylevel of this device The battery level is a value between 0 and 100 that indicates the...
Definition: xsdevice_def.cpp:535
XsDevice::wirelessPriority
virtual int wirelessPriority() const
Returns the wireless priority of the device.
Definition: xsdevice_def.cpp:3571
XsDevice::gravityMagnitude
virtual double gravityMagnitude() const
Returns the 'Gravity Magnitude' of the device.
Definition: xsdevice_def.cpp:2566
XsDevice::deviceConfigurationRef
XsDeviceConfiguration &XSNOEXPORT deviceConfigurationRef()
XsDevice::setInitialized
void setInitialized(bool initialized)
Set the initialized state to initialized.
Definition: xsdevice_def.h:611
XsDevice::onWirelessConnectionLost
virtual XSNOEXPORT void onWirelessConnectionLost()
lastresultmanager.h
XsCanOutputConfigurationArray
A list of XsCanOutputConfiguration values.
XsDeviceState
XsDeviceState
XsDevice state identifiers.
Definition: xsdevicestate.h:77
XsDevice::objectAlignment
virtual XsMatrix objectAlignment() const
Returns the object alignment matrix of the device.
Definition: xsdevice_def.cpp:2541
XsDevice::MtContainer
friend class MtContainer
Definition: xsdevice_def.h:543
XsDevice::setInitialBiasUpdateEnabled
virtual bool setInitialBiasUpdateEnabled(bool enable)
Set if the device does gyroscope bias estimation when switching to measurement mode.
Definition: xsdevice_def.cpp:2912
XsDevice::clearCacheToRecordingStart
virtual void clearCacheToRecordingStart()
XsDevice::addReplyObject
virtual std::shared_ptr< ReplyObject > addReplyObject(XsXbusMessageId messageId, uint8_t data)
communicator.h
XsDevice::writeEmtsPage
virtual XSNOEXPORT bool writeEmtsPage(uint8_t const *data, int pageNr, int bankNr)
XsDevice::makeOperational
virtual bool makeOperational()
Sets the Awinda station to operational state.
Definition: xsdevice_def.cpp:3778
XsDevice::doTransaction
bool doTransaction(const XsMessage &snd) const
xsens::GuardedMutex
A two-layer mutex, typically used for status+data protection.
Definition: xsens_mutex.h:1259
XsOutputConfiguration
Single data type output configuration.
Definition: xsoutputconfiguration.h:96
XsDevice::scheduleOrientationReset
virtual bool scheduleOrientationReset(XsResetMethod method)
xsdeviceconfiguration.h
CallbackManagerXda
Class that delegates callbacks to registered XsCallbackHandlerItems.
Definition: callbackmanagerxda.h:78
XsDevice::setDeviceRejected
virtual bool setDeviceRejected(const XsDeviceId &deviceId)
Rejects a device.
Definition: xsdevice_def.cpp:3739
XsDevice::setGnssPlatform
XSNOEXPORT virtual XSDEPRECATED bool setGnssPlatform(XsGnssPlatform gnssPlatform)
XsDevice::logFileSize
XsFilePos logFileSize() const
Get the size of the log file the device is reading from.
Definition: xsdevice_def.cpp:3219
XsDevice::setBlueToothEnabled
virtual bool setBlueToothEnabled(bool enabled)
Enable or disable the BlueTooth radio of the device.
Definition: xsdevice_def.cpp:2422
XsFilePos
int64_t XsFilePos
The type that is used for positioning inside a file.
Definition: xsfilepos.h:102
XsString
A 0-terminated managed string of characters.
XsDevice::clearExternalPacketCaches
virtual void clearExternalPacketCaches()
XsDevice::m_linearPacketCache
std::deque< XsDataPacket * > m_linearPacketCache
A linear data packet cache.
Definition: xsdevice_def.h:780
XsDevice::writeFilterStateToFile
virtual void writeFilterStateToFile()
XsDevice
Definition: xsdevice_def.h:164
XsDevice::supportedSyncSettings
virtual XsSyncSettingArray supportedSyncSettings() const
Get all supported synchronization settings available on the device.
Definition: xsdevice_def.cpp:3175
XsDevice::deinitializeSoftwareCalibration
virtual void XSNOEXPORT deinitializeSoftwareCalibration()
XsDevice::extractFirmwareVersion
void extractFirmwareVersion(XsMessage const &message)
XsDevice::latestBufferedPacketConst
XsDataPacket const & latestBufferedPacketConst() const
Definition: xsdevice_def.h:596
XsDevice::setCanConfiguration
virtual bool setCanConfiguration(uint32_t config)
Set the CAN configuration for this device.
Definition: xsdevice_def.cpp:1198
XsDevice::hasDataEnabled
virtual bool hasDataEnabled(XsDataIdentifier dataType) const
Returns if the currently configured output contains dataType.
Definition: xsdevice_def.cpp:632
XsDevice::dataLength
virtual int dataLength() const
Returns the length of the data in the legacy MTData packets that the device will send in measurement ...
Definition: xsdevice_def.cpp:825
XsDevice::syncRole
virtual XsSyncRole syncRole() const
Returns the synchronization role of the device.
Definition: xsdevice_def.cpp:1821
XsDevice::m_isInitialized
bool m_isInitialized
Is intialized boolean variable.
Definition: xsdevice_def.h:736
XsDevice::cacheSize
int cacheSize() const
Get the number of items currently in the slow data cache for the device.
Definition: xsdevice_def.cpp:3131
XsDevice::processedOutputConfiguration
virtual XsOutputConfigurationArray processedOutputConfiguration() const
Return the full output configuration including post processing outputs.
Definition: xsdevice_def.cpp:1209
XsDevice::setSkipEmtsReadOnInit
XSNOEXPORT void setSkipEmtsReadOnInit(bool skip)
XsDevice::restartFilter
virtual void restartFilter()
Restart the software filter used by this device.
Definition: xsdevice_def.cpp:785
XsDevice::errorMode
virtual XsErrorMode errorMode() const
Returns the error mode of the device.
Definition: xsdevice_def.cpp:2463
DataPacketCache
A cache of data packets.
Definition: datapacketcache.h:75
XsDevice::handleNonDataMessage
virtual XSNOEXPORT void handleNonDataMessage(const XsMessage &msg)
XsDevice::setDeviceOptionFlags
virtual bool setDeviceOptionFlags(XsDeviceOptionFlag setFlags, XsDeviceOptionFlag clearFlags)
Set the device option flags.
Definition: xsdevice_def.cpp:1112
XsDevice::defaultChildConnectivityState
virtual XsConnectivityState defaultChildConnectivityState() const
XsDevice::isLoadLogFileInProgress
bool isLoadLogFileInProgress() const
Returns true if the file operation started by loadLogFile is still in progress.
Definition: xsdevice_def.cpp:4349
XsTimeStamp
This class contains method to set, retrieve and compare timestamps.
Definition: xstimestamp.h:115
XsDevice::setBusPowerEnabled
virtual bool setBusPowerEnabled(bool enabled)
Tell the Xbus to provide power to its child devices or not.
Definition: xsdevice_def.cpp:2444
CallbackManagerXda::clearCallbackHandlers
void clearCallbackHandlers(bool chain=true)
Clear the callback list.
Definition: callbackmanagerxda.cpp:129
XsDevice::m_master
XsDevice * m_master
A device object.
Definition: xsdevice_def.h:727
XsDevice::updatePortInfo
virtual XsResultValue updatePortInfo(XsPortInfo const &newInfo)
Update the connection information, this is only useful for devices communicating over a dynamic link ...
Definition: xsdevice_def.cpp:4620
XsDevice::isFixedGravityEnabled
virtual bool isFixedGravityEnabled() const
Returns if the fixed gravity value should be used or if it should be computed from the initialPositio...
Definition: xsdevice_def.cpp:2923
XsDeviceOptionFlag
XsDeviceOptionFlag
Used to enable or disable some device options.
Definition: xsdeviceoptionflag.h:75
XsDevice::getStopRecordingPacketId
int64_t getStopRecordingPacketId() const
Return the ID of the last packet that should be recorded.
Definition: xsdevice_def.cpp:4383
XsDevice::triggerStartRecording
virtual bool triggerStartRecording()
Start recording incoming data through generating a virtual input trigger.
Definition: xsdevice_def.cpp:2191
XsDevice::lastResultText
XsString lastResultText() const
Get the accompanying error text for the value returned by lastResult() It may provide situation-speci...
Definition: xsdevice_def.cpp:804
XsAlignmentFrame
XsAlignmentFrame
Alignment frame.
Definition: xsalignmentframe.h:74
CallbackManagerXda::addCallbackHandler
void addCallbackHandler(XsCallbackPlainC *cb, bool chain=true)
Add a handler to the list.
Definition: callbackmanagerxda.cpp:158
XsDevice::latestLivePacketId
virtual int64_t latestLivePacketId() const
XsDevice::batteryLevelTime
virtual XsTimeStamp batteryLevelTime()
Requests the time the battery level was last updated.
Definition: xsdevice_def.cpp:2981
XsTimeInfo
A structure for storing Time values.
Definition: xstimeinfo.h:87
XsDevice::setLocationId
virtual bool setLocationId(int id)
Set the location ID of the device.
Definition: xsdevice_def.cpp:2506
XsDevice::hasProcessedDataEnabled
virtual bool hasProcessedDataEnabled(XsDataIdentifier dataType) const
Returns if the currently configured output contains dataType after processing on the host.
Definition: xsdevice_def.cpp:665


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