Go to the documentation of this file.
70 using namespace xsens;
94 LockReadWrite portLock(&m_broadcaster->m_control->m_portMutex);
97 std::vector<XsDevice*>& ch = m_broadcaster->m_control->m_deviceList;
101 for (std::vector<XsDevice*>::iterator it = ch.begin(); it != ch.end(); ++it)
106 m_broadcaster->m_control->m_lastResult = res;
124 return (device->*m_func)();
131 template <
typename Arg1>
140 return (device->*m_func)(m_arg1);
156 return (device->*m_func)();
163 template <
typename Arg1>
172 return (device->*m_func)(m_arg1);
180 template <
typename Arg1,
typename Arg2>
189 return (device->*m_func)(m_arg1, m_arg2);
198 template <
typename Arg1,
typename Arg2,
typename Arg3>
202 typedef bool (
XsDevice::*FuncType)(Arg1, Arg2, Arg3);
207 return (device->*m_func)(m_arg1, m_arg2, m_arg3);
233 template <
typename Arg1>
242 (device->*m_func)(m_arg1);
251 template <
typename Arg1,
typename Arg2>
260 (device->*m_func)(m_arg1, m_arg2);
273 , m_control(control_)
301 return std::vector<int>();
405 for (std::vector<XsDevice*>::reverse_iterator it = ch.rbegin(); it != ch.rend(); ++it)
407 if (!(*it)->gotoConfig())
2-argument forwarding function class
ForwardConstFunc1Arg(BroadcastDevice *bc, FuncType func, Arg1 arg1)
virtual bool call(XsDevice *device)
std::vector< XsDevice * > m_deviceList
This list contains device-information and cached data per device.
A class that represents a matrix of real numbers.
void setTerminationPrepared(bool prepared) NOEXCEPT
Set the "termination prepared" state to prepared.
1-argument forwarding function class, void return
bool setSerialBaudRate(XsBaudRate baudrate) override
Change the serial baudrate to baudrate.
A class that represents a vector of real numbers.
bool call(const std::string &service_name, MReq &req, MRes &res)
bool setSyncSettings(const XsSyncSettingArray &s) override
Set the synchronization settings of the device.
virtual bool storeFilterState()
Store orientation filter state in the device.
bool gotoConfig() override
Put the device in config mode.
virtual ~BroadcastForwardFunc()
0-argument const forwarding function class
virtual bool isReadingFromFile() const
Returns true if the device is reading from a file.
BroadcastForwardFunc3Arg(BroadcastDevice *bc, FuncType func, Arg1 arg1, Arg2 arg2, Arg3 arg3)
virtual bool setInitialPositionLLA(const XsVector &lla)
Sets the 'Latitude Longitude Altitude' setting of the device to the given vector.
virtual bool setSerialBaudRate(XsBaudRate baudrate)
Change the serial baudrate to baudrate.
bool closeLogFile() override
Close the log file.
bool lock(bool write)
Make sure that the lock has exactly the given lock state.
std::vector< int > supportedUpdateRates(XsDataIdentifier dataType) const override
required function to prevent pure-virtualness
bool setTransportMode(bool transportModeEnabled) override
Enable or disable the transport mode for the device.
virtual bool setXdaFilterProfile(int profileType)
Sets the filter profile to use for computing orientations on the host PC.
virtual bool setSyncSettings(const XsSyncSettingArray &settingList)
Set the synchronization settings of the device.
bool isMeasuring() const override
Returns true if the device is currently in a measuring state.
virtual bool call(XsDevice *device)
struct XsVersion XsVersion
BroadcastForwardFunc0Arg(BroadcastDevice *bc, FuncType func)
A readers-writer lock class.
bool storeFilterState() override
Store orientation filter state in the device.
High level Motion Tracker (MT) management class.
bool isReadingFromFile() const override final
Returns true if the device is reading from a file.
Intimately entangled class with XsControl that allows broadcasting to all main devices.
virtual void flushInputBuffers()
Clear the inbound data buffers of the device.
@ XRV_OK
0: Operation was performed successfully
void flushInputBuffers() override
Clear the inbound data buffers of the device.
bool abortFlushing() override
Abort the wireless flushing operation and finalize the recording.
bool resetLogFileReadPosition() override
Set the read position of the open log file to the start of the file.
virtual bool stopRecording()
Stop recording incoming data.
bool resetOrientation(XsResetMethod resetMethod) override
Perform an orientation reset on the device using the given resetMethod.
virtual bool setNoRotation(uint16_t duration)
Set the no rotation period to duration.
XsOption
Xda options, used to control the kind of data processing done by XDA.
bool setNoRotation(uint16_t duration) override
Set the no rotation period to duration.
XsResultValue
Xsens result values.
bool requestBatteryLevel() override
Request the battery level from the device.
bool setHeadingOffset(double offset) override
Set the 'heading offset' setting of the device.
XsVersion hardwareVersion() const override
required function to prevent pure-virtualness
bool updateCachedDeviceInformation() override
Updates the cached device information for all devices connected to this port.
XsDataIdentifier
Defines the data identifiers.
virtual bool loadLogFile()
Load a complete logfile.
enum XsBaudRate XsBaudRate
Communication speed.
Pure virtual base class for N-argument specific function forwarding.
@ XRV_NOFILEORPORTOPEN
289: No file or serial port opened for reading/writing
virtual bool call(XsDevice *device)
BroadcastForwardFunc2Arg(BroadcastDevice *bc, FuncType func, Arg1 arg1, Arg2 arg2)
LastResultManager m_lastResult
The last result of an operation.
XsTimeStamp batteryLevelTime() override
Requests the time the battery level was last updated.
BroadcastDevice(XsControl *control)
Constructor, sets up the XsControl reference.
1-argument const forwarding function class
0-argument forwarding function class, void return
virtual bool setHeadingOffset(double offset)
Set the 'heading offset' setting of the device.
virtual bool restoreFactoryDefaults()
Restore the device to its factory default settings.
virtual bool call(XsDevice *device)
bool setGravityMagnitude(double mag) override
Sets the 'Gravity Magnitude' of the device to the given value mag.
BroadcastForwardFunc(BroadcastDevice *bc)
bool isRecording() const override
Returns true if the device is currently in a recording state.
BroadcastForwardFunc1Arg(BroadcastDevice *bc, FuncType func, Arg1 arg1)
virtual bool call(XsDevice *device)
bool restoreFactoryDefaults() override
Restore the device to its factory default settings.
virtual bool setOnboardFilterProfile(int profileType)
Sets the filter profile to use for computing orientations on the device.
XsResetMethod
Orientation reset type.
2-argument forwarding function class, void return
A class to store version information.
BroadcastForwardFunc1ArgVoid(BroadcastDevice *bc, FuncType func, Arg1 arg1)
virtual bool startRecording()
Start recording incoming data.
void updateRecordingState()
bool setXdaFilterProfile(int profileType) override
Sets the filter profile to use for computing orientations on the host PC.
virtual bool isRecording() const
Returns true if the device is currently in a recording state.
virtual bool reset()
Reset the device.
virtual bool setObjectAlignment(const XsMatrix &matrix)
Sets the object alignment of the device to the given matrix.
Contains an Xsens device ID and provides operations for determining the type of device.
bool setOnboardFilterProfile(int profileType) override
Sets the filter profile to use for computing orientations on the device.
virtual bool closeLogFile()
Close the log file.
BroadcastForwardFunc0ArgVoid(BroadcastDevice *bc, FuncType func)
virtual bool updateCachedDeviceInformation()
Updates the cached device information for all devices connected to this port.
virtual bool call(XsDevice *device)
BroadcastDevice *const m_broadcaster
virtual bool resetLogFileReadPosition()
Set the read position of the open log file to the start of the file.
virtual bool requestBatteryLevel()
Request the battery level from the device.
virtual bool abortFlushing()
Abort the wireless flushing operation and finalize the recording.
bool initialize() override
required function to prevent pure-virtualness
virtual bool gotoMeasurement()
Put this device in measurement mode.
bool startRecording() override
Start recording data.
virtual bool setTransportMode(bool transportModeEnabled)
Enable or disable the transport mode for the device.
A list of XsSyncSetting values.
bool loadLogFile() override
Load a complete logfile.
virtual bool resetOrientation(XsResetMethod resetmethod)
Perform an orientation reset on the device using the given resetMethod.
virtual void setOptions(XsOption enable, XsOption disable)
Enable and disable processing options.
virtual bool setGravityMagnitude(double mag)
Sets the 'Gravity Magnitude' of the device to the given value mag.
bool setInitialPositionLLA(const XsVector &lla) override
Sets the 'Latitude Longitude Altitude' setting of the device to the given vector.
bool setLocationId(int id) override
Set the location ID of the device.
virtual bool isMeasuring() const
Returns true if the device is currently in a measuring state.
bool gotoMeasurement() override
Put this device in measurement mode.
virtual bool call(XsDevice *device)
virtual bool call(XsDevice *device)
virtual bool call(XsDevice *device)
~BroadcastDevice() override
Destructor, no special actions taken.
ForwardConstFunc(BroadcastDevice *bc, FuncType func)
1-argument forwarding function class
A 0-terminated managed string of characters.
BroadcastForwardFunc2ArgVoid(BroadcastDevice *bc, FuncType func, Arg1 arg1, Arg2 arg2)
0-argument forwarding function class
XsString productCode() const override
required function to prevent pure-virtualness
bool stopRecording() override
Stop recording data.
std::vector< XsDevice * > children() const
Return the children of this device, actually returns the main devices in the XsControl object.
This class contains method to set, retrieve and compare timestamps.
3-argument forwarding function class
bool setObjectAlignment(const XsMatrix &matrix) override
Sets the object alignment of a device to the given matrix.
void setOptions(XsOption enable, XsOption disable) override
Enable and disable processing options.
virtual XsTimeStamp batteryLevelTime()
Requests the time the battery level was last updated.
virtual bool setLocationId(int id)
Set the location ID of the device.