xscontrol_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 XSCONTROL_DEF_H
66 #define XSCONTROL_DEF_H
67 
68 #include "xsdef.h"
69 #include <vector>
70 #include "xscallback.h"
71 #include <atomic>
72 
73 #include <xstypes/xsdeviceid.h>
74 #include <xstypes/xsfilepos.h>
75 #include <xstypes/xsbaud.h>
76 #include <xstypes/xsresultvalue.h>
77 #include <xstypes/xsmessage.h>
78 #include <xscommon/xsens_mutex.h>
79 #include <xstypes/xsresetmethod.h>
80 #include "devicefactory.h"
81 #include "callbackmanagerxda.h"
82 #include <xstypes/xsvector3.h>
83 #include "lastresultmanager.h"
84 #include <xstypes/xsoption.h>
85 
91 
95 
96 //AUTO namespace xstypes {
97 //AUTO+chdr struct PstdInt;
98 //AUTO+chdr struct XsTypeDefs;
99 //AUTO+chdr struct XsException;
100 struct XsString;
101 struct XsPortInfo;
102 struct XsPortInfoArray;
103 struct XsSyncSetting;
104 struct XsDataPacket;
105 struct XsMessage;
106 struct XsFilterProfile;
107 
108 //AUTO enum XsResultValue;
109 //AUTO enum XsBaud;
110 //AUTO enum XsXbusMessageId;
111 //AUTO struct XsDeviceIdArray;
112 //AUTO struct XsIntArray;
113 //AUTO struct XsSyncSettingArray;
114 //AUTO typename XsDevice;
115 //AUTO enum XsFilePos;
116 //AUTO struct XsFilterProfileArray;
117 //AUTO enum XsOption;
118 
119 //AUTO }
120 
121 //AUTO namespace xscontroller {
122 struct XsDeviceConfiguration;
123 struct XsDevicePtrArray;
124 //AUTO }
125 
126 #ifndef XsensThreadReturn
127  #define XsensThreadReturn XSENS_THREAD_RETURN // for generator
128  #define XsensThreadParam XSENS_THREAD_PARAM // for generator
129 #endif
130 
132 {
133 public:
134  XsControl();
135  ~XsControl();
136 
137  void flushInputBuffers();
138 
139  static XsString resultText(XsResultValue resultCode);
140 
141  void clearHardwareError();
142  void close();
143 
144  bool openPort(const XsString& portname, XsBaudRate baudrate, uint32_t timeout = 0, bool detectRs485 = false);
145  bool openPort(XsPortInfo& portinfo, uint32_t timeout = 0, bool detectRs485 = false);
146  bool openPortWithCredentials(XsPortInfo& portinfo, XsString const& id, XsString const& key, uint32_t timeout = 0);
147  bool openCustomPort(int channelId, uint32_t channelLatency, bool detectRs485 = false);
148  virtual bool openImarPort_internal(const XsString& portname, XsBaudRate baudrate, int imarType, uint32_t timeout = 0);
149 #ifndef XSENS_NO_PORT_NUMBERS
150  XSNOLINUXEXPORT bool openPort(int portNr, XsBaudRate baudrate, uint32_t timeout = 0, bool detectRs485 = false);
151 #endif
152  void closePort(const XsString& portname);
153  void closePort(const XsDeviceId& deviceId);
154  void closePort(const XsPortInfo& portinfo);
155  void closeCustomPort(int channelId);
156 #ifndef XSENS_NO_PORT_NUMBERS
157  XSNOLINUXEXPORT void closePort(int portNr);
158 #endif
159  void closePort(XsDevice* device);
160 
161  XsPortInfo customPortInfo(int channelId) const;
162 
163  bool openLogFile(const XsString& filename);
164 
165  XsResultValue lastResult() const;
166  XsString lastResultText() const;
169 
170  int deviceCount() const;
171  int mainDeviceCount() const;
172  std::vector<XsDeviceId> mainDeviceIds() const;
173  virtual int mtCount() const;
174  virtual std::vector<XsDeviceId> mtDeviceIds() const;
175  virtual std::vector<XsDeviceId> deviceIds() const;
176  XsDevice* getDeviceFromLocationId(uint16_t locationId) const;
177  XsDeviceId dockDeviceId(const XsDeviceId& deviceId) const;
178 
179  virtual bool isDeviceWireless(const XsDeviceId& deviceId) const;
180  virtual bool isDeviceDocked(const XsDeviceId& deviceId) const;
181 
182  virtual bool loadFilterProfiles(const XsString& filename);
183 
184  XsOption enabledOptions() const;
185  XsOption disabledOptions() const;
186  void setOptions(XsOption enable, XsOption disable);
187  void setOptionsForce(XsOption enabled);
188 
189  bool setInitialPositionLLA(const XsVector& lla);
190 
191  XsDevice* device(const XsDeviceId& deviceId) const;
193  XsDevice* broadcast() const;
194 
195  void transmissionReceived(int channelId, const XsByteArray& data);
196 #ifdef DOXYGEN
197  // Explicit inheritance for generator and doxygen
198  void XSNOCOMEXPORT clearCallbackHandlers(bool chain = true);
199  void XSNOCOMEXPORT addCallbackHandler(XsCallbackPlainC* cb, bool chain = true);
200  void XSNOCOMEXPORT removeCallbackHandler(XsCallbackPlainC* cb, bool chain = true);
201 #endif
202 
203  // these are only required to allow using the lib the same way as to using the dll
204  static XSNOEXPORT XsControl* construct();
206  {
207  delete this;
208  }
209 
210  virtual bool XSNOEXPORT finalizeOpenPort(Communicator* communicator, XsPortInfo& portinfo, uint32_t timeout, bool detectRs485);
211  void gotoConfig();
212  void gotoMeasurement();
213 
216 
217 protected:
218  virtual XsDevice* XSNOCOMEXPORT addMasterDevice(Communicator* communicator);
219 
220 #ifndef DOXYGEN
221  XSNOEXPORT XsControl(const XsControl&) = delete;
222 #endif
223 
224  //void gotoOperational(const XsDeviceId& stationId = XsDeviceId());
225 
228 
230  std::vector<XsDevice*> m_deviceList;
231 
233  std::map<int, ProxyCommunicator*> m_proxyChannels;
234 
237 
240 
243 
245  // thread management, multiple locks should always use this same order
250 
252  volatile std::atomic_bool m_recording;
253 
254  void updateRecordingState();
255 
256  XsDevice* findDevice(const XsDeviceId& deviceId) const;
257 
258  virtual void removeExistingDevice(XsDeviceId const& deviceId);
259 
261  Communicator* findXbusInterface(const XsDeviceId& deviceId) const;
262  Communicator* findXbusInterface(const XsPortInfo& portInfo) const;
263  Communicator* findXbusInterface(const XsString& portName) const;
264 
265  void closePortByIndex(uint32_t index);
266 
269 
272 
275 
278 
279  void setPersistentSettings(XsDevice* dev);
280 
283 
286 
289 
291  friend class BroadcastDevice;
292  friend class BroadcastForwardFunc; // XS_INTERNAL
294 };
295 
296 #endif
XsControl::m_deviceList
std::vector< XsDevice * > m_deviceList
This list contains device-information and cached data per device.
Definition: xscontrol_def.h:230
XsControl::startRestoreCommunication
XsResultValue startRestoreCommunication(const XsString &portName)
Starts restore communication procedure.
Definition: xscontrol_def.cpp:538
XsControl::dockDeviceId
XsDeviceId dockDeviceId(const XsDeviceId &deviceId) const
Get the device ID of the dock device for the given deviceId.
Definition: xscontrol_def.cpp:898
xsens::MutexReadWrite
A readers-writer mutex class.
Definition: xsens_mutex.h:248
EmtsManager
class XSNOEXPORT EmtsManager
Definition: xscontrol_def.h:93
XsVector
A class that represents a vector of real numbers.
Definition: xsvector.h:113
XsControl::close
void close()
Close all ports and files.
Definition: xscontrol_def.cpp:194
XsControl::lastHardwareErrorDeviceId
XsDeviceId lastHardwareErrorDeviceId() const
Definition: xscontrol_def.cpp:399
XsControl::m_useFakeMessages
bool m_useFakeMessages
Boolean variable for enabling/disabling the use of fake messages.
Definition: xscontrol_def.h:227
XsByteArray
A list of uint8_t values.
XsControl::openPort
bool openPort(const XsString &portname, XsBaudRate baudrate, uint32_t timeout=0, bool detectRs485=false)
Open a communication channel on serial port with the given portname.
Definition: xscontrol_def.cpp:684
XsCallbackPlainC
Structure that contains callback functions for the Xsens Device API.
Definition: xscallbackplainc.h:99
XsControl::setInitialPositionLLA
bool setInitialPositionLLA(const XsVector &lla)
Sets the current GNSS position of the system.
Definition: xscontrol_def.cpp:935
XsControl::disabledOptions
XsOption disabledOptions() const
Return the currently explicitly disabled options.
Definition: xscontrol_def.cpp:1118
XsControl::isDeviceDocked
virtual bool isDeviceDocked(const XsDeviceId &deviceId) const
Test if the given deviceId is docked.
Definition: xscontrol_def.cpp:558
XsControl::loadFilterProfiles
virtual bool loadFilterProfiles(const XsString &filename)
Load filter profile definitions from a settings file with the given filename.
Definition: xscontrol_def.cpp:1086
XsControl::mainDeviceCount
int mainDeviceCount() const
Get the number of main devices.
Definition: xscontrol_def.cpp:432
XsControl::setOptionsForce
void setOptionsForce(XsOption enabled)
Peristently enable or disable options.
Definition: xscontrol_def.cpp:1157
XsDeviceConfiguration
Structure containing a full device configuration as returned by the ReqConfig message.
Definition: xsdeviceconfiguration.h:143
ProxyCommunicator
Definition: proxycommunicator.h:73
XsControl::openCustomPort
bool openCustomPort(int channelId, uint32_t channelLatency, bool detectRs485=false)
Open a custom communication channel.
Definition: xscontrol_def.cpp:792
XsControl::deviceIds
virtual std::vector< XsDeviceId > deviceIds() const
Get the device IDs of all the connected devices.
Definition: xscontrol_def.cpp:333
XsControl::closePort
void closePort(const XsString &portname)
Close the serial port with the given portname.
Definition: xscontrol_def.cpp:260
XsControl::openLogFile
bool openLogFile(const XsString &filename)
Open the log file with the given filename.
Definition: xscontrol_def.cpp:609
XsControl::stopRestoreCommunication
void stopRestoreCommunication()
Stops restore communication procedure.
Definition: xscontrol_def.cpp:545
XsControl::openPortWithCredentials
bool openPortWithCredentials(XsPortInfo &portinfo, XsString const &id, XsString const &key, uint32_t timeout=0)
Open a communication channel using the details in the supplied XsPortInfo structure using the supplie...
Definition: xscontrol_def.cpp:765
XsDataPacket
Contains an interpreted data message. The class provides easy access to the contained data through it...
Definition: xsdatapacket.h:301
XsControl
High level Motion Tracker (MT) management class.
Definition: xscontrol_def.h:131
XsControl::closeCustomPort
void closeCustomPort(int channelId)
Closes a custom communication channel.
Definition: xscontrol_def.cpp:833
XsControl::lastResult
XsResultValue lastResult() const
Get the result value of the last operation.
Definition: xscontrol_def.cpp:409
XsControl::m_communicatorFactory
XdaCommunicatorFactory * m_communicatorFactory
The communicator factory object.
Definition: xscontrol_def.h:285
xsoption.h
XsControl::m_deviceFactory
DeviceFactory * m_deviceFactory
The device factory object.
Definition: xscontrol_def.h:282
BroadcastDevice
Intimately entangled class with XsControl that allows broadcasting to all main devices.
Definition: broadcastdevice.h:71
XsControl::construct
static XSNOEXPORT XsControl * construct()
Definition: xscontrol_def.cpp:1183
CallbackManagerXda::removeCallbackHandler
void removeCallbackHandler(XsCallbackPlainC *cb, bool chain=true)
Remove a handler from the list.
Definition: callbackmanagerxda.cpp:207
data
data
xsens_mutex.h
xsresetmethod.h
XsControl::mainDevices
XsDevicePtrArray mainDevices() const
Returns all main XsDevice interface objects.
Definition: xscontrol_def.cpp:955
XsOption
XsOption
Xda options, used to control the kind of data processing done by XDA.
Definition: xsoption.h:76
XsResultValue
XsResultValue
Xsens result values.
Definition: xsresultvalue.h:82
XsControl::m_restoreCommunication
RestoreCommunication * m_restoreCommunication
The restore communication object.
Definition: xscontrol_def.h:288
XsControl::setOptions
void setOptions(XsOption enable, XsOption disable)
Peristently enable or disable options.
Definition: xscontrol_def.cpp:1137
XsControl::m_optionsDisable
XsOption m_optionsDisable
Contsins all disabled options.
Definition: xscontrol_def.h:274
XsControl::closePortByIndex
void closePortByIndex(uint32_t index)
XsControl::m_recording
volatile std::atomic_bool m_recording
AwindaStationIndication of threads started or not.
Definition: xscontrol_def.h:252
XSNOEXPORT
#define XSNOEXPORT
Definition: xscommon_config.h:65
XsControl::~XsControl
~XsControl()
Destroy this XsControl object.
Definition: xscontrol_def.cpp:165
XsControl::enabledOptions
XsOption enabledOptions() const
Return the currently enabled options.
Definition: xscontrol_def.cpp:1109
XsSyncSetting
A structure for storing all xsens sync settings.
Definition: xssyncsetting.h:95
XsFilterProfile
Contains information about an available filter profile.
Definition: xsfilterprofile.h:92
Communicator
A base struct for a communication interface.
Definition: communicator.h:95
XsControl::m_lastHwErrorDeviceId
XsDeviceId m_lastHwErrorDeviceId
Contains the XsDevice ID of the device that caused the last hardware error.
Definition: xscontrol_def.h:242
XsBaudRate
enum XsBaudRate XsBaudRate
Communication speed.
Definition: xsbaud.h:81
BroadcastForwardFunc
Pure virtual base class for N-argument specific function forwarding.
Definition: broadcastdevice.cpp:87
uint32_t
unsigned int uint32_t
Definition: pstdint.h:485
XSNOLINUXEXPORT
#define XSNOLINUXEXPORT
Definition: xscontrollerconfig.h:253
XsPortInfo
Contains a descriptor for opening a communication port to an Xsens device.
Definition: xsportinfo.h:128
xsdef.h
Macros and types for use in the Xsens communication protocol and Xsens Device API classes.
XsControl::m_lastResult
LastResultManager m_lastResult
The last result of an operation.
Definition: xscontrol_def.h:236
XsControl::destruct
XSNOEXPORT void destruct()
Definition: xscontrol_def.h:205
XsControl::m_proxyChannels
std::map< int, ProxyCommunicator * > m_proxyChannels
This map contains the proxy channels.
Definition: xscontrol_def.h:233
XsControl::lastResultText
XsString lastResultText() const
Get the accompanying error text for the value returned by lastResult()
Definition: xscontrol_def.cpp:423
XsControl::m_optionsEnable
XsOption m_optionsEnable
Contains all enable options.
Definition: xscontrol_def.h:271
XsControl::mtDeviceIds
virtual std::vector< XsDeviceId > mtDeviceIds() const
Get the device IDs of the available MTs.
Definition: xscontrol_def.cpp:485
XsControl::findXbusInterface
Communicator * findXbusInterface(const XsDeviceId &deviceId) const
Find the xs3 info of the given id.
xsens::Mutex
A base mutex class.
Definition: xsens_mutex.h:132
XsControl::addMasterDevice
virtual XsDevice *XSNOCOMEXPORT addMasterDevice(Communicator *communicator)
devicefactory.h
XsControl::removeExistingDevice
virtual void removeExistingDevice(XsDeviceId const &deviceId)
XsControl::mainDeviceIds
std::vector< XsDeviceId > mainDeviceIds() const
Get the device IDs of the available main devices.
Definition: xscontrol_def.cpp:466
XsControl::finalizeOpenPort
virtual bool XSNOEXPORT finalizeOpenPort(Communicator *communicator, XsPortInfo &portinfo, uint32_t timeout, bool detectRs485)
XsControl::getDeviceFromLocationId
XsDevice * getDeviceFromLocationId(uint16_t locationId) const
Get the device of the device on the given locationId.
Definition: xscontrol_def.cpp:362
XsControl::mtCount
virtual int mtCount() const
Get the number of connected MTs.
Definition: xscontrol_def.cpp:446
XsControl::updateRecordingState
void updateRecordingState()
xsdeviceid.h
XsControl::broadcast
XsDevice * broadcast() const
Returns the broadcast device.
Definition: xscontrol_def.cpp:968
XsMessage
Structure for storing a single message.
Definition: xsmessage.h:202
XsControl::device
XsDevice * device(const XsDeviceId &deviceId) const
Returns the XsDevice interface object associated with the supplied deviceId.
Definition: xscontrol_def.cpp:947
XsPortInfoArray
A list of XsPortInfo values.
XsControl::gotoMeasurement
void gotoMeasurement()
Place all sensors connected through a serial port into Measurement Mode.
Definition: xscontrol_def.cpp:524
XsControl::deviceCount
int deviceCount() const
Get the number of connected devices.
Definition: xscontrol_def.cpp:317
XsControl::lastHardwareError
XsResultValue lastHardwareError() const
Get the last hardware error code.
Definition: xscontrol_def.cpp:392
XsControl::m_lastHwError
XsResultValue m_lastHwError
Contains the last serious error reported by CMT3.
Definition: xscontrol_def.h:239
XsDeviceId
Contains an Xsens device ID and provides operations for determining the type of device.
Definition: xsdeviceid.h:192
XsDevicePtrArray
A list of XsDevicePtr values.
xscallback.h
XsControl::customPortInfo
XsPortInfo customPortInfo(int channelId) const
Returns the port information for a custom communication channel.
Definition: xscontrol_def.cpp:820
XsControl::clearHardwareError
void clearHardwareError()
Clear the last hardware error.
Definition: xscontrol_def.cpp:381
XsControl::gotoConfig
void gotoConfig()
Place all sensors connected through a serial port into Configuration Mode.
Definition: xscontrol_def.cpp:510
xsmessage.h
xsbaud.h
XsControl::isDeviceWireless
virtual bool isDeviceWireless(const XsDeviceId &deviceId) const
Test if the given deviceId is an MTw and if it is wirelessly connected.
Definition: xscontrol_def.cpp:572
XsControl::flushInputBuffers
void flushInputBuffers()
Clear the inbound data buffers of all devices.
Definition: xscontrol_def.cpp:302
RestoreCommunication
Performs restore communication procedure with a provided COM port.
Definition: restorecommunication.h:75
XsControl::XsControl
XsControl()
Construct a new Xsens Device API control object.
Definition: xscontrol_def.cpp:140
XsControl::setPersistentSettings
void setPersistentSettings(XsDevice *dev)
XsControl::openImarPort_internal
virtual bool openImarPort_internal(const XsString &portname, XsBaudRate baudrate, int imarType, uint32_t timeout=0)
Open a communication channel on serial port with the given portname.
Definition: xscontrol_def.cpp:880
callbackmanagerxda.h
LastResultManager
This class manages a result code with optional additional text.
Definition: lastresultmanager.h:75
xsvector3.h
XsVector3
A class that represents a fixed size (3) vector.
Definition: xsvector3.h:95
lastresultmanager.h
XsControl::findDevice
XsDevice * findDevice(const XsDeviceId &deviceId) const
XdaCommunicatorFactory
XDA communication factory.
Definition: xdacommunicatorfactory.h:70
XsControl::m_portMutex
xsens::MutexReadWrite m_portMutex
Controls access to the serial ports, also used to suspend the thread.
Definition: xscontrol_def.h:247
xsfilepos.h
xsresultvalue.h
CallbackManagerXda
Class that delegates callbacks to registered XsCallbackHandlerItems.
Definition: callbackmanagerxda.h:78
XsControl::m_latLonAlt
XsVector3 m_latLonAlt
This vector contains the latitude, longitude and altitude.
Definition: xscontrol_def.h:277
XsControl::resultText
static XsString resultText(XsResultValue resultCode)
Get a descriptive text for the given resultCode.
Definition: xscontrol_def.cpp:186
XsControl::m_broadcaster
BroadcastDevice * m_broadcaster
The broadcast device object.
Definition: xscontrol_def.h:268
DeviceFactory
A Factory for the devices.
Definition: devicefactory.h:75
XsString
A 0-terminated managed string of characters.
XsControl::transmissionReceived
void transmissionReceived(int channelId, const XsByteArray &data)
Feed data coming back from an Xsens device over a custom channel into XDA.
Definition: xscontrol_def.cpp:857
XsControl::m_runMutex
xsens::Mutex m_runMutex
Always held by the thread when it is running.
Definition: xscontrol_def.h:249
XsDevice
Definition: xsdevice_def.h:164
CallbackManagerXda::clearCallbackHandlers
void clearCallbackHandlers(bool chain=true)
Clear the callback list.
Definition: callbackmanagerxda.cpp:129
CallbackManagerXda::addCallbackHandler
void addCallbackHandler(XsCallbackPlainC *cb, bool chain=true)
Add a handler to the list.
Definition: callbackmanagerxda.cpp:158
NetworkScanner
class XSNOEXPORT NetworkScanner
Definition: xscontrol_def.h:94


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