broadcastdevice.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 "broadcastdevice.h"
66 #include "xscontrol_def.h"
67 #include <xstypes/xssyncsetting.h>
69 
70 using namespace xsens;
71 
88 {
89 public:
90  BroadcastForwardFunc(BroadcastDevice* bc) : m_broadcaster(bc) {}
91  virtual ~BroadcastForwardFunc() {}
92  bool operator()()
93  {
94  LockReadWrite portLock(&m_broadcaster->m_control->m_portMutex);
95  portLock.lock(true);
96 
97  std::vector<XsDevice*>& ch = m_broadcaster->m_control->m_deviceList;
98 
99  bool ok = true;
101  for (std::vector<XsDevice*>::iterator it = ch.begin(); it != ch.end(); ++it)
102  {
103  if (!call(*it))
104  ok = false;
105  }
106  m_broadcaster->m_control->m_lastResult = res;
107  return ok;
108  }
109 
110  virtual bool call(XsDevice* device) = 0;
111 
113 };
114 
117 {
118 public:
119  typedef bool (XsDevice::*FuncType)() const;
120  inline ForwardConstFunc(BroadcastDevice* bc, FuncType func)
121  : BroadcastForwardFunc(bc), m_func(func) {}
122  virtual bool call(XsDevice* device)
123  {
124  return (device->*m_func)();
125  }
126 private:
127  FuncType m_func;
128 };
129 
131 template <typename Arg1>
133 {
134 public:
135  typedef bool (XsDevice::*FuncType)(Arg1) const;
136  inline ForwardConstFunc1Arg(BroadcastDevice* bc, FuncType func, Arg1 arg1)
137  : BroadcastForwardFunc(bc), m_func(func), m_arg1(arg1) {}
138  virtual bool call(XsDevice* device)
139  {
140  return (device->*m_func)(m_arg1);
141  }
142 private:
143  FuncType m_func;
144  Arg1 m_arg1;
145 };
146 
149 {
150 public:
151  typedef bool (XsDevice::*FuncType)();
152  inline BroadcastForwardFunc0Arg(BroadcastDevice* bc, FuncType func)
153  : BroadcastForwardFunc(bc), m_func(func) {}
154  virtual bool call(XsDevice* device)
155  {
156  return (device->*m_func)();
157  }
158 private:
159  FuncType m_func;
160 };
161 
163 template <typename Arg1>
165 {
166 public:
167  typedef bool (XsDevice::*FuncType)(Arg1);
168  inline BroadcastForwardFunc1Arg(BroadcastDevice* bc, FuncType func, Arg1 arg1)
169  : BroadcastForwardFunc(bc), m_func(func), m_arg1(arg1) {}
170  virtual bool call(XsDevice* device)
171  {
172  return (device->*m_func)(m_arg1);
173  }
174 private:
175  FuncType m_func;
176  Arg1 m_arg1;
177 };
178 
180 template <typename Arg1, typename Arg2>
182 {
183 public:
184  typedef bool (XsDevice::*FuncType)(Arg1, Arg2);
185  inline BroadcastForwardFunc2Arg(BroadcastDevice* bc, FuncType func, Arg1 arg1, Arg2 arg2)
186  : BroadcastForwardFunc(bc), m_func(func), m_arg1(arg1), m_arg2(arg2) {}
187  virtual bool call(XsDevice* device)
188  {
189  return (device->*m_func)(m_arg1, m_arg2);
190  }
191 private:
192  FuncType m_func;
193  Arg1 m_arg1;
194  Arg2 m_arg2;
195 };
196 
198 template <typename Arg1, typename Arg2, typename Arg3>
200 {
201 public:
202  typedef bool (XsDevice::*FuncType)(Arg1, Arg2, Arg3);
203  inline BroadcastForwardFunc3Arg(BroadcastDevice* bc, FuncType func, Arg1 arg1, Arg2 arg2, Arg3 arg3)
204  : BroadcastForwardFunc(bc), m_func(func), m_arg1(arg1), m_arg2(arg2), m_arg3(arg3) {}
205  virtual bool call(XsDevice* device)
206  {
207  return (device->*m_func)(m_arg1, m_arg2, m_arg3);
208  }
209 private:
210  FuncType m_func;
211  Arg1 m_arg1;
212  Arg2 m_arg2;
213  Arg3 m_arg3;
214 };
215 
218 {
219 public:
220  typedef void (XsDevice::*FuncType)();
222  : BroadcastForwardFunc(bc), m_func(func) {}
223  virtual bool call(XsDevice* device)
224  {
225  (device->*m_func)();
226  return true;
227  }
228 private:
229  FuncType m_func;
230 };
231 
233 template <typename Arg1>
235 {
236 public:
237  typedef void (XsDevice::*FuncType)(Arg1);
238  inline BroadcastForwardFunc1ArgVoid(BroadcastDevice* bc, FuncType func, Arg1 arg1)
239  : BroadcastForwardFunc(bc), m_func(func), m_arg1(arg1) {}
240  virtual bool call(XsDevice* device)
241  {
242  (device->*m_func)(m_arg1);
243  return true;
244  }
245 private:
246  FuncType m_func;
247  Arg1 m_arg1;
248 };
249 
251 template <typename Arg1, typename Arg2>
253 {
254 public:
255  typedef void (XsDevice::*FuncType)(Arg1, Arg2);
256  inline BroadcastForwardFunc2ArgVoid(BroadcastDevice* bc, FuncType func, Arg1 arg1, Arg2 arg2)
257  : BroadcastForwardFunc(bc), m_func(func), m_arg1(arg1), m_arg2(arg2) {}
258  virtual bool call(XsDevice* device)
259  {
260  (device->*m_func)(m_arg1, m_arg2);
261  return true;
262  }
263 private:
264  FuncType m_func;
265  Arg1 m_arg1;
266  Arg2 m_arg2;
267 };
268 
272  : XsDevice(XsDeviceId(0))
273  , m_control(control_)
274 {
275 }
276 
280 {
282  m_control = NULL;
283 }
284 
287 std::vector<XsDevice*> BroadcastDevice::children() const
288 {
289  return m_control->m_deviceList;
290 }
291 
294 {
295  return false;
296 }
299 {
300  (void)dataType;
301  return std::vector<int>();
302 }
305 {
306  return XsString("Broadcaster");
307 }
310 {
311  return XsVersion();
312 }
313 
321 {
323 }
324 
328 {
329  JLDEBUGG("");
332  return rv;
333 }
334 
338 {
339  JLDEBUGG("");
342  return rv;
343 }
344 
348 {
350 }
351 
353 {
355 }
356 
358 {
360 }
361 
362 bool BroadcastDevice::setNoRotation(uint16_t duration)
363 {
365 }
366 
368 {
370 }
371 
373 {
375 }
376 
378 {
380 }
381 
383 {
384  return ForwardConstFunc(const_cast<BroadcastDevice* const>(this), &XsDevice::isMeasuring)();
385 }
386 
388 {
389  return ForwardConstFunc(const_cast<BroadcastDevice* const>(this), &XsDevice::isRecording)();
390 }
391 
393 {
394  return ForwardConstFunc(const_cast<BroadcastDevice* const>(this), &XsDevice::isReadingFromFile)();
395 }
396 
398 {
399  // this one needs to go through the list in reverse order in case of multiple devices
400  // for synchronization reasons
401  std::vector<XsDevice*>& ch = m_control->m_deviceList;
402 
403  bool ok = true;
405  for (std::vector<XsDevice*>::reverse_iterator it = ch.rbegin(); it != ch.rend(); ++it)
406  {
407  if (!(*it)->gotoConfig())
408  ok = false;
409  }
410  m_control->m_lastResult = res;
411  return ok;
412 }
413 
415 {
417  {
418  gotoConfig();
419  return false;
420  }
421  return true;
422 }
423 
425 {
427 }
428 
430 {
432 }
433 
435 {
437 }
438 
440 {
442 }
443 
445 {
447 }
448 
450 {
452 }
453 
454 bool BroadcastDevice::reset(bool skipDeviceIdCheck)
455 {
456  return BroadcastForwardFunc1Arg<bool>(this, &XsDevice::reset, skipDeviceIdCheck)();
457 }
458 
459 bool BroadcastDevice::setTransportMode(bool transportModeEnabled)
460 {
461  return BroadcastForwardFunc1Arg<bool>(this, &XsDevice::setTransportMode, transportModeEnabled)();
462 }
463 
465 {
467 }
468 
470 {
471  return BroadcastForwardFunc1Arg<int>(this, &XsDevice::setXdaFilterProfile, profileType)();
472 }
473 
475 {
477 }
478 
480 {
482 }
483 
485 {
487 }
488 
490 {
492 }
493 
495 {
497 }
498 
500 {
502 }
503 
505 {
507 }
508 
510 {
512 }
BroadcastForwardFunc2Arg
2-argument forwarding function class
Definition: broadcastdevice.cpp:181
ForwardConstFunc1Arg::ForwardConstFunc1Arg
ForwardConstFunc1Arg(BroadcastDevice *bc, FuncType func, Arg1 arg1)
Definition: broadcastdevice.cpp:136
XsString
struct XsString XsString
Definition: xsstring.h:87
BroadcastForwardFunc0ArgVoid::call
virtual bool call(XsDevice *device)
Definition: broadcastdevice.cpp:223
XsControl::m_deviceList
std::vector< XsDevice * > m_deviceList
This list contains device-information and cached data per device.
Definition: xscontrol_def.h:230
XsMatrix
A class that represents a matrix of real numbers.
Definition: xsmatrix.h:107
XsDevice::setTerminationPrepared
void setTerminationPrepared(bool prepared) NOEXCEPT
Set the "termination prepared" state to prepared.
Definition: xsdevice_def.h:616
BroadcastForwardFunc1ArgVoid
1-argument forwarding function class, void return
Definition: broadcastdevice.cpp:234
BroadcastDevice::setSerialBaudRate
bool setSerialBaudRate(XsBaudRate baudrate) override
Change the serial baudrate to baudrate.
Definition: broadcastdevice.cpp:347
XsVector
A class that represents a vector of real numbers.
Definition: xsvector.h:113
call
bool call(const std::string &service_name, MReq &req, MRes &res)
BroadcastDevice::setSyncSettings
bool setSyncSettings(const XsSyncSettingArray &s) override
Set the synchronization settings of the device.
Definition: broadcastdevice.cpp:424
XsDevice::storeFilterState
virtual bool storeFilterState()
Store orientation filter state in the device.
Definition: xsdevice_def.cpp:2888
BroadcastDevice::gotoConfig
bool gotoConfig() override
Put the device in config mode.
Definition: broadcastdevice.cpp:397
BroadcastForwardFunc::~BroadcastForwardFunc
virtual ~BroadcastForwardFunc()
Definition: broadcastdevice.cpp:91
ForwardConstFunc
0-argument const forwarding function class
Definition: broadcastdevice.cpp:116
XsDevice::isReadingFromFile
virtual bool isReadingFromFile() const
Returns true if the device is reading from a file.
Definition: xsdevice_def.cpp:1783
BroadcastForwardFunc3Arg::BroadcastForwardFunc3Arg
BroadcastForwardFunc3Arg(BroadcastDevice *bc, FuncType func, Arg1 arg1, Arg2 arg2, Arg3 arg3)
Definition: broadcastdevice.cpp:203
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::setSerialBaudRate
virtual bool setSerialBaudRate(XsBaudRate baudrate)
Change the serial baudrate to baudrate.
Definition: xsdevice_def.cpp:875
BroadcastDevice::closeLogFile
bool closeLogFile() override
Close the log file.
Definition: broadcastdevice.cpp:357
BroadcastForwardFunc2Arg::m_arg2
Arg2 m_arg2
Definition: broadcastdevice.cpp:194
s
XmlRpcServer s
ForwardConstFunc1Arg::m_func
FuncType m_func
Definition: broadcastdevice.cpp:143
xsens::LockReadWrite::lock
bool lock(bool write)
Make sure that the lock has exactly the given lock state.
Definition: xsens_mutex.h:1129
BroadcastDevice::supportedUpdateRates
std::vector< int > supportedUpdateRates(XsDataIdentifier dataType) const override
required function to prevent pure-virtualness
Definition: broadcastdevice.cpp:298
BroadcastDevice::setTransportMode
bool setTransportMode(bool transportModeEnabled) override
Enable or disable the transport mode for the device.
Definition: broadcastdevice.cpp:459
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::setSyncSettings
virtual bool setSyncSettings(const XsSyncSettingArray &settingList)
Set the synchronization settings of the device.
Definition: xsdevice_def.cpp:3158
BroadcastDevice::isMeasuring
bool isMeasuring() const override
Returns true if the device is currently in a measuring state.
Definition: broadcastdevice.cpp:382
BroadcastForwardFunc1ArgVoid::call
virtual bool call(XsDevice *device)
Definition: broadcastdevice.cpp:240
XsVersion
struct XsVersion XsVersion
Definition: xsversion.h:80
BroadcastForwardFunc0ArgVoid::m_func
FuncType m_func
Definition: broadcastdevice.cpp:229
BroadcastForwardFunc0Arg::BroadcastForwardFunc0Arg
BroadcastForwardFunc0Arg(BroadcastDevice *bc, FuncType func)
Definition: broadcastdevice.cpp:152
xsens::LockReadWrite
A readers-writer lock class.
Definition: xsens_mutex.h:1090
BroadcastDevice::storeFilterState
bool storeFilterState() override
Store orientation filter state in the device.
Definition: broadcastdevice.cpp:494
XsControl
High level Motion Tracker (MT) management class.
Definition: xscontrol_def.h:131
BroadcastForwardFunc2ArgVoid::m_arg2
Arg2 m_arg2
Definition: broadcastdevice.cpp:266
BroadcastDevice::isReadingFromFile
bool isReadingFromFile() const override final
Returns true if the device is reading from a file.
Definition: broadcastdevice.cpp:392
BroadcastDevice
Intimately entangled class with XsControl that allows broadcasting to all main devices.
Definition: broadcastdevice.h:71
ok
ROSCPP_DECL bool ok()
XsDevice::flushInputBuffers
virtual void flushInputBuffers()
Clear the inbound data buffers of the device.
Definition: xsdevice_def.cpp:1807
XRV_OK
@ XRV_OK
0: Operation was performed successfully
Definition: xsresultvalue.h:85
BroadcastForwardFunc3Arg::m_arg3
Arg3 m_arg3
Definition: broadcastdevice.cpp:213
BroadcastDevice::flushInputBuffers
void flushInputBuffers() override
Clear the inbound data buffers of the device.
Definition: broadcastdevice.cpp:509
BroadcastDevice::abortFlushing
bool abortFlushing() override
Abort the wireless flushing operation and finalize the recording.
Definition: broadcastdevice.cpp:377
BroadcastDevice::resetLogFileReadPosition
bool resetLogFileReadPosition() override
Set the read position of the open log file to the start of the file.
Definition: broadcastdevice.cpp:449
XsDevice::stopRecording
virtual bool stopRecording()
Stop recording incoming data.
Definition: xsdevice_def.cpp:2201
BroadcastDevice::resetOrientation
bool resetOrientation(XsResetMethod resetMethod) override
Perform an orientation reset on the device using the given resetMethod.
Definition: broadcastdevice.cpp:439
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
BroadcastDevice::setNoRotation
bool setNoRotation(uint16_t duration) override
Set the no rotation period to duration.
Definition: broadcastdevice.cpp:362
XsResultValue
XsResultValue
Xsens result values.
Definition: xsresultvalue.h:82
BroadcastDevice::requestBatteryLevel
bool requestBatteryLevel() override
Request the battery level from the device.
Definition: broadcastdevice.cpp:367
BroadcastDevice::setHeadingOffset
bool setHeadingOffset(double offset) override
Set the 'heading offset' setting of the device.
Definition: broadcastdevice.cpp:429
BroadcastDevice::hardwareVersion
XsVersion hardwareVersion() const override
required function to prevent pure-virtualness
Definition: broadcastdevice.cpp:309
xscontrol_def.h
BroadcastDevice::updateCachedDeviceInformation
bool updateCachedDeviceInformation() override
Updates the cached device information for all devices connected to this port.
Definition: broadcastdevice.cpp:464
BroadcastForwardFunc1Arg::m_func
FuncType m_func
Definition: broadcastdevice.cpp:175
XsDataIdentifier
XsDataIdentifier
Defines the data identifiers.
Definition: xsdataidentifier.h:84
XsDevice::loadLogFile
virtual bool loadLogFile()
Load a complete logfile.
Definition: xsdevice_def.cpp:3045
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
XRV_NOFILEORPORTOPEN
@ XRV_NOFILEORPORTOPEN
289: No file or serial port opened for reading/writing
Definition: xsresultvalue.h:160
BroadcastForwardFunc1Arg::m_arg1
Arg1 m_arg1
Definition: broadcastdevice.cpp:176
BroadcastForwardFunc2ArgVoid::call
virtual bool call(XsDevice *device)
Definition: broadcastdevice.cpp:258
BroadcastForwardFunc0Arg::m_func
FuncType m_func
Definition: broadcastdevice.cpp:159
BroadcastForwardFunc2Arg::BroadcastForwardFunc2Arg
BroadcastForwardFunc2Arg(BroadcastDevice *bc, FuncType func, Arg1 arg1, Arg2 arg2)
Definition: broadcastdevice.cpp:185
ForwardConstFunc::m_func
FuncType m_func
Definition: broadcastdevice.cpp:127
XsControl::m_lastResult
LastResultManager m_lastResult
The last result of an operation.
Definition: xscontrol_def.h:236
BroadcastDevice::batteryLevelTime
XsTimeStamp batteryLevelTime() override
Requests the time the battery level was last updated.
Definition: broadcastdevice.cpp:372
BroadcastDevice::BroadcastDevice
BroadcastDevice(XsControl *control)
Constructor, sets up the XsControl reference.
Definition: broadcastdevice.cpp:271
ForwardConstFunc1Arg
1-argument const forwarding function class
Definition: broadcastdevice.cpp:132
BroadcastForwardFunc0ArgVoid
0-argument forwarding function class, void return
Definition: broadcastdevice.cpp:217
XsDevice::setHeadingOffset
virtual bool setHeadingOffset(double offset)
Set the 'heading offset' setting of the device.
Definition: xsdevice_def.cpp:2486
XsDevice::restoreFactoryDefaults
virtual bool restoreFactoryDefaults()
Restore the device to its factory default settings.
Definition: xsdevice_def.cpp:1953
BroadcastForwardFunc::operator()
bool operator()()
Definition: broadcastdevice.cpp:92
BroadcastForwardFunc2Arg::call
virtual bool call(XsDevice *device)
Definition: broadcastdevice.cpp:187
BroadcastDevice::setGravityMagnitude
bool setGravityMagnitude(double mag) override
Sets the 'Gravity Magnitude' of the device to the given value mag.
Definition: broadcastdevice.cpp:489
BroadcastForwardFunc2Arg::m_arg1
Arg1 m_arg1
Definition: broadcastdevice.cpp:193
BroadcastForwardFunc::BroadcastForwardFunc
BroadcastForwardFunc(BroadcastDevice *bc)
Definition: broadcastdevice.cpp:90
BroadcastDevice::isRecording
bool isRecording() const override
Returns true if the device is currently in a recording state.
Definition: broadcastdevice.cpp:387
BroadcastForwardFunc1Arg::BroadcastForwardFunc1Arg
BroadcastForwardFunc1Arg(BroadcastDevice *bc, FuncType func, Arg1 arg1)
Definition: broadcastdevice.cpp:168
BroadcastForwardFunc3Arg::call
virtual bool call(XsDevice *device)
Definition: broadcastdevice.cpp:205
BroadcastDevice::restoreFactoryDefaults
bool restoreFactoryDefaults() override
Restore the device to its factory default settings.
Definition: broadcastdevice.cpp:444
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
BroadcastForwardFunc2ArgVoid
2-argument forwarding function class, void return
Definition: broadcastdevice.cpp:252
XsVersion
A class to store version information.
Definition: xsversion.h:95
BroadcastForwardFunc1ArgVoid::BroadcastForwardFunc1ArgVoid
BroadcastForwardFunc1ArgVoid(BroadcastDevice *bc, FuncType func, Arg1 arg1)
Definition: broadcastdevice.cpp:238
XsDevice::startRecording
virtual bool startRecording()
Start recording incoming data.
Definition: xsdevice_def.cpp:2171
XsControl::updateRecordingState
void updateRecordingState()
BroadcastForwardFunc1ArgVoid::m_arg1
Arg1 m_arg1
Definition: broadcastdevice.cpp:247
BroadcastDevice::setXdaFilterProfile
bool setXdaFilterProfile(int profileType) override
Sets the filter profile to use for computing orientations on the host PC.
Definition: broadcastdevice.cpp:469
BroadcastForwardFunc1ArgVoid::m_func
FuncType m_func
Definition: broadcastdevice.cpp:246
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
broadcastdevice.h
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
XsDeviceId
Contains an Xsens device ID and provides operations for determining the type of device.
Definition: xsdeviceid.h:192
BroadcastDevice::setOnboardFilterProfile
bool setOnboardFilterProfile(int profileType) override
Sets the filter profile to use for computing orientations on the device.
Definition: broadcastdevice.cpp:479
XsDevice::closeLogFile
virtual bool closeLogFile()
Close the log file.
Definition: xsdevice_def.cpp:2150
BroadcastForwardFunc0ArgVoid::BroadcastForwardFunc0ArgVoid
BroadcastForwardFunc0ArgVoid(BroadcastDevice *bc, FuncType func)
Definition: broadcastdevice.cpp:221
BroadcastDevice::m_control
XsControl * m_control
Definition: broadcastdevice.h:124
BroadcastForwardFunc3Arg::m_arg1
Arg1 m_arg1
Definition: broadcastdevice.cpp:211
XsDevice::updateCachedDeviceInformation
virtual bool updateCachedDeviceInformation()
Updates the cached device information for all devices connected to this port.
Definition: xsdevice_def.cpp:3254
ForwardConstFunc::call
virtual bool call(XsDevice *device)
Definition: broadcastdevice.cpp:122
BroadcastForwardFunc2Arg::m_func
FuncType m_func
Definition: broadcastdevice.cpp:192
xssyncsetting.h
BroadcastForwardFunc::m_broadcaster
BroadcastDevice *const m_broadcaster
Definition: broadcastdevice.cpp:112
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
XsDevice::requestBatteryLevel
virtual bool requestBatteryLevel()
Request the battery level from the device.
Definition: xsdevice_def.cpp:2973
BroadcastForwardFunc3Arg::m_arg2
Arg2 m_arg2
Definition: broadcastdevice.cpp:212
ForwardConstFunc1Arg::m_arg1
Arg1 m_arg1
Definition: broadcastdevice.cpp:144
XsDevice::abortFlushing
virtual bool abortFlushing()
Abort the wireless flushing operation and finalize the recording.
Definition: xsdevice_def.cpp:3537
JLDEBUGG
#define JLDEBUGG(msg)
Definition: journaller.h:280
BroadcastDevice::initialize
bool initialize() override
required function to prevent pure-virtualness
Definition: broadcastdevice.cpp:293
XsDevice::gotoMeasurement
virtual bool gotoMeasurement()
Put this device in measurement mode.
Definition: xsdevice_def.cpp:960
BroadcastDevice::startRecording
bool startRecording() override
Start recording data.
Definition: broadcastdevice.cpp:327
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.
BroadcastDevice::loadLogFile
bool loadLogFile() override
Load a complete logfile.
Definition: broadcastdevice.cpp:352
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
BroadcastDevice::setInitialPositionLLA
bool setInitialPositionLLA(const XsVector &lla) override
Sets the 'Latitude Longitude Altitude' setting of the device to the given vector.
Definition: broadcastdevice.cpp:499
BroadcastDevice::setLocationId
bool setLocationId(int id) override
Set the location ID of the device.
Definition: broadcastdevice.cpp:434
XsDevice::isMeasuring
virtual bool isMeasuring() const
Returns true if the device is currently in a measuring state.
Definition: xsdevice_def.cpp:1741
BroadcastDevice::gotoMeasurement
bool gotoMeasurement() override
Put this device in measurement mode.
Definition: broadcastdevice.cpp:414
ForwardConstFunc1Arg::call
virtual bool call(XsDevice *device)
Definition: broadcastdevice.cpp:138
BroadcastForwardFunc1Arg::call
virtual bool call(XsDevice *device)
Definition: broadcastdevice.cpp:170
BroadcastForwardFunc2ArgVoid::m_func
FuncType m_func
Definition: broadcastdevice.cpp:264
BroadcastForwardFunc0Arg::call
virtual bool call(XsDevice *device)
Definition: broadcastdevice.cpp:154
BroadcastDevice::~BroadcastDevice
~BroadcastDevice() override
Destructor, no special actions taken.
Definition: broadcastdevice.cpp:279
ForwardConstFunc::ForwardConstFunc
ForwardConstFunc(BroadcastDevice *bc, FuncType func)
Definition: broadcastdevice.cpp:120
BroadcastForwardFunc1Arg
1-argument forwarding function class
Definition: broadcastdevice.cpp:164
XsString
A 0-terminated managed string of characters.
XsDevice
Definition: xsdevice_def.h:164
BroadcastForwardFunc2ArgVoid::BroadcastForwardFunc2ArgVoid
BroadcastForwardFunc2ArgVoid(BroadcastDevice *bc, FuncType func, Arg1 arg1, Arg2 arg2)
Definition: broadcastdevice.cpp:256
BroadcastForwardFunc2ArgVoid::m_arg1
Arg1 m_arg1
Definition: broadcastdevice.cpp:265
BroadcastForwardFunc0Arg
0-argument forwarding function class
Definition: broadcastdevice.cpp:148
xsens
Definition: threading.cpp:78
BroadcastDevice::productCode
XsString productCode() const override
required function to prevent pure-virtualness
Definition: broadcastdevice.cpp:304
BroadcastDevice::stopRecording
bool stopRecording() override
Stop recording data.
Definition: broadcastdevice.cpp:337
BroadcastForwardFunc3Arg::m_func
FuncType m_func
Definition: broadcastdevice.cpp:210
BroadcastDevice::children
std::vector< XsDevice * > children() const
Return the children of this device, actually returns the main devices in the XsControl object.
Definition: broadcastdevice.cpp:287
XsTimeStamp
This class contains method to set, retrieve and compare timestamps.
Definition: xstimestamp.h:115
BroadcastForwardFunc3Arg
3-argument forwarding function class
Definition: broadcastdevice.cpp:199
BroadcastDevice::setObjectAlignment
bool setObjectAlignment(const XsMatrix &matrix) override
Sets the object alignment of a device to the given matrix.
Definition: broadcastdevice.cpp:320
BroadcastDevice::setOptions
void setOptions(XsOption enable, XsOption disable) override
Enable and disable processing options.
Definition: broadcastdevice.cpp:504
XsDevice::batteryLevelTime
virtual XsTimeStamp batteryLevelTime()
Requests the time the battery level was last updated.
Definition: xsdevice_def.cpp:2981
XsDevice::setLocationId
virtual bool setLocationId(int id)
Set the location ID of the device.
Definition: xsdevice_def.cpp:2506


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