mtibasedevice.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 XSMTIBASEDEVICE_H
66 #define XSMTIBASEDEVICE_H
67 
68 #include "mtdevice.h"
69 #include <xstypes/xssyncline.h>
70 
74 class MtiBaseDevice : public MtDeviceEx
75 {
76 public:
82  {
83  return new MtiBaseDevice(comm);
84  }
85 
86  explicit MtiBaseDevice(Communicator* comm);
87  explicit MtiBaseDevice(XsDevice* master);
88  virtual ~MtiBaseDevice();
89 
91 
93 
94  int getBaseFrequency(XsDataIdentifier dataType = XDI_None) const override;
95  std::vector<int> supportedUpdateRates(XsDataIdentifier dataType = XDI_None) const override;
96 
97  bool setAlignmentRotationMatrix(XsAlignmentFrame frame, const XsMatrix& matrix) override;
99  bool setAlignmentRotationQuaternion(XsAlignmentFrame frame, const XsQuaternion& quat) override;
101 
102  bool setHeadingOffset(double offset);
103 
104  XsSyncSettingArray syncSettings() const override;
105  bool setSyncSettings(const XsSyncSettingArray& s) override;
106 
107  bool setNoRotation(uint16_t duration);
108 
109  bool setInitialPositionLLA(const XsVector& lla);
110  XsTimeInfo utcTime() const;
111  bool setUtcTime(const XsTimeInfo& time);
112 
113  XsErrorMode errorMode() const override;
114  bool setErrorMode(XsErrorMode errorMode) override;
115  uint16_t rs485TransmissionDelay() const;
116  bool setRs485TransmissionDelay(uint16_t delay);
117 
118  bool startRepresentativeMotion() override;
119  bool representativeMotionState() override;
121  bool storeIccResults() override;
122 
125  {
127  bool m_divedable;
128  };
129 
130 protected:
131  virtual int calculateUpdateRate(XsDataIdentifier dataType) const;
132 
133  virtual int calculateUpdateRateImp(XsDataIdentifier dataType, const XsOutputConfigurationArray& configurations) const;
134 
135  virtual XsSyncLine syncSettingsLine(const uint8_t* buff, XsSize offset) const;
136  virtual uint8_t syncLine(const XsSyncSetting& setting) const;
137  virtual XsSyncSettingArray syncSettingsFromBuffer(const uint8_t* buffer) const;
138 
139  bool resetRemovesPort() const override;
140 
146  {
147  (void) dataType;
148  return BaseFrequencyResult();
149  };
150 
151  virtual bool hasIccSupport() const;
152  virtual bool deviceUsesOnBoardFiltering();
153 
154  void fetchAvailableHardwareScenarios() override;
155 };
156 
157 #ifndef XDA_PRIVATE_BUILD
158 
162 {
164  explicit MtiBaseDeviceEx(Communicator* comm) : MtiBaseDevice(comm) { };
165 
168 };
169 #else
170 #include "mtibasedeviceex.h"
171 #endif
172 
173 #endif
MtiBaseDevice::setOutputConfigurationInternal
XsResultValue setOutputConfigurationInternal(XsOutputConfigurationArray &o) override
Set the output configuration for this device.
Definition: mtibasedevice.cpp:137
XsMatrix
A class that represents a matrix of real numbers.
Definition: xsmatrix.h:107
XsVector
A class that represents a vector of real numbers.
Definition: xsvector.h:113
xssyncline.h
MtiBaseDevice::alignmentRotationMatrix
XsMatrix alignmentRotationMatrix(XsAlignmentFrame frame) const override
Retrieve the alignment rotation matrix to rotate S to the chosen frame S'.
Definition: mtibasedevice.cpp:181
MtiBaseDevice::setSyncSettings
bool setSyncSettings(const XsSyncSettingArray &s) override
Set the synchronization settings of the device.
Definition: mtibasedevice.cpp:190
MtiBaseDevice::BaseFrequencyResult::m_frequency
int m_frequency
A frequency value.
Definition: mtibasedevice.h:126
XsIccRepMotionResult
Contains the result of the representative motion processed by ICC.
Definition: xsiccrepmotionresult.h:72
MtiBaseDevice::constructAsMaster
static XsDevice * constructAsMaster(Communicator *comm)
Construct a device as a master.
Definition: mtibasedevice.h:81
XsDevice::master
virtual XsDevice * master() const
Return the master device of this device.
Definition: xsdevice_def.cpp:332
MtiBaseDevice::fetchAvailableHardwareScenarios
void fetchAvailableHardwareScenarios() override
Fetches available hardware scenarios.
Definition: mtibasedevice.cpp:631
XDI_None
@ XDI_None
Empty datatype.
Definition: xsdataidentifier.h:86
MtiBaseDevice::syncSettingsLine
virtual XsSyncLine syncSettingsLine(const uint8_t *buff, XsSize offset) const
Returns the sync settings line for a generic mti device.
Definition: mtibasedevice.cpp:504
MtiBaseDevice::startRepresentativeMotion
bool startRepresentativeMotion() override
Starts the representative motion.
Definition: mtibasedevice.cpp:543
MtiBaseDevice
The generic class for MTi devices.
Definition: mtibasedevice.h:74
MtiBaseDevice::stopRepresentativeMotion
XsIccRepMotionResult stopRepresentativeMotion() override
Stops the representative motion.
Definition: mtibasedevice.cpp:585
MtiBaseDevice::setNoRotation
bool setNoRotation(uint16_t duration)
Set the no rotation period to duration.
Definition: mtibasedevice.cpp:376
MtiBaseDevice::outputConfiguration
XsOutputConfigurationArray outputConfiguration() const
Returns the currently configured output of the device.
Definition: mtibasedevice.cpp:111
MtiBaseDevice::setAlignmentRotationQuaternion
bool setAlignmentRotationQuaternion(XsAlignmentFrame frame, const XsQuaternion &quat) override
Set an arbitrary alignment rotation matrix Use to rotate either L to the chosen frame L' or S to the ...
Definition: mtibasedevice.cpp:147
MtiBaseDevice::setRs485TransmissionDelay
bool setRs485TransmissionDelay(uint16_t delay)
Set the transmission delay used for RS485 transmissions.
Definition: mtibasedevice.cpp:479
MtiBaseDevice::setInitialPositionLLA
bool setInitialPositionLLA(const XsVector &lla)
Sets the 'Latitude Longitude Altitude' setting of the device to the given vector.
Definition: mtibasedevice.cpp:383
MtiBaseDevice::hasIccSupport
virtual bool hasIccSupport() const
Definition: mtibasedevice.cpp:626
XsQuaternion
A class that implements a quaternion.
Definition: xsquaternion.h:102
MtiBaseDeviceEx::MtiBaseDeviceEx
MtiBaseDeviceEx(Communicator *comm)
Constructs a device.
Definition: mtibasedevice.h:164
MtiBaseDevice::calculateUpdateRate
virtual int calculateUpdateRate(XsDataIdentifier dataType) const
Definition: mtibasedevice.cpp:335
MtDeviceEx
An abstract struct of MT device.
Definition: mtdevice.h:189
XsResultValue
XsResultValue
Xsens result values.
Definition: xsresultvalue.h:82
MtiBaseDevice::resetRemovesPort
bool resetRemovesPort() const override
Definition: mtibasedevice.cpp:486
XsOutputConfigurationArray
A list of XsOutputConfiguration values.
MtiBaseDevice::setUtcTime
bool setUtcTime(const XsTimeInfo &time)
Sets the 'UTC Time' setting of the device to the given time.
Definition: mtibasedevice.cpp:428
XsSyncSetting
A structure for storing all xsens sync settings.
Definition: xssyncsetting.h:95
XsDataIdentifier
XsDataIdentifier
Defines the data identifiers.
Definition: xsdataidentifier.h:84
MtiBaseDevice::setHeadingOffset
bool setHeadingOffset(double offset)
Set the 'heading offset' setting of the device.
Definition: mtibasedevice.cpp:104
MtiBaseDevice::syncSettings
XsSyncSettingArray syncSettings() const override
Get all the current synchronization settings of the device.
Definition: mtibasedevice.cpp:249
Communicator
A base struct for a communication interface.
Definition: communicator.h:95
MtiBaseDeviceEx::MtiBaseDeviceEx
MtiBaseDeviceEx(XsDevice *master)
Constructs a device.
Definition: mtibasedevice.h:167
MtiBaseDevice::deviceUsesOnBoardFiltering
virtual bool deviceUsesOnBoardFiltering()
Definition: mtibasedevice.cpp:535
MtiBaseDevice::setErrorMode
bool setErrorMode(XsErrorMode errorMode) override
Sets the error mode of the device.
Definition: mtibasedevice.cpp:453
MtiBaseDevice::calculateUpdateRateImp
virtual int calculateUpdateRateImp(XsDataIdentifier dataType, const XsOutputConfigurationArray &configurations) const
Definition: mtibasedevice.cpp:299
MtiBaseDevice::syncSettingsFromBuffer
virtual XsSyncSettingArray syncSettingsFromBuffer(const uint8_t *buffer) const
Create an XsSyncSttingsArray from the given buffer of sync configuration data.
Definition: mtibasedevice.cpp:260
XsSize
size_t XsSize
XsSize must be unsigned number!
Definition: xstypedefs.h:74
MtiBaseDevice::utcTime
XsTimeInfo utcTime() const
Gets the 'UTC Time' setting of the device.
Definition: mtibasedevice.cpp:400
MtiBaseDevice::representativeMotionState
bool representativeMotionState() override
Definition: mtibasedevice.cpp:562
mtdevice.h
MtiBaseDevice::supportedUpdateRates
std::vector< int > supportedUpdateRates(XsDataIdentifier dataType=XDI_None) const override
Ask the device for its supported update rates for the given dataType.
Definition: mtibasedevice.cpp:350
MtiBaseDevice::alignmentRotationQuaternion
XsQuaternion alignmentRotationQuaternion(XsAlignmentFrame frame) const override
Retrieve the alignment rotation quaternion.
Definition: mtibasedevice.cpp:159
MtiBaseDevice::rs485TransmissionDelay
uint16_t rs485TransmissionDelay() const
Returns the transmission delay used for RS485 transmissions.
Definition: mtibasedevice.cpp:469
MtiBaseDevice::errorMode
XsErrorMode errorMode() const override
Returns the error mode of the device.
Definition: mtibasedevice.cpp:462
MtiBaseDevice::syncLine
virtual uint8_t syncLine(const XsSyncSetting &setting) const
Returns the sync line for a generic mti device.
Definition: mtibasedevice.cpp:514
MtiBaseDevice::getBaseFrequencyInternal
virtual BaseFrequencyResult getBaseFrequencyInternal(XsDataIdentifier dataType=XDI_None) const
An internal function that gets the base frequency.
Definition: mtibasedevice.h:145
MtiBaseDevice::setAlignmentRotationMatrix
bool setAlignmentRotationMatrix(XsAlignmentFrame frame, const XsMatrix &matrix) override
Set an arbitrary alignment rotation matrix Use to rotate either L to the chosen frame L' or S to the ...
Definition: mtibasedevice.cpp:174
MtiBaseDevice::getBaseFrequency
int getBaseFrequency(XsDataIdentifier dataType=XDI_None) const override
Definition: mtibasedevice.cpp:343
XsSyncLine
XsSyncLine
Synchronization line identifiers.
Definition: xssyncline.h:74
XsErrorMode
XsErrorMode
Error modes for use in XsDevice::setErrorMode.
Definition: xserrormode.h:74
MtiBaseDevice::BaseFrequencyResult::m_divedable
bool m_divedable
A divedable value.
Definition: mtibasedevice.h:127
XsSyncSettingArray
A list of XsSyncSetting values.
MtiBaseDevice::BaseFrequencyResult
A struct for base frequency result.
Definition: mtibasedevice.h:124
MtiBaseDevice::~MtiBaseDevice
virtual ~MtiBaseDevice()
Definition: mtibasedevice.cpp:98
MtiBaseDevice::storeIccResults
bool storeIccResults() override
Stores the ICC results.
Definition: mtibasedevice.cpp:612
XsDevice
Definition: xsdevice_def.h:164
XsAlignmentFrame
XsAlignmentFrame
Alignment frame.
Definition: xsalignmentframe.h:74
XsTimeInfo
A structure for storing Time values.
Definition: xstimeinfo.h:87
MtiBaseDeviceEx
The internal base class for MTi devices.
Definition: mtibasedevice.h:161
MtiBaseDevice::MtiBaseDevice
MtiBaseDevice(Communicator *comm)
Constructs a device.
Definition: mtibasedevice.cpp:85


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