mti7_mti8device.cpp
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 #include "mti7_mti8device.h"
66 #include <xstypes/xsstatusflag.h>
67 #include <xstypes/xsvector.h>
68 
70  : MtiBaseDeviceEx(comm)
71 {
72  if (comm)
73  comm->setDefaultTimeout(2000); //Increase the default timeout for MTi-1 devices because a settings write can occasionally take ~900ms
74 }
75 
77  : MtiBaseDeviceEx(masterdevice)
78 {
79 }
80 
82 {
83 }
84 
85 namespace
86 {
88 int baseFreq(XsDataIdentifier dataType)
89 {
90  switch (dataType & XDI_TypeMask)
91  {
92  case XDI_None:
93  return 100;
94  case XDI_TimestampGroup:
95  return XDI_MAX_FREQUENCY_VAL;
96  case XDI_StatusGroup:
97  return 100;
99  return 100;
100  case XDI_PositionGroup:
101  return 100;
102  case XDI_VelocityGroup:
103  return 100;
105  return 100;
107  return 100;
109  return 100;
110  case XDI_MagneticGroup:
111  return 100;
112  case XDI_PressureGroup:
113  return 50;
114  case XDI_GnssGroup:
115  {
116  XsDataIdentifier fullType = (dataType & XDI_FullTypeMask);
117  if (fullType == XDI_GnssGroup || fullType == XDI_GnssPvtData)
118  return 4;
119  return 0;
120  }
121  default:
122  return 0;
123  }
124 }
125 }
126 
130 {
131  BaseFrequencyResult result;
132  result.m_frequency = 0;
133  result.m_divedable = true;
134 
135  if ((dataType & XDI_FullTypeMask) == XDI_LocationId || (dataType & XDI_FullTypeMask) == XDI_DeviceId)
136  return result;
137 
138  if ((dataType & XDI_FullTypeMask) == XDI_AccelerationHR || (dataType & XDI_FullTypeMask) == XDI_RateOfTurnHR)
139  {
140  bool isMtMk4_1_v1 = hardwareVersion().major() == 1;
141  bool isMtMk4_1_v2 = hardwareVersion().major() == 2;
142  result.m_frequency = isMtMk4_1_v2 ? 800 : 1000;
143  result.m_divedable = isMtMk4_1_v1 ? false : true;
144 
145  return result;
146  }
147 
148  result.m_frequency = baseFreq(dataType);
149 
150  if (((dataType & XDI_TypeMask) == XDI_TimestampGroup) || ((dataType & XDI_TypeMask) == XDI_GnssGroup))
151  result.m_divedable = false;
152 
153  return result;
154 }
155 
157 {
158  return true;
159 }
160 
162 {
163  return (uint32_t)(
164  //|XSF_SelfTestOk
166  | XSF_GpsValid
170  | XSF_ClipAccX
171  | XSF_ClipAccY
172  | XSF_ClipAccZ
173  | XSF_ClipGyrX
174  | XSF_ClipGyrY
175  | XSF_ClipGyrZ
176  | XSF_ClipMagX
177  | XSF_ClipMagY
178  | XSF_ClipMagZ
179  //|XSF_Retransmitted
181  //|XSF_Interpolated
182  //|XSF_SyncIn
183  //|XSF_SyncOut
186  | (deviceId().isRtk() ? XSF_RtkStatus : 0)
187  );
188 }
189 
190 bool MTi7_MTi8Device::setStringOutputMode(uint16_t /*type*/, uint16_t /*period*/, uint16_t /*skipFactor*/)
191 {
192  return true;
193 }
194 
198 {
199  XsString code = productCode();
200 
201  if (hardwareVersion() >= XsVersion(2, 0, 0))
202  code = stripProductCode(code);
203 
204  return code;
205 }
206 
210 {
211  if (!deviceId().isRtk())
212  return false;
213 
214  XsMessage snd(XMID_SetGnssLeverArm, 3 * sizeof(float));
215  snd.setBusId(busId());
216  snd.setDataFloat((float)arm[0], 0/* sizeof(float)*/);
217  snd.setDataFloat((float)arm[1], 1 * sizeof(float));
218  snd.setDataFloat((float)arm[2], 2 * sizeof(float));
219 
220  XsMessage rcv;
221  if (!doTransaction(snd, rcv))
222  return false;
223 
224  return true;
225 }
226 
230 {
231  if (!deviceId().isRtk())
232  return XsVector();
233 
235  if (!doTransaction(snd, rcv))
236  return XsVector();
237 
238  XsVector arm(3);
239  arm[0] = rcv.getDataFloat(0/* sizeof(float)*/);
240  arm[1] = rcv.getDataFloat(1 * sizeof(float));
241  arm[2] = rcv.getDataFloat(2 * sizeof(float));
242  return arm;
243 }
XDI_RateOfTurnHR
@ XDI_RateOfTurnHR
Rate of turn HR data.
Definition: xsdataidentifier.h:154
XDI_GnssPvtData
@ XDI_GnssPvtData
Gnss position, velocity and time data.
Definition: xsdataidentifier.h:147
XsDevice::deviceId
XsDeviceId const & deviceId() const
Return the device ID of the device.
Definition: xsdevice_def.cpp:742
XDI_PositionGroup
@ XDI_PositionGroup
Group for position related outputs.
Definition: xsdataidentifier.h:140
XsVector
A class that represents a vector of real numbers.
Definition: xsvector.h:113
XDI_AccelerationGroup
@ XDI_AccelerationGroup
Group for acceleration related outputs.
Definition: xsdataidentifier.h:129
XDI_AngularVelocityGroup
@ XDI_AngularVelocityGroup
Group for angular velocity related outputs.
Definition: xsdataidentifier.h:151
MtiBaseDevice::BaseFrequencyResult::m_frequency
int m_frequency
A frequency value.
Definition: mtibasedevice.h:126
MtDevice::stripProductCode
static XsString stripProductCode(const XsString &code)
Helper function to strip the hardware type from the product code.
Definition: mtdevice.cpp:895
mti7_mti8device.h
XSF_ClipGyrZ
@ XSF_ClipGyrZ
Definition: xsstatusflag.h:101
XDI_None
@ XDI_None
Empty datatype.
Definition: xsdataidentifier.h:86
XSF_GpsValid
@ XSF_GpsValid
Is set when the device has a GPS receiver and the receiver says that there is a GPS position fix.
Definition: xsstatusflag.h:83
XDI_DeviceId
@ XDI_DeviceId
DeviceId output.
Definition: xsdataidentifier.h:196
MtDevice::productCode
XsString productCode() const
Return the product code of the device.
Definition: mtdevice.cpp:497
MTi7_MTi8Device::hasIccSupport
bool hasIccSupport() const override
Definition: mti7_mti8device.cpp:156
xsvector.h
XDI_VelocityGroup
@ XDI_VelocityGroup
Group for velocity related outputs.
Definition: xsdataidentifier.h:189
xsstatusflag.h
XsVersion
struct XsVersion XsVersion
Definition: xsversion.h:80
MtDevice::hardwareVersion
XsVersion hardwareVersion() const
Return the hardware version of the device.
Definition: mtdevice.cpp:424
XSF_ClippingDetected
@ XSF_ClippingDetected
When set Indicates clipping has occurred.
Definition: xsstatusflag.h:107
MTi7_MTi8Device::shortProductCode
XsString shortProductCode() const override
Return the shortened product code of the device suitable for display.
Definition: mti7_mti8device.cpp:197
XSF_ClipMagZ
@ XSF_ClipMagZ
Definition: xsstatusflag.h:104
MTi7_MTi8Device::getBaseFrequencyInternal
BaseFrequencyResult getBaseFrequencyInternal(XsDataIdentifier dataType=XDI_None) const override
Returns the base update rate (hz) corresponding to the dataType.
Definition: mti7_mti8device.cpp:129
XSF_RepresentativeMotion
@ XSF_RepresentativeMotion
Indicates if the In-Run Compass Calibration is doing the representative motion analysis.
Definition: xsstatusflag.h:90
XSF_FilterMode
@ XSF_FilterMode
Mask for the 3 bit filter mode field.
Definition: xsstatusflag.h:112
XDI_MagneticGroup
@ XDI_MagneticGroup
Group for magnetometer related outputs.
Definition: xsdataidentifier.h:172
XDI_FullTypeMask
@ XDI_FullTypeMask
Mask to get the type of data, without the data format.
Definition: xsdataidentifier.h:88
XSF_ClipAccX
@ XSF_ClipAccX
Definition: xsstatusflag.h:96
XDI_LocationId
@ XDI_LocationId
LocationId output.
Definition: xsdataidentifier.h:197
XSF_NoRotationMask
@ XSF_NoRotationMask
If all of these flags are set, the No Rotation algorithm is running.
Definition: xsstatusflag.h:85
XsDevice::busId
virtual int busId() const
The bus ID for this device.
Definition: xsdevice_def.cpp:860
XSF_ExternalClockSynced
@ XSF_ExternalClockSynced
Indicates whether the internal clock is synced with an external clock (Either GNNS or custom provided...
Definition: xsstatusflag.h:92
MTi7_MTi8Device::MTi7_MTi8Device
MTi7_MTi8Device(Communicator *comm)
An empty constructor for a device.
Definition: mti7_mti8device.cpp:69
XSF_OrientationValid
@ XSF_OrientationValid
Is set when the computed orientation is valid. The orientation may be invalid during startup or when ...
Definition: xsstatusflag.h:82
XSF_ClipMagX
@ XSF_ClipMagX
Definition: xsstatusflag.h:102
XSF_RtkStatus
@ XSF_RtkStatus
Mask for 2 bit RTK status field 00: No RTK; 01: RTK floating; 10: RTK fixed.
Definition: xsstatusflag.h:115
XsDataIdentifier
XsDataIdentifier
Defines the data identifiers.
Definition: xsdataidentifier.h:84
Communicator
A base struct for a communication interface.
Definition: communicator.h:95
uint32_t
unsigned int uint32_t
Definition: pstdint.h:485
MTi7_MTi8Device::setStringOutputMode
bool setStringOutputMode(uint16_t type, uint16_t period, uint16_t skipFactor) override
Sets the string output mode for this device.
Definition: mti7_mti8device.cpp:190
MTi7_MTi8Device::supportedStatusFlags
uint32_t supportedStatusFlags() const override
Returns a bitmask with all the status flags supported by this device.
Definition: mti7_mti8device.cpp:161
XSF_ClipGyrX
@ XSF_ClipGyrX
Definition: xsstatusflag.h:99
MTi7_MTi8Device::~MTi7_MTi8Device
virtual ~MTi7_MTi8Device()
Definition: mti7_mti8device.cpp:81
XDI_TimestampGroup
@ XDI_TimestampGroup
Group for time stamp related outputs.
Definition: xsdataidentifier.h:105
Communicator::setDefaultTimeout
void setDefaultTimeout(uint32_t timeout)
Sets a default timeout.
Definition: communicator.h:139
XDI_GnssGroup
@ XDI_GnssGroup
Group for Gnss related outputs.
Definition: xsdataidentifier.h:146
XDI_StatusGroup
@ XDI_StatusGroup
Group for status related outputs.
Definition: xsdataidentifier.h:192
XsVector
struct XsVector XsVector
Definition: xsvector.h:87
XSF_ClipGyrY
@ XSF_ClipGyrY
Definition: xsstatusflag.h:100
XsMessage
Structure for storing a single message.
Definition: xsmessage.h:202
XDI_MAX_FREQUENCY_VAL
#define XDI_MAX_FREQUENCY_VAL
Definition: xsdataidentifiervalue.h:69
XSF_ClipAccZ
@ XSF_ClipAccZ
Definition: xsstatusflag.h:98
XMID_SetGnssLeverArm
@ XMID_SetGnssLeverArm
Definition: xsxbusmessageid.h:258
MtiBaseDevice::BaseFrequencyResult::m_divedable
bool m_divedable
A divedable value.
Definition: mtibasedevice.h:127
XSF_ClipMagY
@ XSF_ClipMagY
Definition: xsstatusflag.h:103
XSF_ClipAccY
@ XSF_ClipAccY
Definition: xsstatusflag.h:97
XDI_PressureGroup
@ XDI_PressureGroup
Group for pressure related outputs.
Definition: xsdataidentifier.h:126
MTi7_MTi8Device::setGnssLeverArm
bool setGnssLeverArm(const XsVector &arm) override
Sets the GNSS Lever Arm vector.
Definition: mti7_mti8device.cpp:209
XDI_OrientationGroup
@ XDI_OrientationGroup
Group for orientation related outputs.
Definition: xsdataidentifier.h:117
XDI_TemperatureGroup
@ XDI_TemperatureGroup
Group for temperature outputs.
Definition: xsdataidentifier.h:102
XsDevice::doTransaction
bool doTransaction(const XsMessage &snd) const
MTi7_MTi8Device::gnssLeverArm
XsVector gnssLeverArm() const override
Definition: mti7_mti8device.cpp:229
MtiBaseDevice::BaseFrequencyResult
A struct for base frequency result.
Definition: mtibasedevice.h:124
XsString
A 0-terminated managed string of characters.
XsDevice
Definition: xsdevice_def.h:164
XSF_HaveGnssTimePulse
@ XSF_HaveGnssTimePulse
Indicates that the 1PPS GNSS time pulse is present.
Definition: xsstatusflag.h:113
XDI_TypeMask
@ XDI_TypeMask
Mask for checking the group which a dataidentifier belongs to, Eg. XDI_TimestampGroup or XDI_Orientat...
Definition: xsdataidentifier.h:87
XMID_ReqGnssLeverArm
@ XMID_ReqGnssLeverArm
Definition: xsxbusmessageid.h:256
XDI_AccelerationHR
@ XDI_AccelerationHR
AccelerationHR output.
Definition: xsdataidentifier.h:133
MtiBaseDeviceEx
The internal base class for MTi devices.
Definition: mtibasedevice.h:161


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