broadcastdevice.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 BROADCASTDEVICE_H
66 #define BROADCASTDEVICE_H
67 
68 #include "xsdevice_def.h"
69 struct XsControl;
70 
71 class BroadcastDevice : public XsDevice
72 {
73 public:
74  explicit BroadcastDevice(XsControl* control);
75  ~BroadcastDevice() override;
76 
77  std::vector<XsDevice*> children() const;
78 
79  bool initialize() override;
80 
81  std::vector<int> supportedUpdateRates(XsDataIdentifier dataType) const override;
82  XsString productCode() const override;
83  XsVersion hardwareVersion() const override;
84 
85  bool startRecording() override;
86  bool stopRecording() override;
87 
88  bool isMeasuring() const override;
89  bool isRecording() const override;
90  bool isReadingFromFile() const override final;
91 
92  bool setSerialBaudRate(XsBaudRate baudrate) override;
93  bool setSyncSettings(const XsSyncSettingArray& s) override;
94  bool gotoMeasurement() override;
95  bool gotoConfig() override;
96  bool resetOrientation(XsResetMethod resetMethod) override;
97  bool restoreFactoryDefaults() override;
98  bool reset(bool skipDeviceIdCheck = false) override;
99  bool loadLogFile() override;
100  bool closeLogFile() override;
101  //bool gotoOperational() override;
102  bool abortFlushing() override;
103  bool resetLogFileReadPosition() override;
104  bool updateCachedDeviceInformation() override;
105  bool setHeadingOffset(double offset) override;
106  bool setLocationId(int id) override;
107  bool setObjectAlignment(const XsMatrix& matrix) override;
108  bool setGravityMagnitude(double mag) override;
109  bool setXdaFilterProfile(int profileType) override;
110  bool setXdaFilterProfile(XsString const& profileType) override;
111  bool setOnboardFilterProfile(int profileType) override;
112  bool setOnboardFilterProfile(XsString const& profileType) override;
113  bool setNoRotation(uint16_t duration) override;
114  bool setInitialPositionLLA(const XsVector& lla) override;
115  bool storeFilterState() override;
116  bool requestBatteryLevel() override;
117  XsTimeStamp batteryLevelTime() override;
118  bool setTransportMode(bool transportModeEnabled) override;
119  void setOptions(XsOption enable, XsOption disable) override;
120  void flushInputBuffers() override;
121 
122 private:
123  friend class BroadcastForwardFunc;
125 };
126 
127 #endif
XsMatrix
A class that represents a matrix of real numbers.
Definition: xsmatrix.h:107
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
BroadcastDevice::setSyncSettings
bool setSyncSettings(const XsSyncSettingArray &s) override
Set the synchronization settings of the device.
Definition: broadcastdevice.cpp:424
BroadcastDevice::gotoConfig
bool gotoConfig() override
Put the device in config mode.
Definition: broadcastdevice.cpp:397
BroadcastDevice::closeLogFile
bool closeLogFile() override
Close the log file.
Definition: broadcastdevice.cpp:357
s
XmlRpcServer s
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
BroadcastDevice::isMeasuring
bool isMeasuring() const override
Returns true if the device is currently in a measuring state.
Definition: broadcastdevice.cpp:382
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
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
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
BroadcastDevice::resetOrientation
bool resetOrientation(XsResetMethod resetMethod) override
Perform an orientation reset on the device using the given resetMethod.
Definition: broadcastdevice.cpp:439
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
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
BroadcastDevice::updateCachedDeviceInformation
bool updateCachedDeviceInformation() override
Updates the cached device information for all devices connected to this port.
Definition: broadcastdevice.cpp:464
XsDataIdentifier
XsDataIdentifier
Defines the data identifiers.
Definition: xsdataidentifier.h:84
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
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
BroadcastDevice::setGravityMagnitude
bool setGravityMagnitude(double mag) override
Sets the 'Gravity Magnitude' of the device to the given value mag.
Definition: broadcastdevice.cpp:489
BroadcastDevice::isRecording
bool isRecording() const override
Returns true if the device is currently in a recording state.
Definition: broadcastdevice.cpp:387
xsdevice_def.h
BroadcastDevice::restoreFactoryDefaults
bool restoreFactoryDefaults() override
Restore the device to its factory default settings.
Definition: broadcastdevice.cpp:444
XsResetMethod
XsResetMethod
Orientation reset type.
Definition: xsresetmethod.h:74
XsVersion
A class to store version information.
Definition: xsversion.h:95
BroadcastDevice::setXdaFilterProfile
bool setXdaFilterProfile(int profileType) override
Sets the filter profile to use for computing orientations on the host PC.
Definition: broadcastdevice.cpp:469
XsDevice::reset
virtual bool reset()
Reset the device.
Definition: xsdevice_def.cpp:1971
BroadcastDevice::setOnboardFilterProfile
bool setOnboardFilterProfile(int profileType) override
Sets the filter profile to use for computing orientations on the device.
Definition: broadcastdevice.cpp:479
BroadcastDevice::m_control
XsControl * m_control
Definition: broadcastdevice.h:124
BroadcastDevice::initialize
bool initialize() override
required function to prevent pure-virtualness
Definition: broadcastdevice.cpp:293
BroadcastDevice::startRecording
bool startRecording() override
Start recording data.
Definition: broadcastdevice.cpp:327
XsSyncSettingArray
A list of XsSyncSetting values.
BroadcastDevice::loadLogFile
bool loadLogFile() override
Load a complete logfile.
Definition: broadcastdevice.cpp:352
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
BroadcastDevice::gotoMeasurement
bool gotoMeasurement() override
Put this device in measurement mode.
Definition: broadcastdevice.cpp:414
BroadcastDevice::~BroadcastDevice
~BroadcastDevice() override
Destructor, no special actions taken.
Definition: broadcastdevice.cpp:279
XsString
A 0-terminated managed string of characters.
XsDevice
Definition: xsdevice_def.h:164
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
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
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


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