xscallbackplainc.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 XSCALLBACKPLAINC_H
66 #define XSCALLBACKPLAINC_H
67 
68 #include <xstypes/pstdint.h>
69 #include <xstypes/xsresultvalue.h>
70 #include <xstypes/xsinforequest.h>
71 #include "xsdevicestate.h"
72 #include "xsconnectivitystate.h"
73 #include "xsprotocoltype.h"
74 
75 #ifndef __cplusplus
76  #define XSCALLBACK_INITIALIZER { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }
77 #endif
78 
79 struct XsDevice;
80 struct XsDevicePtrArray;
81 struct XsDataPacket;
83 struct XsString;
84 struct XsMessage;
85 struct XsByteArray;
86 
99 typedef struct XsCallbackPlainC
100 {
110  void (*m_onDeviceStateChanged)(struct XsCallbackPlainC* thisPtr, struct XsDevice* dev, XsDeviceState newState, XsDeviceState oldState);
111 
119  void (*m_onLiveDataAvailable)(struct XsCallbackPlainC* thisPtr, struct XsDevice* dev, const struct XsDataPacket* packet);
120 
127  void (*m_onMissedPackets)(struct XsCallbackPlainC* thisPtr, struct XsDevice* dev, int count, int first, int last);
128 
132  void (*m_onWakeupReceived)(struct XsCallbackPlainC* thisPtr, struct XsDevice* dev);
133 
140  void (*m_onProgressUpdated)(struct XsCallbackPlainC* thisPtr, struct XsDevice* dev, int current, int total, const struct XsString* identifier);
141 
148  int (*m_onWriteMessageToLogFile)(struct XsCallbackPlainC* thisPtr, struct XsDevice* dev, const struct XsMessage* message);
149 
157  void (*m_onBufferedDataAvailable)(struct XsCallbackPlainC* thisPtr, struct XsDevice* dev, const struct XsDataPacket* packet);
158 
163  void (*m_onConnectivityChanged)(struct XsCallbackPlainC* thisPtr, struct XsDevice* dev, XsConnectivityState newState);
164 
172  void (*m_onInfoResponse)(struct XsCallbackPlainC* thisPtr, struct XsDevice* dev, XsInfoRequest request);
173 
178  void (*m_onError)(struct XsCallbackPlainC* thisPtr, struct XsDevice* dev, XsResultValue error);
179 
184  void (*m_onNonDataMessage)(struct XsCallbackPlainC* thisPtr, struct XsDevice* dev, struct XsMessage const* message);
185 
192  void(*m_onMessageDetected)(struct XsCallbackPlainC* thisPtr, struct XsDevice* dev, XsProtocolType type, struct XsByteArray const* rawMessage);
193 
198  void (*m_onMessageReceivedFromDevice)(struct XsCallbackPlainC* thisPtr, struct XsDevice* dev, struct XsMessage const* message);
199 
204  void (*m_onMessageSentToDevice)(struct XsCallbackPlainC* thisPtr, struct XsDevice* dev, struct XsMessage const* message);
205 
213  void (*m_onAllLiveDataAvailable)(struct XsCallbackPlainC* thisPtr, struct XsDevicePtrArray* devs, const struct XsDataPacketPtrArray* packets);
214 
222  void (*m_onAllBufferedDataAvailable)(struct XsCallbackPlainC* thisPtr, struct XsDevicePtrArray* devs, const struct XsDataPacketPtrArray* packets);
223 
230  void (*m_onDataUnavailable)(struct XsCallbackPlainC* thisPtr, struct XsDevice* dev, int64_t packetId);
231 
238  void (*m_onDataAvailable)(struct XsCallbackPlainC* thisPtr, struct XsDevice* dev, const struct XsDataPacket* packet);
239 
246  void (*m_onAllDataAvailable)(struct XsCallbackPlainC* thisPtr, struct XsDevicePtrArray* devs, const struct XsDataPacketPtrArray* packets);
247 
254  void (*m_onRecordedDataAvailable)(struct XsCallbackPlainC* thisPtr, struct XsDevice* dev, const struct XsDataPacket* packet);
255 
262  void (*m_onAllRecordedDataAvailable)(struct XsCallbackPlainC* thisPtr, struct XsDevicePtrArray* devs, const struct XsDataPacketPtrArray* packets);
263 
268  void (*m_onTransmissionRequest)(struct XsCallbackPlainC* thisPtr, int channelId, const struct XsByteArray* data);
269 
274  void (*m_onRestoreCommunication)(struct XsCallbackPlainC* thisPtr, const struct XsString* portName, XsResultValue result);
275 
277 #ifdef __cplusplus
278  // Make sure that this struct is not used in C++ (except as base class for XsCallback)
279  friend class XsCallback;
280 protected:
282  : m_onDeviceStateChanged(nullptr)
283  , m_onLiveDataAvailable(nullptr)
284  , m_onMissedPackets(nullptr)
285  , m_onWakeupReceived(nullptr)
286  , m_onProgressUpdated(nullptr)
287  , m_onWriteMessageToLogFile(nullptr)
288  , m_onBufferedDataAvailable(nullptr)
289  , m_onConnectivityChanged(nullptr)
290  , m_onInfoResponse(nullptr)
291  , m_onError(nullptr)
292  , m_onNonDataMessage(nullptr)
293  , m_onMessageDetected(nullptr)
295  , m_onMessageSentToDevice(nullptr)
296  , m_onAllLiveDataAvailable(nullptr)
298  , m_onDataUnavailable(nullptr)
299  , m_onDataAvailable(nullptr)
300  , m_onAllDataAvailable(nullptr)
301  , m_onRecordedDataAvailable(nullptr)
303  , m_onTransmissionRequest(nullptr)
304  , m_onRestoreCommunication(nullptr)
305  {}
306  ~XsCallbackPlainC() throw() {}
307 private:
309  XsCallbackPlainC& operator = (XsCallbackPlainC const&);
310 #endif
311 
313 
314 #endif
XsCallbackPlainC::m_onProgressUpdated
void(* m_onProgressUpdated)(struct XsCallbackPlainC *thisPtr, struct XsDevice *dev, int current, int total, const struct XsString *identifier)
Called when a long-duration operation has made some progress or has completed. Examples include loadL...
Definition: xscallbackplainc.h:140
XsDataPacketPtrArray
A list of XsDataPacketPtr values.
XsCallbackPlainC::m_onError
void(* m_onError)(struct XsCallbackPlainC *thisPtr, struct XsDevice *dev, XsResultValue error)
Called when an error has occurred while handling incoming data.
Definition: xscallbackplainc.h:178
XsByteArray
A list of uint8_t values.
XsCallbackPlainC
Structure that contains callback functions for the Xsens Device API.
Definition: xscallbackplainc.h:99
XsCallbackPlainC::m_onDataUnavailable
void(* m_onDataUnavailable)(struct XsCallbackPlainC *thisPtr, struct XsDevice *dev, int64_t packetId)
Called when XDA detects that data is forever unavailable.
Definition: xscallbackplainc.h:230
XsCallbackPlainC::m_onLiveDataAvailable
void(* m_onLiveDataAvailable)(struct XsCallbackPlainC *thisPtr, struct XsDevice *dev, const struct XsDataPacket *packet)
Called when new data has been received from a device or read from a file. When processing on PC is en...
Definition: xscallbackplainc.h:119
XsCallbackPlainC::m_onMessageSentToDevice
void(* m_onMessageSentToDevice)(struct XsCallbackPlainC *thisPtr, struct XsDevice *dev, struct XsMessage const *message)
Called just after a message is sent to the device.
Definition: xscallbackplainc.h:204
XsDataPacket
Contains an interpreted data message. The class provides easy access to the contained data through it...
Definition: xsdatapacket.h:301
XsCallbackPlainC::m_onWakeupReceived
void(* m_onWakeupReceived)(struct XsCallbackPlainC *thisPtr, struct XsDevice *dev)
Called when a wakeup message has been received from a device. This indicates that the device has just...
Definition: xscallbackplainc.h:132
XsCallbackPlainC::m_onMessageDetected
void(* m_onMessageDetected)(struct XsCallbackPlainC *thisPtr, struct XsDevice *dev, XsProtocolType type, struct XsByteArray const *rawMessage)
Called just after a message is detected in raw data from the device.
Definition: xscallbackplainc.h:192
XsCallbackPlainC::m_onAllDataAvailable
void(* m_onAllDataAvailable)(struct XsCallbackPlainC *thisPtr, struct XsDevicePtrArray *devs, const struct XsDataPacketPtrArray *packets)
Called when new data has been received for devices connected to the same main device....
Definition: xscallbackplainc.h:246
data
data
XsCallbackPlainC::m_onDataAvailable
void(* m_onDataAvailable)(struct XsCallbackPlainC *thisPtr, struct XsDevice *dev, const struct XsDataPacket *packet)
Called when new data has been received from a device or read from a file. When processing on PC is en...
Definition: xscallbackplainc.h:238
XsCallbackPlainC::m_onWriteMessageToLogFile
int(* m_onWriteMessageToLogFile)(struct XsCallbackPlainC *thisPtr, struct XsDevice *dev, const struct XsMessage *message)
Called when XDA has a message that could be written to a log file.
Definition: xscallbackplainc.h:148
XsResultValue
XsResultValue
Xsens result values.
Definition: xsresultvalue.h:82
XsCallbackPlainC::m_onMissedPackets
void(* m_onMissedPackets)(struct XsCallbackPlainC *thisPtr, struct XsDevice *dev, int count, int first, int last)
Called when XDA detects that packets have been missed.
Definition: xscallbackplainc.h:127
xsinforequest.h
XsCallbackPlainC::m_onDeviceStateChanged
void(* m_onDeviceStateChanged)(struct XsCallbackPlainC *thisPtr, struct XsDevice *dev, XsDeviceState newState, XsDeviceState oldState)
Called when a device's state has changed (ie config mode, measurement mode, recording mode)
Definition: xscallbackplainc.h:110
xsprotocoltype.h
XsCallbackPlainC::m_onBufferedDataAvailable
void(* m_onBufferedDataAvailable)(struct XsCallbackPlainC *thisPtr, struct XsDevice *dev, const struct XsDataPacket *packet)
Called when XDA has a data packet that could be written to a log file.
Definition: xscallbackplainc.h:157
XsCallbackPlainC::m_onRestoreCommunication
void(* m_onRestoreCommunication)(struct XsCallbackPlainC *thisPtr, const struct XsString *portName, XsResultValue result)
Called when restore communication is completed, stopped or an error occurred.
Definition: xscallbackplainc.h:274
XsCallbackPlainC::m_onConnectivityChanged
void(* m_onConnectivityChanged)(struct XsCallbackPlainC *thisPtr, struct XsDevice *dev, XsConnectivityState newState)
Called when XDA has detected a change in the connectivity state of a device.
Definition: xscallbackplainc.h:163
XsInfoRequest
XsInfoRequest
Information request identifiers.
Definition: xsinforequest.h:77
XsCallbackPlainC::m_onMessageReceivedFromDevice
void(* m_onMessageReceivedFromDevice)(struct XsCallbackPlainC *thisPtr, struct XsDevice *dev, struct XsMessage const *message)
Called just after a valid message (after parsing) is received from the device.
Definition: xscallbackplainc.h:198
XsMessage
Structure for storing a single message.
Definition: xsmessage.h:202
XsCallbackPlainC::m_onAllLiveDataAvailable
void(* m_onAllLiveDataAvailable)(struct XsCallbackPlainC *thisPtr, struct XsDevicePtrArray *devs, const struct XsDataPacketPtrArray *packets)
Called when new data has been received for devices connected to the same main device....
Definition: xscallbackplainc.h:213
XsDevicePtrArray
A list of XsDevicePtr values.
pstdint.h
XsCallbackPlainC::m_onRecordedDataAvailable
void(* m_onRecordedDataAvailable)(struct XsCallbackPlainC *thisPtr, struct XsDevice *dev, const struct XsDataPacket *packet)
Called when new data has been received from a device in a recording state or read from a file....
Definition: xscallbackplainc.h:254
XsCallbackPlainC::m_onAllRecordedDataAvailable
void(* m_onAllRecordedDataAvailable)(struct XsCallbackPlainC *thisPtr, struct XsDevicePtrArray *devs, const struct XsDataPacketPtrArray *packets)
Called when new data has been received for devices connected to the same main device in a recording s...
Definition: xscallbackplainc.h:262
XsCallbackPlainC::m_onNonDataMessage
void(* m_onNonDataMessage)(struct XsCallbackPlainC *thisPtr, struct XsDevice *dev, struct XsMessage const *message)
Called when a non data, non reply message has been received.
Definition: xscallbackplainc.h:184
XsConnectivityState
XsConnectivityState
XsDevice connectivity state identifiers.
Definition: xsconnectivitystate.h:78
XsProtocolType
XsProtocolType
Protocol types (XsDevice::enableProtocol())
Definition: xsprotocoltype.h:72
XsDeviceState
XsDeviceState
XsDevice state identifiers.
Definition: xsdevicestate.h:77
XsCallbackPlainC::m_onAllBufferedDataAvailable
void(* m_onAllBufferedDataAvailable)(struct XsCallbackPlainC *thisPtr, struct XsDevicePtrArray *devs, const struct XsDataPacketPtrArray *packets)
Called when new data has been received for devices connected to the same main device....
Definition: xscallbackplainc.h:222
xsresultvalue.h
XsCallbackPlainC::m_onInfoResponse
void(* m_onInfoResponse)(struct XsCallbackPlainC *thisPtr, struct XsDevice *dev, XsInfoRequest request)
Called when an information request has resulted in a response.
Definition: xscallbackplainc.h:172
XsString
A 0-terminated managed string of characters.
XsDevice
Definition: xsdevice_def.h:164
xsdevicestate.h
XsCallbackPlainC
struct XsCallbackPlainC XsCallbackPlainC
Structure that contains callback functions for the Xsens Device API.
xsconnectivitystate.h
XsCallbackPlainC::m_onTransmissionRequest
void(* m_onTransmissionRequest)(struct XsCallbackPlainC *thisPtr, int channelId, const struct XsByteArray *data)
Called when XDA needs to send raw data to a device connected using a custom communication channel.
Definition: xscallbackplainc.h:268


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